From fc82ed0c693635ccfaeee4f060b93b1a1c083acb Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Wed, 20 Mar 2013 13:21:00 +0100 Subject: [PATCH 001/102] Skeleton code. --- apps/drivers/ets/Makefile | 42 ++ apps/drivers/ets/ets_airspeed.cpp | 784 ++++++++++++++++++++++++++++++ 2 files changed, 826 insertions(+) create mode 100644 apps/drivers/ets/Makefile create mode 100644 apps/drivers/ets/ets_airspeed.cpp diff --git a/apps/drivers/ets/Makefile b/apps/drivers/ets/Makefile new file mode 100644 index 0000000000..9089d97af2 --- /dev/null +++ b/apps/drivers/ets/Makefile @@ -0,0 +1,42 @@ +############################################################################ +# +# Copyright (C) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Makefile to build the Eagle Tree Airspeed V3 driver. +# + +APPNAME = ets_airspeed +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/ets/ets_airspeed.cpp b/apps/drivers/ets/ets_airspeed.cpp new file mode 100644 index 0000000000..4ac707c3cb --- /dev/null +++ b/apps/drivers/ets/ets_airspeed.cpp @@ -0,0 +1,784 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file airspeed.cpp + * @author Simon Wilks + * + * Driver for the Eagle Tree Airspeed V3 connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include + +#include +#include + +#include + +#include +#include + + +/* Configuration Constants */ +#define ETS_BUS PX4_I2C_BUS_EXPANSION +#define ETS_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xEA */ + +/* ETS Registers addresses */ + +#define ETS_READ_CMD 0x07 /* Read the data */ + +#define ETS_CONVERSION_INTERVAL 60000 /* 60ms */ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + +#ifndef CONFIG_SCHED_WORKQUEUE +# error This requires CONFIG_SCHED_WORKQUEUE. +#endif + +class ETS : public device::I2C +{ +public: + ETS(int bus = ETS_BUS, int address = ETS_BASEADDR); + virtual ~ETS(); + + virtual int init(); + + virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + /** + * Diagnostics - print some basic information about the driver. + */ + void print_info(); + +protected: + virtual int probe(); + +private: + work_s _work; + unsigned _num_reports; + volatile unsigned _next_report; + volatile unsigned _oldest_report; + range_finder_report *_reports; + bool _sensor_ok; + int _measure_ticks; + bool _collect_phase; + + orb_advert_t _differential_pressure_topic; + + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; + + /** + * Test whether the device supported by the driver is present at a + * specific address. + * + * @param address The I2C bus address to probe. + * @return True if the device is present. + */ + int probe_address(uint8_t address); + + /** + * Initialise the automatic measurement state machine and start it. + * + * @note This function is called at open and error time. It might make sense + * to make it more aggressive about resetting the bus in case of errors. + */ + void start(); + + /** + * Stop the automatic measurement state machine. + */ + void stop(); + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + void cycle(); + int measure(); + int collect(); + /** + * Static trampoline from the workq context; because we don't have a + * generic workq wrapper yet. + * + * @param arg Instance pointer for the driver that is polling. + */ + static void cycle_trampoline(void *arg); + + +}; + +/* helper macro for handling report buffer indices */ +#define INCREMENT(_x, _lim) do { _x++; if (_x >= _lim) _x = 0; } while(0) + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int ETS_main(int argc, char *argv[]); + +ETS::ETS(int bus, int address) : + I2C("ETS", AIRSPEED_SENSOR_DEVICE_PATH, bus, address, 100000), + _num_reports(0), + _next_report(0), + _oldest_report(0), + _reports(nullptr), + _sensor_ok(false), + _measure_ticks(0), + _collect_phase(false), + _differential_pressure_topic(-1), + _sample_perf(perf_alloc(PC_ELAPSED, "ETS_read")), + _comms_errors(perf_alloc(PC_COUNT, "ETS_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "ETS_buffer_overflows")) +{ + // enable debug() calls + _debug_enabled = true; + + // work_cancel in the dtor will explode if we don't do this... + memset(&_work, 0, sizeof(_work)); +} + +ETS::~ETS() +{ + /* make sure we are truly inactive */ + stop(); + + /* free any existing reports */ + if (_reports != nullptr) + delete[] _reports; +} + +int +ETS::init() +{ + int ret = ERROR; + + /* do I2C init (and probe) first */ + if (I2C::init() != OK) + goto out; + + /* allocate basic report buffers */ + _num_reports = 2; + _reports = new struct range_finder_report[_num_reports]; + + if (_reports == nullptr) + goto out; + + _oldest_report = _next_report = 0; + + /* get a publish handle on the airspeed topic */ + memset(&_reports[0], 0, sizeof(_reports[0])); + _differential_pressure_topic = orb_advertise(ORB_ID(_differential_pressure), &_reports[0]); + + if (_differential_pressure_topic < 0) + debug("failed to create airspeed sensor object. Did you start uOrb?"); + + ret = OK; + /* sensor is ok, but we don't really know if it is within range */ + _sensor_ok = true; +out: + return ret; +} + +int +ETS::probe() +{ + return measure(); +} + +int +ETS::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + + case SENSORIOCSPOLLRATE: { + switch (arg) { + + /* switching to manual polling */ + case SENSOR_POLLRATE_MANUAL: + stop(); + _measure_ticks = 0; + return OK; + + /* external signalling (DRDY) not supported */ + case SENSOR_POLLRATE_EXTERNAL: + + /* zero would be bad */ + case 0: + return -EINVAL; + + /* set default/max polling rate */ + case SENSOR_POLLRATE_MAX: + case SENSOR_POLLRATE_DEFAULT: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* set interval for next measurement to minimum legal value */ + _measure_ticks = USEC2TICK(ETS_CONVERSION_INTERVAL); + + /* if we need to start the poll state machine, do it */ + if (want_start) + start(); + + return OK; + } + + /* adjust to a legal polling interval in Hz */ + default: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* convert hz to tick interval via microseconds */ + unsigned ticks = USEC2TICK(1000000 / arg); + + /* check against maximum rate */ + if (ticks < USEC2TICK(ETS_CONVERSION_INTERVAL)) + return -EINVAL; + + /* update interval for next measurement */ + _measure_ticks = ticks; + + /* if we need to start the poll state machine, do it */ + if (want_start) + start(); + + return OK; + } + } + } + + case SENSORIOCGPOLLRATE: + if (_measure_ticks == 0) + return SENSOR_POLLRATE_MANUAL; + + return (1000 / _measure_ticks); + + case SENSORIOCSQUEUEDEPTH: { + /* add one to account for the sentinel in the ring */ + arg++; + + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 2) || (arg > 100)) + return -EINVAL; + + /* allocate new buffer */ + struct range_finder_report *buf = new struct range_finder_report[arg]; + + if (nullptr == buf) + return -ENOMEM; + + /* reset the measurement state machine with the new buffer, free the old */ + stop(); + delete[] _reports; + _num_reports = arg; + _reports = buf; + start(); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _num_reports - 1; + + case SENSORIOCRESET: + /* XXX implement this */ + return -EINVAL; + + default: + /* give it to the superclass */ + return I2C::ioctl(filp, cmd, arg); + } +} + +ssize_t +ETS::read(struct file *filp, char *buffer, size_t buflen) +{ + unsigned count = buflen / sizeof(struct range_finder_report); + int ret = 0; + + /* buffer must be large enough */ + if (count < 1) + return -ENOSPC; + + /* if automatic measurement is enabled */ + if (_measure_ticks > 0) { + + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the workq thread while we are doing this; + * we are careful to avoid racing with them. + */ + while (count--) { + if (_oldest_report != _next_report) { + memcpy(buffer, _reports + _oldest_report, sizeof(*_reports)); + ret += sizeof(_reports[0]); + INCREMENT(_oldest_report, _num_reports); + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement - run one conversion */ + /* XXX really it'd be nice to lock against other readers here */ + do { + _oldest_report = _next_report = 0; + + /* trigger a measurement */ + if (OK != measure()) { + ret = -EIO; + break; + } + + /* wait for it to complete */ + usleep(ETS_CONVERSION_INTERVAL); + + /* run the collection phase */ + if (OK != collect()) { + ret = -EIO; + break; + } + + /* state machine will have generated a report, copy it out */ + memcpy(buffer, _reports, sizeof(*_reports)); + ret = sizeof(*_reports); + + } while (0); + + return ret; +} + +int +ETS::measure() +{ + int ret; + + /* + * Send the command to begin a measurement. + */ + uint8_t cmd = ETS_READ_CMD; + ret = transfer(&cmd, 1, nullptr, 0); + + if (OK != ret) + { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } + ret = OK; + + return ret; +} + +int +ETS::collect() +{ + int ret = -EIO; + + /* read from the sensor */ + uint8_t val[2] = {0, 0}; + + perf_begin(_sample_perf); + + ret = transfer(nullptr, 0, &val[0], 2); + + if (ret < 0) + { + log("error reading from sensor: %d", ret); + return ret; + } + + uint16_t distance = val[0] << 8 | val[1]; + float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */ + /* this should be fairly close to the end of the measurement, so the best approximation of the time */ + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].distance = si_units; + _reports[_next_report].valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; + + /* publish it */ + orb_publish(ORB_ID(_differential_pressure), _differential_pressure_topic, &_reports[_next_report]); + + /* post a report to the ring - note, not locked */ + INCREMENT(_next_report, _num_reports); + + /* if we are running up against the oldest report, toss it */ + if (_next_report == _oldest_report) { + perf_count(_buffer_overflows); + INCREMENT(_oldest_report, _num_reports); + } + + /* notify anyone waiting for data */ + poll_notify(POLLIN); + + ret = OK; + +out: + perf_end(_sample_perf); + return ret; + + return ret; +} + +void +ETS::start() +{ + /* reset the report ring and state machine */ + _collect_phase = false; + _oldest_report = _next_report = 0; + + /* schedule a cycle to start things */ + work_queue(HPWORK, &_work, (worker_t)&ETS::cycle_trampoline, this, 1); + + /* notify about state change */ + struct subsystem_info_s info = { + true, + true, + true, + SUBSYSTEM_TYPE_DIFFPRESSURE}; + static orb_advert_t pub = -1; + + if (pub > 0) { + orb_publish(ORB_ID(subsystem_info), pub, &info); + } else { + pub = orb_advertise(ORB_ID(subsystem_info), &info); + } +} + +void +ETS::stop() +{ + work_cancel(HPWORK, &_work); +} + +void +ETS::cycle_trampoline(void *arg) +{ + ETS *dev = (ETS *)arg; + + dev->cycle(); +} + +void +ETS::cycle() +{ + /* collection phase? */ + if (_collect_phase) { + + /* perform collection */ + if (OK != collect()) { + log("collection error"); + /* restart the measurement state machine */ + start(); + return; + } + + /* next phase is measurement */ + _collect_phase = false; + + /* + * Is there a collect->measure gap? + */ + if (_measure_ticks > USEC2TICK(ETS_CONVERSION_INTERVAL)) { + + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&ETS::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(ETS_CONVERSION_INTERVAL)); + + return; + } + } + + /* measurement phase */ + if (OK != measure()) + log("measure error"); + + /* next phase is collection */ + _collect_phase = true; + + /* schedule a fresh cycle call when the measurement is done */ + work_queue(HPWORK, + &_work, + (worker_t)&ETS::cycle_trampoline, + this, + USEC2TICK(ETS_CONVERSION_INTERVAL)); +} + +void +ETS::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); + perf_print_counter(_buffer_overflows); + printf("poll interval: %u ticks\n", _measure_ticks); + printf("report queue: %u (%u/%u @ %p)\n", + _num_reports, _oldest_report, _next_report, _reports); +} + +/** + * Local functions in support of the shell command. + */ +namespace ETS +{ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +const int ERROR = -1; + +ETS *g_dev; + +void start(); +void stop(); +void test(); +void reset(); +void info(); + +/** + * Start the driver. + */ +void +start() +{ + int fd; + + if (g_dev != nullptr) + errx(1, "already started"); + + /* create the driver */ + g_dev = new ETS(ETS_BUS); + + if (g_dev == nullptr) + goto fail; + + if (OK != g_dev->init()) + goto fail; + + /* set the poll rate to default, starts automatic data collection */ + fd = open(AIRSPEED_SENSOR_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + goto fail; + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + goto fail; + + exit(0); + +fail: + + if (g_dev != nullptr) + { + delete g_dev; + g_dev = nullptr; + } + + errx(1, "driver start failed"); +} + +/** + * Stop the driver + */ +void stop() +{ + if (g_dev != nullptr) + { + delete g_dev; + g_dev = nullptr; + } + else + { + errx(1, "driver not running"); + } + exit(0); +} + +/** + * Perform some basic functional tests on the driver; + * make sure we can collect data from the sensor in polled + * and automatic modes. + */ +void +test() +{ + struct range_finder_report report; + ssize_t sz; + int ret; + + int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "%s open failed (try 'ETS start' if the driver is not running", RANGE_FINDER_DEVICE_PATH); + + /* do a simple demand read */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) + err(1, "immediate read failed"); + + warnx("single read"); + warnx("measurement: %0.2f m", (double)report.distance); + warnx("time: %lld", report.timestamp); + + /* start the sensor polling at 2Hz */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) + errx(1, "failed to set 2Hz poll rate"); + + /* read the sensor 5x and report each value */ + for (unsigned i = 0; i < 5; i++) { + struct pollfd fds; + + /* wait for data to be ready */ + fds.fd = fd; + fds.events = POLLIN; + ret = poll(&fds, 1, 2000); + + if (ret != 1) + errx(1, "timed out waiting for sensor data"); + + /* now go get it */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) + err(1, "periodic read failed"); + + warnx("periodic read %u", i); + warnx("measurement: %0.3f", (double)report.distance); + warnx("time: %lld", report.timestamp); + } + + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + + if (fd < 0) + err(1, "failed "); + + if (ioctl(fd, SENSORIOCRESET, 0) < 0) + err(1, "driver reset failed"); + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + err(1, "driver poll restart failed"); + + exit(0); +} + +/** + * Print a little info about the driver. + */ +void +info() +{ + if (g_dev == nullptr) + errx(1, "driver not running"); + + printf("state @ %p\n", g_dev); + g_dev->print_info(); + + exit(0); +} + +} // namespace + +int +ETS_main(int argc, char *argv[]) +{ + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) + ETS::start(); + + /* + * Stop the driver + */ + if (!strcmp(argv[1], "stop")) + ETS::stop(); + + /* + * Test the driver/device. + */ + if (!strcmp(argv[1], "test")) + ETS::test(); + + /* + * Reset the driver. + */ + if (!strcmp(argv[1], "reset")) + ETS::reset(); + + /* + * Print driver information. + */ + if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) + ETS::info(); + + errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); +} From 4f99200b0ff102c01f415a57e9f173a863483d2a Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 11 Apr 2013 08:36:54 +0200 Subject: [PATCH 002/102] Initial implementation that can read values from the ETS. --- apps/drivers/{ets => ets_airspeed}/Makefile | 0 .../{ets => ets_airspeed}/ets_airspeed.cpp | 123 +++++++++--------- apps/px4io/controls.c | 2 +- apps/uORB/objects_common.cpp | 3 + nuttx/configs/px4fmu/nsh/appconfig | 1 + 5 files changed, 67 insertions(+), 62 deletions(-) rename apps/drivers/{ets => ets_airspeed}/Makefile (100%) rename apps/drivers/{ets => ets_airspeed}/ets_airspeed.cpp (82%) diff --git a/apps/drivers/ets/Makefile b/apps/drivers/ets_airspeed/Makefile similarity index 100% rename from apps/drivers/ets/Makefile rename to apps/drivers/ets_airspeed/Makefile diff --git a/apps/drivers/ets/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp similarity index 82% rename from apps/drivers/ets/ets_airspeed.cpp rename to apps/drivers/ets_airspeed/ets_airspeed.cpp index 4ac707c3cb..790e949e0f 100644 --- a/apps/drivers/ets/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -65,20 +65,22 @@ #include #include +#include #include #include /* Configuration Constants */ -#define ETS_BUS PX4_I2C_BUS_EXPANSION -#define ETS_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xEA */ +#define ETS_AIRSPEED_BUS PX4_I2C_BUS_ESC +#define ETS_AIRSPEED_ADDRESS 0x75 -/* ETS Registers addresses */ +/* ETS_AIRSPEED Registers addresses */ -#define ETS_READ_CMD 0x07 /* Read the data */ +#define ETS_AIRSPEED_READ_CMD 0x07 /* Read the data */ -#define ETS_CONVERSION_INTERVAL 60000 /* 60ms */ +/* Max measurement rate is 100Hz */ +#define ETS_AIRSPEED_CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -90,11 +92,11 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -class ETS : public device::I2C +class ETS_AIRSPEED : public device::I2C { public: - ETS(int bus = ETS_BUS, int address = ETS_BASEADDR); - virtual ~ETS(); + ETS_AIRSPEED(int bus = ETS_AIRSPEED_BUS, int address = ETS_AIRSPEED_ADDRESS); + virtual ~ETS_AIRSPEED(); virtual int init(); @@ -114,7 +116,7 @@ private: unsigned _num_reports; volatile unsigned _next_report; volatile unsigned _oldest_report; - range_finder_report *_reports; + airspeed_report *_reports; bool _sensor_ok; int _measure_ticks; bool _collect_phase; @@ -171,10 +173,10 @@ private: /* * Driver 'main' command. */ -extern "C" __EXPORT int ETS_main(int argc, char *argv[]); +extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]); -ETS::ETS(int bus, int address) : - I2C("ETS", AIRSPEED_SENSOR_DEVICE_PATH, bus, address, 100000), +ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : + I2C("ETS_AIRSPEED", AIRSPEED_DEVICE_PATH, bus, address, 100000), _num_reports(0), _next_report(0), _oldest_report(0), @@ -183,9 +185,9 @@ ETS::ETS(int bus, int address) : _measure_ticks(0), _collect_phase(false), _differential_pressure_topic(-1), - _sample_perf(perf_alloc(PC_ELAPSED, "ETS_read")), - _comms_errors(perf_alloc(PC_COUNT, "ETS_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ETS_buffer_overflows")) + _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), + _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")) { // enable debug() calls _debug_enabled = true; @@ -194,7 +196,7 @@ ETS::ETS(int bus, int address) : memset(&_work, 0, sizeof(_work)); } -ETS::~ETS() +ETS_AIRSPEED::~ETS_AIRSPEED() { /* make sure we are truly inactive */ stop(); @@ -205,7 +207,7 @@ ETS::~ETS() } int -ETS::init() +ETS_AIRSPEED::init() { int ret = ERROR; @@ -215,7 +217,7 @@ ETS::init() /* allocate basic report buffers */ _num_reports = 2; - _reports = new struct range_finder_report[_num_reports]; + _reports = new struct airspeed_report[_num_reports]; if (_reports == nullptr) goto out; @@ -224,7 +226,7 @@ ETS::init() /* get a publish handle on the airspeed topic */ memset(&_reports[0], 0, sizeof(_reports[0])); - _differential_pressure_topic = orb_advertise(ORB_ID(_differential_pressure), &_reports[0]); + _differential_pressure_topic = orb_advertise(ORB_ID(sensor_differential_pressure), &_reports[0]); if (_differential_pressure_topic < 0) debug("failed to create airspeed sensor object. Did you start uOrb?"); @@ -237,13 +239,13 @@ out: } int -ETS::probe() +ETS_AIRSPEED::probe() { return measure(); } int -ETS::ioctl(struct file *filp, int cmd, unsigned long arg) +ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) { switch (cmd) { @@ -270,7 +272,7 @@ ETS::ioctl(struct file *filp, int cmd, unsigned long arg) bool want_start = (_measure_ticks == 0); /* set interval for next measurement to minimum legal value */ - _measure_ticks = USEC2TICK(ETS_CONVERSION_INTERVAL); + _measure_ticks = USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL); /* if we need to start the poll state machine, do it */ if (want_start) @@ -288,7 +290,7 @@ ETS::ioctl(struct file *filp, int cmd, unsigned long arg) unsigned ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ - if (ticks < USEC2TICK(ETS_CONVERSION_INTERVAL)) + if (ticks < USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)) return -EINVAL; /* update interval for next measurement */ @@ -318,7 +320,7 @@ ETS::ioctl(struct file *filp, int cmd, unsigned long arg) return -EINVAL; /* allocate new buffer */ - struct range_finder_report *buf = new struct range_finder_report[arg]; + struct airspeed_report *buf = new struct airspeed_report[arg]; if (nullptr == buf) return -ENOMEM; @@ -347,9 +349,9 @@ ETS::ioctl(struct file *filp, int cmd, unsigned long arg) } ssize_t -ETS::read(struct file *filp, char *buffer, size_t buflen) +ETS_AIRSPEED::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct range_finder_report); + unsigned count = buflen / sizeof(struct airspeed_report); int ret = 0; /* buffer must be large enough */ @@ -388,7 +390,7 @@ ETS::read(struct file *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(ETS_CONVERSION_INTERVAL); + usleep(ETS_AIRSPEED_CONVERSION_INTERVAL); /* run the collection phase */ if (OK != collect()) { @@ -406,14 +408,14 @@ ETS::read(struct file *filp, char *buffer, size_t buflen) } int -ETS::measure() +ETS_AIRSPEED::measure() { int ret; /* * Send the command to begin a measurement. */ - uint8_t cmd = ETS_READ_CMD; + uint8_t cmd = ETS_AIRSPEED_READ_CMD; ret = transfer(&cmd, 1, nullptr, 0); if (OK != ret) @@ -428,7 +430,7 @@ ETS::measure() } int -ETS::collect() +ETS_AIRSPEED::collect() { int ret = -EIO; @@ -449,11 +451,10 @@ ETS::collect() float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */ /* this should be fairly close to the end of the measurement, so the best approximation of the time */ _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].distance = si_units; - _reports[_next_report].valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; + _reports[_next_report].speed = si_units; /* publish it */ - orb_publish(ORB_ID(_differential_pressure), _differential_pressure_topic, &_reports[_next_report]); + orb_publish(ORB_ID(sensor_differential_pressure), _differential_pressure_topic, &_reports[_next_report]); /* post a report to the ring - note, not locked */ INCREMENT(_next_report, _num_reports); @@ -477,14 +478,14 @@ out: } void -ETS::start() +ETS_AIRSPEED::start() { /* reset the report ring and state machine */ _collect_phase = false; _oldest_report = _next_report = 0; /* schedule a cycle to start things */ - work_queue(HPWORK, &_work, (worker_t)&ETS::cycle_trampoline, this, 1); + work_queue(HPWORK, &_work, (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, 1); /* notify about state change */ struct subsystem_info_s info = { @@ -502,21 +503,21 @@ ETS::start() } void -ETS::stop() +ETS_AIRSPEED::stop() { work_cancel(HPWORK, &_work); } void -ETS::cycle_trampoline(void *arg) +ETS_AIRSPEED::cycle_trampoline(void *arg) { - ETS *dev = (ETS *)arg; + ETS_AIRSPEED *dev = (ETS_AIRSPEED *)arg; dev->cycle(); } void -ETS::cycle() +ETS_AIRSPEED::cycle() { /* collection phase? */ if (_collect_phase) { @@ -535,14 +536,14 @@ ETS::cycle() /* * Is there a collect->measure gap? */ - if (_measure_ticks > USEC2TICK(ETS_CONVERSION_INTERVAL)) { + if (_measure_ticks > USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)) { /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, - (worker_t)&ETS::cycle_trampoline, + (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, - _measure_ticks - USEC2TICK(ETS_CONVERSION_INTERVAL)); + _measure_ticks - USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)); return; } @@ -558,13 +559,13 @@ ETS::cycle() /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, &_work, - (worker_t)&ETS::cycle_trampoline, + (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, - USEC2TICK(ETS_CONVERSION_INTERVAL)); + USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)); } void -ETS::print_info() +ETS_AIRSPEED::print_info() { perf_print_counter(_sample_perf); perf_print_counter(_comms_errors); @@ -577,7 +578,7 @@ ETS::print_info() /** * Local functions in support of the shell command. */ -namespace ETS +namespace ets_airspeed { /* oddly, ERROR is not defined for c++ */ @@ -586,7 +587,7 @@ namespace ETS #endif const int ERROR = -1; -ETS *g_dev; +ETS_AIRSPEED *g_dev; void start(); void stop(); @@ -606,7 +607,7 @@ start() errx(1, "already started"); /* create the driver */ - g_dev = new ETS(ETS_BUS); + g_dev = new ETS_AIRSPEED(ETS_AIRSPEED_BUS); if (g_dev == nullptr) goto fail; @@ -615,7 +616,7 @@ start() goto fail; /* set the poll rate to default, starts automatic data collection */ - fd = open(AIRSPEED_SENSOR_DEVICE_PATH, O_RDONLY); + fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd < 0) goto fail; @@ -661,14 +662,14 @@ void stop() void test() { - struct range_finder_report report; + struct airspeed_report report; ssize_t sz; int ret; - int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'ETS start' if the driver is not running", RANGE_FINDER_DEVICE_PATH); + err(1, "%s open failed (try 'ets_airspeed start' if the driver is not running", AIRSPEED_DEVICE_PATH); /* do a simple demand read */ sz = read(fd, &report, sizeof(report)); @@ -677,7 +678,7 @@ test() err(1, "immediate read failed"); warnx("single read"); - warnx("measurement: %0.2f m", (double)report.distance); + warnx("measurement: %0.2f m", (double)report.speed); warnx("time: %lld", report.timestamp); /* start the sensor polling at 2Hz */ @@ -703,7 +704,7 @@ test() err(1, "periodic read failed"); warnx("periodic read %u", i); - warnx("measurement: %0.3f", (double)report.distance); + warnx("measurement: %0.3f", (double)report.speed); warnx("time: %lld", report.timestamp); } @@ -716,7 +717,7 @@ test() void reset() { - int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd < 0) err(1, "failed "); @@ -748,37 +749,37 @@ info() } // namespace int -ETS_main(int argc, char *argv[]) +ets_airspeed_main(int argc, char *argv[]) { /* * Start/load the driver. */ if (!strcmp(argv[1], "start")) - ETS::start(); + ets_airspeed::start(); /* * Stop the driver */ if (!strcmp(argv[1], "stop")) - ETS::stop(); + ets_airspeed::stop(); /* * Test the driver/device. */ if (!strcmp(argv[1], "test")) - ETS::test(); + ets_airspeed::test(); /* * Reset the driver. */ if (!strcmp(argv[1], "reset")) - ETS::reset(); + ets_airspeed::reset(); /* * Print driver information. */ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) - ETS::info(); + ets_airspeed::info(); errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); } diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index e80a41f15c..9a0f0e5c1b 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -70,7 +70,7 @@ controls_init(void) unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = 0; - r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 1000; + r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 950; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_CENTER] = 1500; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MAX] = 2000; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_DEADZONE] = 30; diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp index 1363751401..cd21d556c5 100644 --- a/apps/uORB/objects_common.cpp +++ b/apps/uORB/objects_common.cpp @@ -56,6 +56,9 @@ ORB_DEFINE(sensor_baro, struct baro_report); #include ORB_DEFINE(sensor_range_finder, struct range_finder_report); +#include +ORB_DEFINE(sensor_differential_pressure, struct airspeed_report); + #include ORB_DEFINE(output_pwm, struct pwm_output_values); diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 80cf6f312c..b5f35f5140 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -127,6 +127,7 @@ CONFIGURED_APPS += drivers/px4fmu CONFIGURED_APPS += drivers/hil CONFIGURED_APPS += drivers/gps CONFIGURED_APPS += drivers/mb12xx +CONFIGURED_APPS += drivers/ets_airspeed # Testing stuff CONFIGURED_APPS += px4/sensors_bringup From c8ac1d0b0a97f5fc926a48e64e0e116387453dcd Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 11 Apr 2013 08:37:25 +0200 Subject: [PATCH 003/102] Add in the missing header. --- apps/drivers/drv_airspeed.h | 74 +++++++++++++++++++++++++++++++++++++ 1 file changed, 74 insertions(+) create mode 100644 apps/drivers/drv_airspeed.h diff --git a/apps/drivers/drv_airspeed.h b/apps/drivers/drv_airspeed.h new file mode 100644 index 0000000000..a98f568070 --- /dev/null +++ b/apps/drivers/drv_airspeed.h @@ -0,0 +1,74 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file Airspeed driver interface. + */ + +#ifndef _DRV_AIRSPEED_H +#define _DRV_AIRSPEED_H + +#include +#include + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +#define AIRSPEED_DEVICE_PATH "/dev/airspeed" + +/** + * Airspeed report structure. Reads from the device must be in multiples of this + * structure. + */ +struct airspeed_report { + uint64_t timestamp; + uint8_t speed; /** in meters/sec */ +}; + +/* + * ObjDev tag for raw range finder data. + */ +ORB_DECLARE(sensor_differential_pressure); + +/* + * ioctl() definitions + * + * Airspeed drivers also implement the generic sensor driver + * interfaces from drv_sensor.h + */ + +#define _AIRSPEEDIOCBASE (0x7700) +#define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n)) + + +#endif /* _DRV_AIRSPEED_H */ From 42f4a9e8800c4d5d2823b4f477c556547fe0d3d0 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 13 Apr 2013 08:47:12 +0200 Subject: [PATCH 004/102] Switch to differential pressure topic --- apps/drivers/drv_airspeed.h | 14 +- apps/drivers/ets_airspeed/ets_airspeed.cpp | 150 ++++++++++++++------- apps/systemlib/airspeed.c | 2 +- apps/uORB/objects_common.cpp | 3 - 4 files changed, 110 insertions(+), 59 deletions(-) diff --git a/apps/drivers/drv_airspeed.h b/apps/drivers/drv_airspeed.h index a98f568070..269ee45591 100644 --- a/apps/drivers/drv_airspeed.h +++ b/apps/drivers/drv_airspeed.h @@ -47,18 +47,18 @@ #define AIRSPEED_DEVICE_PATH "/dev/airspeed" /** - * Airspeed report structure. Reads from the device must be in multiples of this + * Airspeed report structure. Reads from the device must be in multiples of this * structure. */ -struct airspeed_report { - uint64_t timestamp; - uint8_t speed; /** in meters/sec */ -}; +//struct airspeed_report { +// uint64_t timestamp; +// uint8_t diff_pressure; /** differential pressure in Pa */ +//}; /* * ObjDev tag for raw range finder data. */ -ORB_DECLARE(sensor_differential_pressure); +//ORB_DECLARE(sensor_differential_pressure); /* * ioctl() definitions @@ -67,7 +67,7 @@ ORB_DECLARE(sensor_differential_pressure); * interfaces from drv_sensor.h */ -#define _AIRSPEEDIOCBASE (0x7700) +#define _AIRSPEEDIOCBASE (0x7700) #define __AIRSPEEDIOC(_n) (_IOC(_AIRSPEEDIOCBASE, _n)) diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 790e949e0f..0b535b0b5f 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -63,24 +63,28 @@ #include #include +#include -#include #include +#include #include +#include +#include /* for baro readings */ #include - /* Configuration Constants */ -#define ETS_AIRSPEED_BUS PX4_I2C_BUS_ESC -#define ETS_AIRSPEED_ADDRESS 0x75 +#define I2C_BUS PX4_I2C_BUS_ESC +#define I2C_ADDRESS 0x75 /* ETS_AIRSPEED Registers addresses */ - -#define ETS_AIRSPEED_READ_CMD 0x07 /* Read the data */ +#define READ_CMD 0x07 /* Read the data */ /* Max measurement rate is 100Hz */ -#define ETS_AIRSPEED_CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ +#define CONVERSION_INTERVAL (1000000 / 10) /* microseconds */ + +#define DIFF_PRESSURE_SCALE 1.0 +#define DIFF_PRESSURE_OFFSET 1673 /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -92,10 +96,13 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif +static int _sensor_sub = -1; + + class ETS_AIRSPEED : public device::I2C { public: - ETS_AIRSPEED(int bus = ETS_AIRSPEED_BUS, int address = ETS_AIRSPEED_ADDRESS); + ETS_AIRSPEED(int bus = I2C_BUS, int address = I2C_ADDRESS); virtual ~ETS_AIRSPEED(); virtual int init(); @@ -112,20 +119,21 @@ protected: virtual int probe(); private: - work_s _work; - unsigned _num_reports; - volatile unsigned _next_report; - volatile unsigned _oldest_report; - airspeed_report *_reports; - bool _sensor_ok; - int _measure_ticks; - bool _collect_phase; + work_s _work; + unsigned _num_reports; + volatile unsigned _next_report; + volatile unsigned _oldest_report; + differential_pressure_s *_reports; + bool _sensor_ok; + int _measure_ticks; + bool _collect_phase; - orb_advert_t _differential_pressure_topic; + orb_advert_t _airspeed_pub; + + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; - perf_counter_t _sample_perf; - perf_counter_t _comms_errors; - perf_counter_t _buffer_overflows; /** * Test whether the device supported by the driver is present at a @@ -184,7 +192,7 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), - _differential_pressure_topic(-1), + _airspeed_pub(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")) @@ -217,7 +225,7 @@ ETS_AIRSPEED::init() /* allocate basic report buffers */ _num_reports = 2; - _reports = new struct airspeed_report[_num_reports]; + _reports = new struct differential_pressure_s[_num_reports]; if (_reports == nullptr) goto out; @@ -226,11 +234,18 @@ ETS_AIRSPEED::init() /* get a publish handle on the airspeed topic */ memset(&_reports[0], 0, sizeof(_reports[0])); - _differential_pressure_topic = orb_advertise(ORB_ID(sensor_differential_pressure), &_reports[0]); + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_reports[0]); - if (_differential_pressure_topic < 0) + if (_airspeed_pub < 0) debug("failed to create airspeed sensor object. Did you start uOrb?"); + _sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + + if (_sensor_sub < 0) { + debug("failed to subscribe to sensor_combined object."); + return ret; + } + ret = OK; /* sensor is ok, but we don't really know if it is within range */ _sensor_ok = true; @@ -272,7 +287,7 @@ ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) bool want_start = (_measure_ticks == 0); /* set interval for next measurement to minimum legal value */ - _measure_ticks = USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL); + _measure_ticks = USEC2TICK(CONVERSION_INTERVAL); /* if we need to start the poll state machine, do it */ if (want_start) @@ -290,7 +305,7 @@ ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) unsigned ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ - if (ticks < USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)) + if (ticks < USEC2TICK(CONVERSION_INTERVAL)) return -EINVAL; /* update interval for next measurement */ @@ -320,7 +335,7 @@ ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) return -EINVAL; /* allocate new buffer */ - struct airspeed_report *buf = new struct airspeed_report[arg]; + struct differential_pressure_s *buf = new struct differential_pressure_s[arg]; if (nullptr == buf) return -ENOMEM; @@ -351,7 +366,7 @@ ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) ssize_t ETS_AIRSPEED::read(struct file *filp, char *buffer, size_t buflen) { - unsigned count = buflen / sizeof(struct airspeed_report); + unsigned count = buflen / sizeof(struct differential_pressure_s); int ret = 0; /* buffer must be large enough */ @@ -390,7 +405,7 @@ ETS_AIRSPEED::read(struct file *filp, char *buffer, size_t buflen) } /* wait for it to complete */ - usleep(ETS_AIRSPEED_CONVERSION_INTERVAL); + usleep(CONVERSION_INTERVAL); /* run the collection phase */ if (OK != collect()) { @@ -415,7 +430,7 @@ ETS_AIRSPEED::measure() /* * Send the command to begin a measurement. */ - uint8_t cmd = ETS_AIRSPEED_READ_CMD; + uint8_t cmd = READ_CMD; ret = transfer(&cmd, 1, nullptr, 0); if (OK != ret) @@ -441,20 +456,48 @@ ETS_AIRSPEED::collect() ret = transfer(nullptr, 0, &val[0], 2); - if (ret < 0) - { + if (ret < 0) { log("error reading from sensor: %d", ret); return ret; } - uint16_t distance = val[0] << 8 | val[1]; - float si_units = (distance * 1.0f)/ 100.0f; /* cm to m */ - /* this should be fairly close to the end of the measurement, so the best approximation of the time */ - _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].speed = si_units; + uint16_t diff_pres_pa = val[1] << 8 | val[0]; + //log("val: %0.3f", (float)(diff_pressure)); + + /* adjust if necessary */ + diff_pres_pa = DIFF_PRESSURE_SCALE * (diff_pres_pa - DIFF_PRESSURE_OFFSET); + //log("measurement: %0.2f m/s", calc_indicated_airspeed((float)_reports[_next_report].diff_pressure)); + + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + + bool updated; + orb_check(_sensor_sub, &updated); + if (updated) { + orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw); + printf("baro temp %3.6f\n", raw.baro_pres_mbar); + } + unlock(); + //if (raw.baro_temp_celcius > 0) + // log("baro temp %3.3f\n", (uint8_t) raw.baro_temp_celcius); + + float airspeed_true = calc_true_airspeed(diff_pres_pa + raw.baro_pres_mbar*1e2f, + raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa + // XXX HACK - true temperature is much less than indicated temperature in baro, + // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB + + float airspeed_indicated = calc_indicated_airspeed(diff_pres_pa); - /* publish it */ - orb_publish(ORB_ID(sensor_differential_pressure), _differential_pressure_topic, &_reports[_next_report]); + _reports[_next_report].timestamp = hrt_absolute_time(); + _reports[_next_report].static_pressure_mbar = raw.baro_pres_mbar; + _reports[_next_report].differential_pressure_mbar = diff_pres_pa * 1e-2f; + _reports[_next_report].temperature_celcius = raw.baro_temp_celcius; + _reports[_next_report].indicated_airspeed_m_s = airspeed_indicated; + _reports[_next_report].true_airspeed_m_s = airspeed_true; + _reports[_next_report].voltage = 0; + + /* announce the airspeed if needed, just publish else */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); /* post a report to the ring - note, not locked */ INCREMENT(_next_report, _num_reports); @@ -472,7 +515,6 @@ ETS_AIRSPEED::collect() out: perf_end(_sample_perf); - return ret; return ret; } @@ -536,14 +578,14 @@ ETS_AIRSPEED::cycle() /* * Is there a collect->measure gap? */ - if (_measure_ticks > USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)) { + if (_measure_ticks > USEC2TICK(CONVERSION_INTERVAL)) { /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, - _measure_ticks - USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)); + _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); return; } @@ -561,7 +603,7 @@ ETS_AIRSPEED::cycle() &_work, (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, - USEC2TICK(ETS_AIRSPEED_CONVERSION_INTERVAL)); + USEC2TICK(CONVERSION_INTERVAL)); } void @@ -607,7 +649,7 @@ start() errx(1, "already started"); /* create the driver */ - g_dev = new ETS_AIRSPEED(ETS_AIRSPEED_BUS); + g_dev = new ETS_AIRSPEED(I2C_BUS); if (g_dev == nullptr) goto fail; @@ -662,7 +704,7 @@ void stop() void test() { - struct airspeed_report report; + struct differential_pressure_s report; ssize_t sz; int ret; @@ -678,7 +720,18 @@ test() err(1, "immediate read failed"); warnx("single read"); - warnx("measurement: %0.2f m", (double)report.speed); + warnx("diff pressure: %0.3f mbar", report.differential_pressure_mbar); + warnx("indicated airspeed: %0.1f m/s", report.indicated_airspeed_m_s); + warnx("true airspeed: %0.1f m/s", report.true_airspeed_m_s); + + struct sensor_combined_s raw; + memset(&raw, 0, sizeof(raw)); + int sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); + + //if (raw.baro_temp_celcius > 0) + // log("baro temp %3.3f\n", (uint8_t) raw.baro_temp_celcius); + warnx("temp: %3.5f", raw.baro_temp_celcius); warnx("time: %lld", report.timestamp); /* start the sensor polling at 2Hz */ @@ -704,8 +757,9 @@ test() err(1, "periodic read failed"); warnx("periodic read %u", i); - warnx("measurement: %0.3f", (double)report.speed); - warnx("time: %lld", report.timestamp); + warnx("diff pressure: %0.3f mbar", report.differential_pressure_mbar); + warnx("indicated airspeed: %0.1f m/s", report.indicated_airspeed_m_s); + warnx("true airspeed: %0.1f m/s", report.true_airspeed_m_s); warnx("time: %lld", report.timestamp); } errx(0, "PASS"); diff --git a/apps/systemlib/airspeed.c b/apps/systemlib/airspeed.c index 264287b10f..15bb833a99 100644 --- a/apps/systemlib/airspeed.c +++ b/apps/systemlib/airspeed.c @@ -97,7 +97,7 @@ float calc_true_airspeed(float total_pressure, float static_pressure, float temp float density = get_air_density(static_pressure, temperature_celsius); if (density < 0.0001f || !isfinite(density)) { density = CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C; - printf("[airspeed] Invalid air density, using density at sea level\n"); +// printf("[airspeed] Invalid air density, using density at sea level\n"); } float pressure_difference = total_pressure - static_pressure; diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp index cd21d556c5..1363751401 100644 --- a/apps/uORB/objects_common.cpp +++ b/apps/uORB/objects_common.cpp @@ -56,9 +56,6 @@ ORB_DEFINE(sensor_baro, struct baro_report); #include ORB_DEFINE(sensor_range_finder, struct range_finder_report); -#include -ORB_DEFINE(sensor_differential_pressure, struct airspeed_report); - #include ORB_DEFINE(output_pwm, struct pwm_output_values); From c5a453cd18949d2d4673c0b343e22c22a8d2854d Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sat, 13 Apr 2013 09:09:21 +0200 Subject: [PATCH 005/102] Remove some testing code. --- apps/drivers/ets_airspeed/ets_airspeed.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 0b535b0b5f..58d016a307 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -477,7 +477,6 @@ ETS_AIRSPEED::collect() orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw); printf("baro temp %3.6f\n", raw.baro_pres_mbar); } - unlock(); //if (raw.baro_temp_celcius > 0) // log("baro temp %3.3f\n", (uint8_t) raw.baro_temp_celcius); From 59573e5b69f9afc5dbe00bc165ae8e1f4d457f89 Mon Sep 17 00:00:00 2001 From: marco Date: Wed, 17 Apr 2013 19:46:01 +0200 Subject: [PATCH 006/102] BLCtrl 2.0 testing - currently only 8 Bit resolution - this should fly --- apps/drivers/mkblctrl/Makefile | 44 + apps/drivers/mkblctrl/mkblctrl.cpp | 1403 ++++++++++++++++++++++++++++ nuttx/configs/px4fmu/nsh/appconfig | 1 + 3 files changed, 1448 insertions(+) create mode 100644 apps/drivers/mkblctrl/Makefile create mode 100644 apps/drivers/mkblctrl/mkblctrl.cpp diff --git a/apps/drivers/mkblctrl/Makefile b/apps/drivers/mkblctrl/Makefile new file mode 100644 index 0000000000..b3be2c4687 --- /dev/null +++ b/apps/drivers/mkblctrl/Makefile @@ -0,0 +1,44 @@ +############################################################################ +# +# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Interface driver for the Mikrokopter BLCtrl +# + +APPNAME = mkblctrl +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common + +include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp new file mode 100644 index 0000000000..c14fdfd1d8 --- /dev/null +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -0,0 +1,1403 @@ +/**************************************************************************** + * + * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mkblctrl.cpp + * + * Driver/configurator for the Mikrokopter BL-Ctrl. + * Marco Bauer + * + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +#include + +#define I2C_BUS_SPEED 400000 +#define UPDATE_RATE 400 +#define MAX_MOTORS 8 +#define BLCTRL_BASE_ADDR 0x29 +#define BLCTRL_OLD 0 +#define BLCTRL_NEW 1 +#define BLCTRL_MIN_VALUE -0.984F +#define MOTOR_STATE_PRESENT_MASK 0x80 +#define MOTOR_STATE_ERROR_MASK 0x7F +#define MOTOR_SPINUP_COUNTER 2500 + + +class MK : public device::I2C +{ +public: + enum Mode { + MODE_2PWM, + MODE_4PWM, + MODE_NONE + }; + + enum MappingMode { + MAPPING_MK = 0, + MAPPING_PX4, + }; + + enum FrameType { + FRAME_PLUS = 0, + FRAME_X, + }; + + MK(int bus); + ~MK(); + + virtual int ioctl(file *filp, int cmd, unsigned long arg); + virtual int init(unsigned motors); + + int set_mode(Mode mode); + int set_pwm_rate(unsigned rate); + int set_motor_count(unsigned count); + int set_motor_test(bool motortest); + int set_px4mode(int px4mode); + int set_frametype(int frametype); + +private: + static const unsigned _max_actuators = MAX_MOTORS; + static const bool showDebug = false; + + Mode _mode; + int _update_rate; + int _current_update_rate; + int _task; + int _t_actuators; + int _t_armed; + unsigned int _motor; + int _px4mode; + int _frametype; + orb_advert_t _t_outputs; + orb_advert_t _t_actuators_effective; + unsigned int _num_outputs; + bool _primary_pwm_device; + bool _motortest; + + volatile bool _task_should_exit; + bool _armed; + + unsigned long debugCounter; + + MixerGroup *_mixers; + + actuator_controls_s _controls; + + static void task_main_trampoline(int argc, char *argv[]); + void task_main() __attribute__((noreturn)); + + static int control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input); + + int pwm_ioctl(file *filp, int cmd, unsigned long arg); + + struct GPIOConfig { + uint32_t input; + uint32_t output; + uint32_t alt; + }; + + static const GPIOConfig _gpio_tab[]; + static const unsigned _ngpio; + + void gpio_reset(void); + void gpio_set_function(uint32_t gpios, int function); + void gpio_write(uint32_t gpios, int function); + uint32_t gpio_read(void); + int gpio_ioctl(file *filp, int cmd, unsigned long arg); + int mk_servo_arm(bool status); + + int mk_check_for_blctrl(unsigned int count); + int mk_servo_set(unsigned int chan, float val); + int mk_servo_set_test(unsigned int chan, float val); + int mk_servo_test(unsigned int chan); + + +}; + +const MK::GPIOConfig MK::_gpio_tab[] = { + {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, + {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, + {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, + {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1}, + {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1}, + {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1}, + {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, + {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, +}; + +const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]); + +const int blctrlAddr_quad_plus[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad + configuration +const int blctrlAddr_hexa_plus[] = { 0, 2, 2, -2, 1, -3, 0, 0 }; // Addresstranslator for Hexa + configuration +const int blctrlAddr_octo_plus[] = { 0, 3, -1, 0, 3, 0, 0, -5 }; // Addresstranslator for Octo + configuration + +const int blctrlAddr_quad_x[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad X configuration +const int blctrlAddr_hexa_x[] = { 2, 4, -2, 0, -3, -1, 0, 0 }; // Addresstranslator for Hexa X configuration +const int blctrlAddr_octo_x[] = { 1, 4, 0, 1, -4, 1, 1, -4 }; // Addresstranslator for Octo X configuration + +const int blctrlAddr_px4[] = { 0, 0, 0, 0, 0, 0, 0, 0}; + +int addrTranslator[] = {0,0,0,0,0,0,0,0}; + +struct MotorData_t +{ + unsigned int Version; // the version of the BL (0 = old) + unsigned int SetPoint; // written by attitude controller + unsigned int SetPointLowerBits; // for higher Resolution of new BLs + unsigned int State; // 7 bit for I2C error counter, highest bit indicates if motor is present + unsigned int ReadMode; // select data to read + // the following bytes must be exactly in that order! + unsigned int Current; // in 0.1 A steps, read back from BL + unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit + unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in °C + unsigned int RoundCount; +}; + +MotorData_t Motor[MAX_MOTORS]; + + +namespace +{ + +MK *g_mk; + +} // namespace + +MK::MK(int bus) : + I2C("mkblctrl", "/dev/mkblctrl", bus, 0, I2C_BUS_SPEED), + _mode(MODE_NONE), + _update_rate(50), + _task(-1), + _t_actuators(-1), + _t_armed(-1), + _t_outputs(0), + _t_actuators_effective(0), + _num_outputs(0), + _motortest(false), + _motor(-1), + _px4mode(MAPPING_MK), + _frametype(FRAME_PLUS), + _primary_pwm_device(false), + _task_should_exit(false), + _armed(false), + _mixers(nullptr) +{ + _debug_enabled = true; +} + +MK::~MK() +{ + if (_task != -1) { + /* tell the task we want it to go away */ + _task_should_exit = true; + + unsigned i = 10; + + do { + /* wait 50ms - it should wake every 100ms or so worst-case */ + usleep(50000); + + /* if we have given up, kill it */ + if (--i == 0) { + task_delete(_task); + break; + } + + } while (_task != -1); + } + + /* clean up the alternate device node */ + if (_primary_pwm_device) + unregister_driver(PWM_OUTPUT_DEVICE_PATH); + + g_mk = nullptr; +} + +int +MK::init(unsigned motors) +{ + _num_outputs = motors; + debugCounter = 0; + int ret; + ASSERT(_task == -1); + + ret = I2C::init(); + + if (ret != OK) { + warnx("I2C init failed"); + return ret; + } + + usleep(500000); + + /* try to claim the generic PWM output device node as well - it's OK if we fail at this */ + ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this); + + if (ret == OK) { + log("default PWM output device"); + _primary_pwm_device = true; + } + + /* reset GPIOs */ + gpio_reset(); + + /* check for connected blctrls */ + //mk_check_for_blctrl(_num_outputs); + + /* start the IO interface task */ + _task = task_spawn("mkblctrl", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX -20, + 2048, + (main_t)&MK::task_main_trampoline, + nullptr); + + + if (_task < 0) { + debug("task start failed: %d", errno); + return -errno; + } + + return OK; +} + +void +MK::task_main_trampoline(int argc, char *argv[]) +{ + g_mk->task_main(); +} + +int +MK::set_mode(Mode mode) +{ + /* + * Configure for PWM output. + * + * Note that regardless of the configured mode, the task is always + * listening and mixing; the mode just selects which of the channels + * are presented on the output pins. + */ + switch (mode) { + case MODE_2PWM: + if(_num_outputs == 4) { + debug("MODE_QUAD"); + } else if(_num_outputs == 6) { + debug("MODE_HEXA"); + } else if(_num_outputs == 8) { + debug("MODE_OCTO"); + } + //up_pwm_servo_init(0x3); + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; /* default output rate */ + break; + + case MODE_4PWM: + if(_num_outputs == 4) { + debug("MODE_QUADRO"); + } else if(_num_outputs == 6) { + debug("MODE_HEXA"); + } else if(_num_outputs == 8) { + debug("MODE_OCTO"); + } + //up_pwm_servo_init(0xf); + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; /* default output rate */ + break; + + case MODE_NONE: + debug("MODE_NONE"); + /* disable servo outputs and set a very low update rate */ + up_pwm_servo_deinit(); + _update_rate = UPDATE_RATE; + break; + + default: + return -EINVAL; + } + + _mode = mode; + return OK; +} + +int +MK::set_pwm_rate(unsigned rate) +{ + if ((rate > 500) || (rate < 10)) + return -EINVAL; + + _update_rate = rate; + return OK; +} + +int +MK::set_px4mode(int px4mode) +{ + _px4mode = px4mode; +} + +int +MK::set_frametype(int frametype) +{ + _frametype = frametype; +} + + +int +MK::set_motor_count(unsigned count) +{ + _num_outputs = count; + + if(_px4mode == MAPPING_MK) { + if(_frametype == FRAME_PLUS) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); + } else if(_frametype == FRAME_X) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + } + if(_num_outputs == 4) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); + } + } else if(_num_outputs == 6) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); + } + } else if(_num_outputs == 8) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); + } + } + } else { + fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); + memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); + } + + /* check for connected blctrls */ + mk_check_for_blctrl(_num_outputs); + + return OK; +} + +int +MK::set_motor_test(bool motortest) +{ + _motortest = motortest; + return OK; +} + + +void +MK::task_main() +{ + /* + * Subscribe to the appropriate PWM output topic based on whether we are the + * primary PWM output or not. + */ + _t_actuators = orb_subscribe(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : + ORB_ID(actuator_controls_1)); + /* force a reset of the update rate */ + _current_update_rate = 0; + + _t_armed = orb_subscribe(ORB_ID(actuator_armed)); + orb_set_interval(_t_armed, 200); /* 5Hz update rate */ + + /* advertise the mixed control outputs */ + actuator_outputs_s outputs; + memset(&outputs, 0, sizeof(outputs)); + /* advertise the mixed control outputs */ + _t_outputs = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), + &outputs); + + /* advertise the effective control inputs */ + actuator_controls_effective_s controls_effective; + memset(&controls_effective, 0, sizeof(controls_effective)); + /* advertise the effective control inputs */ + _t_actuators_effective = orb_advertise(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), + &controls_effective); + + pollfd fds[2]; + fds[0].fd = _t_actuators; + fds[0].events = POLLIN; + fds[1].fd = _t_armed; + fds[1].events = POLLIN; + + log("starting"); + long update_rate_in_us = 0; + + /* loop until killed */ + while (!_task_should_exit) { + + /* handle update rate changes */ + if (_current_update_rate != _update_rate) { + int update_rate_in_ms = int(1000 / _update_rate); + update_rate_in_us = long(1000000 / _update_rate); + + /* reject faster than 500 Hz updates */ + if (update_rate_in_ms < 2) { + update_rate_in_ms = 2; + _update_rate = 500; + } + /* reject slower than 50 Hz updates */ + if (update_rate_in_ms > 20) { + update_rate_in_ms = 20; + _update_rate = 50; + } + + orb_set_interval(_t_actuators, update_rate_in_ms); + up_pwm_servo_set_rate(_update_rate); + _current_update_rate = _update_rate; + } + + /* sleep waiting for data, but no more than a second */ + int ret = ::poll(&fds[0], 2, 1000); + + /* this would be bad... */ + if (ret < 0) { + log("poll error %d", errno); + usleep(1000000); + continue; + } + + /* do we have a control update? */ + if (fds[0].revents & POLLIN) { + + /* get controls - must always do this to avoid spinning */ + orb_copy(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS : ORB_ID(actuator_controls_1), _t_actuators, &_controls); + + /* can we mix? */ + if (_mixers != nullptr) { + + /* do mixing */ + outputs.noutputs = _mixers->mix(&outputs.output[0], _num_outputs); + outputs.timestamp = hrt_absolute_time(); + + // XXX output actual limited values + memcpy(&controls_effective, &_controls, sizeof(controls_effective)); + + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE : ORB_ID(actuator_controls_effective_1), _t_actuators_effective, &controls_effective); + + /* iterate actuators */ + for (unsigned int i = 0; i < _num_outputs; i++) { + + /* last resort: catch NaN, INF and out-of-band errors */ + if (i < outputs.noutputs && + isfinite(outputs.output[i]) && + outputs.output[i] >= -1.0f && + outputs.output[i] <= 1.0f) { + /* scale for PWM output 900 - 2100us */ + //outputs.output[i] = 1500 + (600 * outputs.output[i]); + //outputs.output[i] = 127 + (127 * outputs.output[i]); + } else { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + if(outputs.output[i] < -1.0f) { + outputs.output[i] = -1.0f; + } else if(outputs.output[i] > 1.0f) { + outputs.output[i] = 1.0f; + } else { + outputs.output[i] = -1.0f; + } + } + + /* don't go under BLCTRL_MIN_VALUE */ + if(outputs.output[i] < BLCTRL_MIN_VALUE) { + outputs.output[i] = BLCTRL_MIN_VALUE; + } + //_motortest = true; + /* output to BLCtrl's */ + if(_motortest == true) { + mk_servo_test(i); + } else { + //mk_servo_set(i, outputs.output[i]); + mk_servo_set_test(i, outputs.output[i]); // 8Bit + } + + + } + + /* and publish for anyone that cares to see */ + orb_publish(_primary_pwm_device ? ORB_ID_VEHICLE_CONTROLS : ORB_ID(actuator_outputs_1), _t_outputs, &outputs); + } + } + + /* how about an arming update? */ + if (fds[1].revents & POLLIN) { + actuator_armed_s aa; + + /* get new value */ + orb_copy(ORB_ID(actuator_armed), _t_armed, &aa); + + /* update PWM servo armed status if armed and not locked down */ + ////up_pwm_servo_arm(aa.armed && !aa.lockdown); + mk_servo_arm(aa.armed && !aa.lockdown); + } + } + + ::close(_t_actuators); + ::close(_t_actuators_effective); + ::close(_t_armed); + + + /* make sure servos are off */ + up_pwm_servo_deinit(); + + log("stopping"); + + /* note - someone else is responsible for restoring the GPIO config */ + + /* tell the dtor that we are exiting */ + _task = -1; + _exit(0); +} + + +int +MK::mk_servo_arm(bool status) +{ + _armed = status; + return 0; +} + + +int +MK::mk_check_for_blctrl(unsigned int count) +{ + _retries = 10; + uint8_t foundMotorCount = 0; + + for(unsigned i=0; i 2047) { + tmpVal = 2047; + } + + + Motor[chan].SetPoint = (uint8_t) tmpVal / 3; // divide 8 + Motor[chan].SetPointLowerBits = (uint8_t) tmpVal % 8; // rest of divide 8 + //rod = (uint8_t) tmpVal % 8; + //Motor[chan].SetPointLowerBits = rod<<1; // rest of divide 8 + Motor[chan].SetPointLowerBits = 0; + + if(_armed == false) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + //if(Motor[chan].State & MOTOR_STATE_PRESENT_MASK) { + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + + if(Motor[chan].Version == BLCTRL_OLD) { + /* + * Old BL-Ctrl 8Bit served. Version < 2.0 + */ + msg[0] = Motor[chan].SetPoint; + if(Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], 1, &result[0], 2)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = 255;; + } else { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + Motor[chan].RoundCount = 0; + } else { + if (OK != transfer(&msg[0], 1, nullptr, 0)) { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + } + + } else { + /* + * New BL-Ctrl 11Bit served. Version >= 2.0 + */ + msg[0] = Motor[chan].SetPoint; + msg[1] = Motor[chan].SetPointLowerBits; + + if(Motor[chan].SetPointLowerBits == 0) { + bytesToSendBL2 = 1; // if setpoint lower bits are zero, we send only the higher bits - this saves time + } + + if(Motor[chan].RoundCount >= 16) { + // on each 16th cyle we read out the status messages from the blctrl + if (OK == transfer(&msg[0], bytesToSendBL2, &result[0], 3)) { + Motor[chan].Current = result[0]; + Motor[chan].MaxPWM = result[1]; + Motor[chan].Temperature = result[2]; + } else { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + Motor[chan].RoundCount = 0; + } else { + if (OK != transfer(&msg[0], bytesToSendBL2, nullptr, 0)) { + if((Motor[chan].State & MOTOR_STATE_ERROR_MASK) < MOTOR_STATE_ERROR_MASK) Motor[chan].State++; // error + } + } + + } + + Motor[chan].RoundCount++; + //} + + if(showDebug == true) { + debugCounter++; + if(debugCounter == 2000) { + debugCounter = 0; + for(int i=0; i<_num_outputs; i++){ + if(Motor[i].State & MOTOR_STATE_PRESENT_MASK) { + fprintf(stderr, "[mkblctrl] #%i:\tVer: %i\tVal: %i\tCurr: %i\tMaxPWM: %i\tTemp: %i\tState: %i\n", i, Motor[i].Version, Motor[i].SetPoint, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature, Motor[i].State); + } + } + fprintf(stderr, "\n"); + } + } + return 0; +} + +int +MK::mk_servo_set_test(unsigned int chan, float val) +{ + _retries = 0; + int ret; + + float tmpVal = 0; + + uint8_t msg[2] = { 0,0 }; + + tmpVal = (1023 + (1023 * val)); + if(tmpVal > 2048) { + tmpVal = 2048; + } + + Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); + + if(_armed == false) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + msg[0] = Motor[chan].SetPoint; + + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + ret = transfer(&msg[0], 1, nullptr, 0); + + ret = OK; + + return ret; +} + + +int +MK::mk_servo_test(unsigned int chan) +{ + int ret=0; + float tmpVal = 0; + float val = -1; + _retries = 0; + uint8_t msg[2] = { 0,0 }; + + if(debugCounter >= MOTOR_SPINUP_COUNTER) { + debugCounter = 0; + _motor++; + + if(_motor < _num_outputs) { + fprintf(stderr, "[mkblctrl] Motortest - #%i:\tspinup\n", _motor); + } + + if(_motor >= _num_outputs) { + _motor = -1; + _motortest = false; + } + + } + debugCounter++; + + if(_motor == chan) { + val = BLCTRL_MIN_VALUE; + } else { + val = -1; + } + + tmpVal = (1023 + (1023 * val)); + if(tmpVal > 2048) { + tmpVal = 2048; + } + + //Motor[chan].SetPoint = (uint8_t) (tmpVal / 8); + //Motor[chan].SetPointLowerBits = (uint8_t) (tmpVal % 8) & 0x07; + Motor[chan].SetPoint = (uint8_t) tmpVal>>3; + Motor[chan].SetPointLowerBits = (uint8_t) tmpVal & 0x07; + + if(_motor != chan) { + Motor[chan].SetPoint = 0; + Motor[chan].SetPointLowerBits = 0; + } + + if(Motor[chan].Version == BLCTRL_OLD) { + msg[0] = Motor[chan].SetPoint; + } else { + msg[0] = Motor[chan].SetPoint; + msg[1] = Motor[chan].SetPointLowerBits; + } + + set_address(BLCTRL_BASE_ADDR + (chan + addrTranslator[chan])); + if(Motor[chan].Version == BLCTRL_OLD) { + ret = transfer(&msg[0], 1, nullptr, 0); + } else { + ret = transfer(&msg[0], 2, nullptr, 0); + } + + return ret; +} + + +int +MK::control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input) +{ + const actuator_controls_s *controls = (actuator_controls_s *)handle; + + input = controls->control[control_index]; + return 0; +} + +int +MK::ioctl(file *filp, int cmd, unsigned long arg) +{ + int ret; + + // XXX disabled, confusing users + //debug("ioctl 0x%04x 0x%08x", cmd, arg); + + /* try it as a GPIO ioctl first */ + ret = gpio_ioctl(filp, cmd, arg); + + if (ret != -ENOTTY) + return ret; + + /* if we are in valid PWM mode, try it as a PWM ioctl as well */ + switch (_mode) { + case MODE_2PWM: + case MODE_4PWM: + ret = pwm_ioctl(filp, cmd, arg); + break; + + default: + debug("not in a PWM mode"); + break; + } + + /* if nobody wants it, let CDev have it */ + if (ret == -ENOTTY) + ret = CDev::ioctl(filp, cmd, arg); + + return ret; +} + +int +MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + int channel; + + lock(); + + switch (cmd) { + case PWM_SERVO_ARM: + ////up_pwm_servo_arm(true); + mk_servo_arm(true); + break; + + case PWM_SERVO_DISARM: + ////up_pwm_servo_arm(false); + mk_servo_arm(false); + break; + + case PWM_SERVO_SET_UPDATE_RATE: + set_pwm_rate(arg); + break; + + + case PWM_SERVO_SET(0) ... PWM_SERVO_SET(_max_actuators - 1): + + /* fake an update to the selected 'servo' channel */ + if ((arg >= 0) && (arg <= 255)) { + channel = cmd - PWM_SERVO_SET(0); + //mk_servo_set(channel, arg); + } else { + ret = -EINVAL; + } + + break; + + case PWM_SERVO_GET(0) ... PWM_SERVO_GET(_max_actuators - 1): + /* copy the current output value from the channel */ + *(servo_position_t *)arg = cmd - PWM_SERVO_GET(0); + break; + + case MIXERIOCGETOUTPUTCOUNT: + /* + if (_mode == MODE_4PWM) { + *(unsigned *)arg = 4; + } else { + *(unsigned *)arg = 2; + } + */ + + *(unsigned *)arg = _num_outputs; + + break; + + case MIXERIOCRESET: + if (_mixers != nullptr) { + delete _mixers; + _mixers = nullptr; + } + + break; + + case MIXERIOCADDSIMPLE: { + mixer_simple_s *mixinfo = (mixer_simple_s *)arg; + + SimpleMixer *mixer = new SimpleMixer(control_callback, + (uintptr_t)&_controls, mixinfo); + + if (mixer->check()) { + delete mixer; + ret = -EINVAL; + + } else { + if (_mixers == nullptr) + _mixers = new MixerGroup(control_callback, + (uintptr_t)&_controls); + + _mixers->add_mixer(mixer); + } + + break; + } + + case MIXERIOCLOADBUF: { + const char *buf = (const char *)arg; + unsigned buflen = strnlen(buf, 1024); + + if (_mixers == nullptr) + _mixers = new MixerGroup(control_callback, (uintptr_t)&_controls); + + if (_mixers == nullptr) { + ret = -ENOMEM; + + } else { + + ret = _mixers->load_from_buf(buf, buflen); + + if (ret != 0) { + debug("mixer load failed with %d", ret); + delete _mixers; + _mixers = nullptr; + ret = -EINVAL; + } + } + break; + } + + default: + ret = -ENOTTY; + break; + } + + unlock(); + + return ret; +} + +void +MK::gpio_reset(void) +{ + /* + * Setup default GPIO config - all pins as GPIOs, GPIO driver chip + * to input mode. + */ + for (unsigned i = 0; i < _ngpio; i++) + stm32_configgpio(_gpio_tab[i].input); + + stm32_gpiowrite(GPIO_GPIO_DIR, 0); + stm32_configgpio(GPIO_GPIO_DIR); +} + +void +MK::gpio_set_function(uint32_t gpios, int function) +{ + /* + * GPIOs 0 and 1 must have the same direction as they are buffered + * by a shared 2-port driver. Any attempt to set either sets both. + */ + if (gpios & 3) { + gpios |= 3; + + /* flip the buffer to output mode if required */ + if (GPIO_SET_OUTPUT == function) + stm32_gpiowrite(GPIO_GPIO_DIR, 1); + } + + /* configure selected GPIOs as required */ + for (unsigned i = 0; i < _ngpio; i++) { + if (gpios & (1 << i)) { + switch (function) { + case GPIO_SET_INPUT: + stm32_configgpio(_gpio_tab[i].input); + break; + + case GPIO_SET_OUTPUT: + stm32_configgpio(_gpio_tab[i].output); + break; + + case GPIO_SET_ALT_1: + if (_gpio_tab[i].alt != 0) + stm32_configgpio(_gpio_tab[i].alt); + + break; + } + } + } + + /* flip buffer to input mode if required */ + if ((GPIO_SET_INPUT == function) && (gpios & 3)) + stm32_gpiowrite(GPIO_GPIO_DIR, 0); +} + +void +MK::gpio_write(uint32_t gpios, int function) +{ + int value = (function == GPIO_SET) ? 1 : 0; + + for (unsigned i = 0; i < _ngpio; i++) + if (gpios & (1 << i)) + stm32_gpiowrite(_gpio_tab[i].output, value); +} + +uint32_t +MK::gpio_read(void) +{ + uint32_t bits = 0; + + for (unsigned i = 0; i < _ngpio; i++) + if (stm32_gpioread(_gpio_tab[i].input)) + bits |= (1 << i); + + return bits; +} + +int +MK::gpio_ioctl(struct file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + + lock(); + + switch (cmd) { + + case GPIO_RESET: + gpio_reset(); + break; + + case GPIO_SET_OUTPUT: + case GPIO_SET_INPUT: + case GPIO_SET_ALT_1: + gpio_set_function(arg, cmd); + break; + + case GPIO_SET_ALT_2: + case GPIO_SET_ALT_3: + case GPIO_SET_ALT_4: + ret = -EINVAL; + break; + + case GPIO_SET: + case GPIO_CLEAR: + gpio_write(arg, cmd); + break; + + case GPIO_GET: + *(uint32_t *)arg = gpio_read(); + break; + + default: + ret = -ENOTTY; + } + + unlock(); + + return ret; +} + +namespace +{ + +enum PortMode { + PORT_MODE_UNSET = 0, + PORT_FULL_GPIO, + PORT_FULL_SERIAL, + PORT_FULL_PWM, + PORT_GPIO_AND_SERIAL, + PORT_PWM_AND_SERIAL, + PORT_PWM_AND_GPIO, +}; + +enum MappingMode { + MAPPING_MK = 0, + MAPPING_PX4, +}; + + enum FrameType { + FRAME_PLUS = 0, + FRAME_X, + }; + +PortMode g_port_mode; + +int +mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype) +{ + uint32_t gpio_bits; + MK::Mode servo_mode; + + /* reset to all-inputs */ + g_mk->ioctl(0, GPIO_RESET, 0); + + gpio_bits = 0; + servo_mode = MK::MODE_NONE; + + switch (new_mode) { + case PORT_FULL_GPIO: + case PORT_MODE_UNSET: + /* nothing more to do here */ + break; + + case PORT_FULL_SERIAL: + /* set all multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_1 | GPIO_MULTI_2 | GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_FULL_PWM: + /* select 4-pin PWM mode */ + servo_mode = MK::MODE_4PWM; + break; + + case PORT_GPIO_AND_SERIAL: + /* set RX/TX multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_PWM_AND_SERIAL: + /* select 2-pin PWM mode */ + servo_mode = MK::MODE_2PWM; + /* set RX/TX multi-GPIOs to serial mode */ + gpio_bits = GPIO_MULTI_3 | GPIO_MULTI_4; + break; + + case PORT_PWM_AND_GPIO: + /* select 2-pin PWM mode */ + servo_mode = MK::MODE_2PWM; + break; + } + + /* adjust GPIO config for serial mode(s) */ + if (gpio_bits != 0) + g_mk->ioctl(0, GPIO_SET_ALT_1, gpio_bits); + + /* native PX4 addressing) */ + g_mk->set_px4mode(px4mode); + + /* set frametype (geometry) */ + g_mk->set_frametype(frametype); + + /* (re)set count of used motors */ + g_mk->set_motor_count(motorcount); + + /* (re)set the PWM output mode */ + g_mk->set_mode(servo_mode); + + /* motortest if enabled */ + g_mk->set_motor_test(motortest); + + if ((servo_mode != MK::MODE_NONE) && (update_rate != 0)) + g_mk->set_pwm_rate(update_rate); + + return OK; +} + +int +mk_start(unsigned bus, unsigned motors) +{ + int ret = OK; + + if (g_mk == nullptr) { + + g_mk = new MK(bus); + + if (g_mk == nullptr) { + ret = -ENOMEM; + + } else { + ret = g_mk->init(motors); + + if (ret != OK) { + delete g_mk; + g_mk = nullptr; + } + } + } + + return ret; +} + + +} // namespace + +extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); + +int +mkblctrl_main(int argc, char *argv[]) +{ + PortMode new_mode = PORT_MODE_UNSET; + int pwm_update_rate_in_hz = UPDATE_RATE; + int motorcount = 0; + int bus = 1; + bool motortest = false; + int px4mode = MAPPING_MK; + int frametype = FRAME_PLUS; // + plus is default + + /* + * Mode switches. + * + * XXX use getopt? + */ + for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + if (!strcmp(argv[i], "mode_quad")) { + new_mode = PORT_FULL_PWM; + motorcount = 4; + } else if (!strcmp(argv[i], "mode_hexa")) { + new_mode = PORT_FULL_PWM; + motorcount = 6; + } else if (!strcmp(argv[i], "mode_octo")) { + new_mode = PORT_FULL_PWM; + motorcount = 8; + } + + /* look for the optional update rate for the supported modes */ + if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { + if (argc > i + 1) { + pwm_update_rate_in_hz = atoi(argv[i + 1]); + } else { + errx(1, "missing argument for update rate (-u)"); + return 1; + } + } + + /* look for the optional i2c bus parameter */ + if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { + if (argc > i + 1) { + bus = atoi(argv[i + 1]); + } else { + errx(1, "missing argument for i2c bus (-b)"); + return 1; + } + } + + /* look for the optional frame parameter */ + if (strcmp(argv[i], "-f") == 0 || strcmp(argv[i], "--frame") == 0) { + if (argc > i + 1) { + if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { + if(strcmp(argv[i + 1], "+") == 0) { + frametype = FRAME_PLUS; + } else { + frametype = FRAME_PLUS; + } + } else { + errx(1, "only + or x for frametype supported !"); + } + } else { + errx(1, "missing argument for frametype (-f)"); + return 1; + } + } + + /* look for the optional geometry parameter */ + if (strcmp(argv[i], "-px4mode") == 0) { + px4mode = MAPPING_PX4; + } + + /* look for the optional test parameter */ + if (strcmp(argv[i], "-t") == 0) { + motortest = true; + } + + } + + if(new_mode == PORT_MODE_UNSET) { + fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); + fprintf(stderr, " mode_quad, mode_hexa, mode_octo [-b i2c_bus_number] [-u update_rate_in_hz] [-t motortest] [-px4mode] [-f frame{+/x}]\n"); + exit(1); + } + + if (mk_start(bus, motorcount) != OK) + errx(1, "failed to start the MK-BLCtrl driver"); + + + /* was a new mode set? */ + if (new_mode != PORT_MODE_UNSET) { + + /* yes but it's the same mode */ + //if (new_mode == g_port_mode) + //return OK; + + /* switch modes */ + fprintf(stderr, "[mkblctrl] %iHz Update Rate\n",pwm_update_rate_in_hz); + return mk_new_mode(new_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); + } + + /* test, etc. here g*/ + + exit(1); +} diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 80cf6f312c..5bac6214c9 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -124,6 +124,7 @@ CONFIGURED_APPS += drivers/blinkm CONFIGURED_APPS += drivers/stm32/tone_alarm CONFIGURED_APPS += drivers/stm32/adc CONFIGURED_APPS += drivers/px4fmu +CONFIGURED_APPS += drivers/mkblctrl CONFIGURED_APPS += drivers/hil CONFIGURED_APPS += drivers/gps CONFIGURED_APPS += drivers/mb12xx From df6976c8d640b395220d46f5b1fd7ecfc8ae3e04 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 19 Apr 2013 16:20:40 +0200 Subject: [PATCH 007/102] Split diff pressure and airspeed. --- apps/commander/commander.c | 10 +-- apps/drivers/ets_airspeed/ets_airspeed.cpp | 71 ++++------------------ apps/sdlog/sdlog.c | 17 +++++- apps/sensors/sensors.cpp | 59 ++++++++++++------ apps/uORB/objects_common.cpp | 3 + apps/uORB/topics/differential_pressure.h | 11 ++-- apps/uORB/topics/sensor_combined.h | 2 + 7 files changed, 80 insertions(+), 93 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 7c0a25f862..fcfffcfef7 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -801,7 +801,7 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) struct differential_pressure_s differential_pressure; int calibration_counter = 0; - float airspeed_offset = 0.0f; + float diff_pres_offset = 0.0f; while (calibration_counter < calibration_count) { @@ -812,7 +812,7 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) if (poll_ret) { orb_copy(ORB_ID(differential_pressure), sub_differential_pressure, &differential_pressure); - airspeed_offset += differential_pressure.voltage; + diff_pres_offset += differential_pressure.differential_pressure_pa; calibration_counter++; } else if (poll_ret == 0) { @@ -822,11 +822,11 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) } } - airspeed_offset = airspeed_offset / calibration_count; + diff_pres_offset = diff_pres_offset / calibration_count; - if (isfinite(airspeed_offset)) { + if (isfinite(diff_pres_offset)) { - if (param_set(param_find("SENS_VAIR_OFF"), &(airspeed_offset))) { + if (param_set(param_find("SENS_VAIR_OFF"), &(diff_pres_offset))) { mavlink_log_critical(mavlink_fd, "Setting offs failed!"); } diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 58d016a307..860baa760c 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -61,16 +61,16 @@ #include -#include -#include #include +#include +#include +#include #include #include #include #include -#include /* for baro readings */ #include /* Configuration Constants */ @@ -83,9 +83,6 @@ /* Max measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 10) /* microseconds */ -#define DIFF_PRESSURE_SCALE 1.0 -#define DIFF_PRESSURE_OFFSET 1673 - /* oddly, ERROR is not defined for c++ */ #ifdef ERROR # undef ERROR @@ -96,9 +93,6 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -static int _sensor_sub = -1; - - class ETS_AIRSPEED : public device::I2C { public: @@ -127,6 +121,7 @@ private: bool _sensor_ok; int _measure_ticks; bool _collect_phase; + int _differential_pressure_offset; orb_advert_t _airspeed_pub; @@ -195,7 +190,8 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : _airspeed_pub(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")) + _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")), + _differential_pressure_offset(0) { // enable debug() calls _debug_enabled = true; @@ -239,12 +235,7 @@ ETS_AIRSPEED::init() if (_airspeed_pub < 0) debug("failed to create airspeed sensor object. Did you start uOrb?"); - _sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); - - if (_sensor_sub < 0) { - debug("failed to subscribe to sensor_combined object."); - return ret; - } + param_get(param_find("SENS_VAIR_OFF"), &_differential_pressure_offset); ret = OK; /* sensor is ok, but we don't really know if it is within range */ @@ -462,38 +453,13 @@ ETS_AIRSPEED::collect() } uint16_t diff_pres_pa = val[1] << 8 | val[0]; - //log("val: %0.3f", (float)(diff_pressure)); /* adjust if necessary */ - diff_pres_pa = DIFF_PRESSURE_SCALE * (diff_pres_pa - DIFF_PRESSURE_OFFSET); + diff_pres_pa -= _differential_pressure_offset; //log("measurement: %0.2f m/s", calc_indicated_airspeed((float)_reports[_next_report].diff_pressure)); - - struct sensor_combined_s raw; - memset(&raw, 0, sizeof(raw)); - - bool updated; - orb_check(_sensor_sub, &updated); - if (updated) { - orb_copy(ORB_ID(sensor_combined), _sensor_sub, &raw); - printf("baro temp %3.6f\n", raw.baro_pres_mbar); - } - //if (raw.baro_temp_celcius > 0) - // log("baro temp %3.3f\n", (uint8_t) raw.baro_temp_celcius); - - float airspeed_true = calc_true_airspeed(diff_pres_pa + raw.baro_pres_mbar*1e2f, - raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa - // XXX HACK - true temperature is much less than indicated temperature in baro, - // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB - - float airspeed_indicated = calc_indicated_airspeed(diff_pres_pa); _reports[_next_report].timestamp = hrt_absolute_time(); - _reports[_next_report].static_pressure_mbar = raw.baro_pres_mbar; - _reports[_next_report].differential_pressure_mbar = diff_pres_pa * 1e-2f; - _reports[_next_report].temperature_celcius = raw.baro_temp_celcius; - _reports[_next_report].indicated_airspeed_m_s = airspeed_indicated; - _reports[_next_report].true_airspeed_m_s = airspeed_true; - _reports[_next_report].voltage = 0; + _reports[_next_report].differential_pressure_pa = diff_pres_pa; /* announce the airspeed if needed, just publish else */ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); @@ -512,7 +478,6 @@ ETS_AIRSPEED::collect() ret = OK; -out: perf_end(_sample_perf); return ret; @@ -719,19 +684,7 @@ test() err(1, "immediate read failed"); warnx("single read"); - warnx("diff pressure: %0.3f mbar", report.differential_pressure_mbar); - warnx("indicated airspeed: %0.1f m/s", report.indicated_airspeed_m_s); - warnx("true airspeed: %0.1f m/s", report.true_airspeed_m_s); - - struct sensor_combined_s raw; - memset(&raw, 0, sizeof(raw)); - int sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); - orb_copy(ORB_ID(sensor_combined), sensor_sub, &raw); - - //if (raw.baro_temp_celcius > 0) - // log("baro temp %3.3f\n", (uint8_t) raw.baro_temp_celcius); - warnx("temp: %3.5f", raw.baro_temp_celcius); - warnx("time: %lld", report.timestamp); + warnx("diff pressure: %0.3f pa", (double) report.differential_pressure_pa); /* start the sensor polling at 2Hz */ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) @@ -756,9 +709,7 @@ test() err(1, "periodic read failed"); warnx("periodic read %u", i); - warnx("diff pressure: %0.3f mbar", report.differential_pressure_mbar); - warnx("indicated airspeed: %0.1f m/s", report.indicated_airspeed_m_s); - warnx("true airspeed: %0.1f m/s", report.true_airspeed_m_s); warnx("time: %lld", report.timestamp); + warnx("diff pressure: %0.3f pa", (double) report.differential_pressure_pa); } errx(0, "PASS"); diff --git a/apps/sdlog/sdlog.c b/apps/sdlog/sdlog.c index df8745d9f5..46b232c34d 100644 --- a/apps/sdlog/sdlog.c +++ b/apps/sdlog/sdlog.c @@ -71,6 +71,7 @@ #include #include #include +#include #include @@ -444,6 +445,7 @@ int sdlog_thread_main(int argc, char *argv[]) struct optical_flow_s flow; struct battery_status_s batt; struct differential_pressure_s diff_pressure; + struct airspeed_s airspeed; } buf; memset(&buf, 0, sizeof(buf)); @@ -462,6 +464,7 @@ int sdlog_thread_main(int argc, char *argv[]) int flow_sub; int batt_sub; int diff_pressure_sub; + int airspeed_sub; } subs; /* --- MANAGEMENT - LOGGING COMMAND --- */ @@ -563,6 +566,13 @@ int sdlog_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; + /* --- AIRSPEED --- */ + /* subscribe to ORB for airspeed */ + subs.airspeed_sub = orb_subscribe(ORB_ID(airspeed)); + fds[fdsc_count].fd = subs.airspeed_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* WARNING: If you get the error message below, * then the number of registered messages (fdsc) * differs from the number of messages in the above list. @@ -655,6 +665,7 @@ int sdlog_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos); orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow); orb_copy(ORB_ID(differential_pressure), subs.diff_pressure_sub, &buf.diff_pressure); + orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed); orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt); /* if skipping is on or logging is disabled, ignore */ @@ -691,9 +702,9 @@ int sdlog_thread_main(int argc, char *argv[]) .vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw}, .control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]}, .flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality}, - .diff_pressure = buf.diff_pressure.differential_pressure_mbar, - .ind_airspeed = buf.diff_pressure.indicated_airspeed_m_s, - .true_airspeed = buf.diff_pressure.true_airspeed_m_s + .diff_pressure = buf.diff_pressure.differential_pressure_pa, + .ind_airspeed = buf.airspeed.indicated_airspeed_m_s, + .true_airspeed = buf.airspeed.true_airspeed_m_s }; /* put into buffer for later IO */ diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index d725c7727f..2cf3b92ef7 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -77,6 +77,7 @@ #include #include #include +#include #define GYRO_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */ #define ACC_HEALTH_COUNTER_LIMIT_ERROR 20 /* 40 ms downtime at 500 Hz update rate */ @@ -156,6 +157,8 @@ private: int _mag_sub; /**< raw mag data subscription */ int _rc_sub; /**< raw rc channels data subscription */ int _baro_sub; /**< raw baro data subscription */ + int _airspeed_sub; /**< airspeed subscription */ + int _differential_pressure_sub; /**< raw differential pressure subscription */ int _vstatus_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ int _manual_control_sub; /**< notification of manual control updates */ @@ -165,6 +168,7 @@ private: orb_advert_t _rc_pub; /**< raw r/c control topic */ orb_advert_t _battery_pub; /**< battery status */ orb_advert_t _airspeed_pub; /**< airspeed */ + orb_advert_t _differential_pressure_pub; /**< differential_pressure */ perf_counter_t _loop_perf; /**< loop performance counter */ @@ -172,6 +176,7 @@ private: struct battery_status_s _battery_status; /**< battery status */ struct baro_report _barometer; /**< barometer data */ struct differential_pressure_s _differential_pressure; + struct airspeed_s _airspeed; struct { float min[_rc_max_chan_count]; @@ -330,6 +335,14 @@ private: */ void baro_poll(struct sensor_combined_s &raw); + /** + * Poll the differential pressure sensor for updated data. + * + * @param raw Combined sensor data structure into which + * data should be returned. + */ + void differential_pressure_poll(struct sensor_combined_s &raw); + /** * Check for changes in vehicle status. */ @@ -398,6 +411,7 @@ Sensors::Sensors() : _rc_pub(-1), _battery_pub(-1), _airspeed_pub(-1), + _differential_pressure_pub(-1), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")) @@ -887,6 +901,27 @@ Sensors::baro_poll(struct sensor_combined_s &raw) } } +void +Sensors::differential_pressure_poll(struct sensor_combined_s &raw) +{ + bool updated; + orb_check(_differential_pressure_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(differential_pressure), _differential_pressure_sub, &_differential_pressure); + + float airspeed_true = calc_true_airspeed(_differential_pressure.differential_pressure_pa + raw.baro_pres_mbar*1e2f, + raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa + // XXX HACK - true temperature is much less than indicated temperature in baro, + // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB + + float airspeed_indicated = calc_indicated_airspeed(_differential_pressure.differential_pressure_pa); + + raw.differential_pressure_pa = _differential_pressure.differential_pressure_pa; + raw.differential_pressure_counter++; + } +} + void Sensors::vehicle_status_poll() { @@ -1045,31 +1080,18 @@ Sensors::adc_poll(struct sensor_combined_s &raw) */ if (voltage > 0.4f) { - float diff_pres_pa = (voltage - _parameters.airspeed_offset) * 1000.0f; //for MPXV7002DP sensor - - float airspeed_true = calc_true_airspeed(diff_pres_pa + _barometer.pressure*1e2f, - _barometer.pressure*1e2f, _barometer.temperature - 5.0f); //factor 1e2 for conversion from mBar to Pa - // XXX HACK - true temperature is much less than indicated temperature in baro, - // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB - - float airspeed_indicated = calc_indicated_airspeed(diff_pres_pa); - - //printf("voltage: %.4f, diff_pres_pa %.4f, baro press %.4f Pa, v_ind %.4f, v_true %.4f\n", (double)voltage, (double)diff_pres_pa, (double)_barometer.pressure*1e2f, (double)airspeed_indicated, (double)airspeed_true); + float diff_pres_pa = voltage * 1000.0f - _parameters.airspeed_offset; //for MPXV7002DP sensor _differential_pressure.timestamp = hrt_absolute_time(); - _differential_pressure.static_pressure_mbar = _barometer.pressure; - _differential_pressure.differential_pressure_mbar = diff_pres_pa*1e-2f; - _differential_pressure.temperature_celcius = _barometer.temperature; - _differential_pressure.indicated_airspeed_m_s = airspeed_indicated; - _differential_pressure.true_airspeed_m_s = airspeed_true; + _differential_pressure.differential_pressure_pa = diff_pres_pa; _differential_pressure.voltage = voltage; /* announce the airspeed if needed, just publish else */ - if (_airspeed_pub > 0) { - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_differential_pressure); + if (_differential_pressure_pub > 0) { + orb_publish(ORB_ID(differential_pressure), _differential_pressure_pub, &_differential_pressure); } else { - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &_differential_pressure); + _differential_pressure_pub = orb_advertise(ORB_ID(differential_pressure), &_differential_pressure); } } } @@ -1334,6 +1356,7 @@ Sensors::task_main() gyro_poll(raw); mag_poll(raw); baro_poll(raw); + differential_pressure_poll(raw); parameter_update_poll(true /* forced */); diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp index 1363751401..4197f6fb2d 100644 --- a/apps/uORB/objects_common.cpp +++ b/apps/uORB/objects_common.cpp @@ -122,6 +122,9 @@ ORB_DEFINE(optical_flow, struct optical_flow_s); #include "topics/omnidirectional_flow.h" ORB_DEFINE(omnidirectional_flow, struct omnidirectional_flow_s); +#include "topics/airspeed.h" +ORB_DEFINE(airspeed, struct airspeed_s); + #include "topics/differential_pressure.h" ORB_DEFINE(differential_pressure, struct differential_pressure_s); diff --git a/apps/uORB/topics/differential_pressure.h b/apps/uORB/topics/differential_pressure.h index d5e4bf37ef..ac52206192 100644 --- a/apps/uORB/topics/differential_pressure.h +++ b/apps/uORB/topics/differential_pressure.h @@ -49,16 +49,13 @@ */ /** - * Differential pressure and airspeed + * Differential pressure. */ struct differential_pressure_s { uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ - float static_pressure_mbar; /**< Static / environment pressure */ - float differential_pressure_mbar; /**< Differential pressure reading */ - float temperature_celcius; /**< ambient temperature in celcius, -1 if unknown */ - float indicated_airspeed_m_s; /**< indicated airspeed in meters per second, -1 if unknown */ - float true_airspeed_m_s; /**< true airspeed in meters per second, -1 if unknown */ - float voltage; /**< Voltage from the airspeed sensor (voltage divider already compensated) */ + float differential_pressure_pa; /**< Differential pressure reading */ + float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */ + }; /** diff --git a/apps/uORB/topics/sensor_combined.h b/apps/uORB/topics/sensor_combined.h index 961ee8b4a6..ad88e4b6e1 100644 --- a/apps/uORB/topics/sensor_combined.h +++ b/apps/uORB/topics/sensor_combined.h @@ -103,6 +103,8 @@ struct sensor_combined_s { float mcu_temp_celcius; /**< Internal temperature measurement of MCU */ uint32_t baro_counter; /**< Number of raw baro measurements taken */ + float differential_pressure_pa; /**< Airspeed sensor differential pressure */ + uint32_t differential_pressure_counter; /**< Number of raw differential pressure measurements taken */ }; /** From 696e48fbf38de9d0ac12494cb2749ba3b04f852f Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 19 Apr 2013 18:28:06 +0200 Subject: [PATCH 008/102] Cleanup variable names and such --- apps/commander/commander.c | 30 ++++++++-------- apps/drivers/ets_airspeed/ets_airspeed.cpp | 8 ++--- apps/sdlog/sdlog.c | 12 +++---- apps/sensors/sensor_params.c | 2 +- apps/sensors/sensors.cpp | 40 +++++++++++----------- apps/uORB/topics/sensor_combined.h | 2 +- 6 files changed, 47 insertions(+), 47 deletions(-) diff --git a/apps/commander/commander.c b/apps/commander/commander.c index fcfffcfef7..2980ab118e 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -797,8 +797,8 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) const int calibration_count = 2500; - int sub_differential_pressure = orb_subscribe(ORB_ID(differential_pressure)); - struct differential_pressure_s differential_pressure; + int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); + struct differential_pressure_s diff_pres; int calibration_counter = 0; float diff_pres_offset = 0.0f; @@ -806,13 +806,13 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) while (calibration_counter < calibration_count) { /* wait blocking for new data */ - struct pollfd fds[1] = { { .fd = sub_differential_pressure, .events = POLLIN } }; + struct pollfd fds[1] = { { .fd = diff_pres_sub, .events = POLLIN } }; int poll_ret = poll(fds, 1, 1000); if (poll_ret) { - orb_copy(ORB_ID(differential_pressure), sub_differential_pressure, &differential_pressure); - diff_pres_offset += differential_pressure.differential_pressure_pa; + orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); + diff_pres_offset += diff_pres.differential_pressure_pa; calibration_counter++; } else if (poll_ret == 0) { @@ -826,7 +826,7 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) if (isfinite(diff_pres_offset)) { - if (param_set(param_find("SENS_VAIR_OFF"), &(diff_pres_offset))) { + if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { mavlink_log_critical(mavlink_fd, "Setting offs failed!"); } @@ -856,7 +856,7 @@ void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) status->flag_preflight_airspeed_calibration = false; state_machine_publish(status_pub, status, mavlink_fd); - close(sub_differential_pressure); + close(diff_pres_sub); } @@ -1477,10 +1477,10 @@ int commander_thread_main(int argc, char *argv[]) struct sensor_combined_s sensors; memset(&sensors, 0, sizeof(sensors)); - int differential_pressure_sub = orb_subscribe(ORB_ID(differential_pressure)); - struct differential_pressure_s differential_pressure; - memset(&differential_pressure, 0, sizeof(differential_pressure)); - uint64_t last_differential_pressure_time = 0; + int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); + struct differential_pressure_s diff_pres; + memset(&diff_pres, 0, sizeof(diff_pres)); + uint64_t last_diff_pres_time = 0; /* Subscribe to command topic */ int cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); @@ -1535,11 +1535,11 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors); } - orb_check(differential_pressure_sub, &new_data); + orb_check(diff_pres_sub, &new_data); if (new_data) { - orb_copy(ORB_ID(differential_pressure), differential_pressure_sub, &differential_pressure); - last_differential_pressure_time = differential_pressure.timestamp; + orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); + last_diff_pres_time = diff_pres.timestamp; } orb_check(cmd_sub, &new_data); @@ -1754,7 +1754,7 @@ int commander_thread_main(int argc, char *argv[]) } /* Check for valid airspeed/differential pressure measurements */ - if (hrt_absolute_time() - last_differential_pressure_time < 2000000) { + if (hrt_absolute_time() - last_diff_pres_time < 2000000) { current_status.flag_airspeed_valid = true; } else { diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 860baa760c..943848d438 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -121,7 +121,7 @@ private: bool _sensor_ok; int _measure_ticks; bool _collect_phase; - int _differential_pressure_offset; + int _diff_pres_offset; orb_advert_t _airspeed_pub; @@ -191,7 +191,7 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")), - _differential_pressure_offset(0) + _diff_pres_offset(0) { // enable debug() calls _debug_enabled = true; @@ -235,7 +235,7 @@ ETS_AIRSPEED::init() if (_airspeed_pub < 0) debug("failed to create airspeed sensor object. Did you start uOrb?"); - param_get(param_find("SENS_VAIR_OFF"), &_differential_pressure_offset); + param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); ret = OK; /* sensor is ok, but we don't really know if it is within range */ @@ -455,7 +455,7 @@ ETS_AIRSPEED::collect() uint16_t diff_pres_pa = val[1] << 8 | val[0]; /* adjust if necessary */ - diff_pres_pa -= _differential_pressure_offset; + diff_pres_pa -= _diff_pres_offset; //log("measurement: %0.2f m/s", calc_indicated_airspeed((float)_reports[_next_report].diff_pressure)); _reports[_next_report].timestamp = hrt_absolute_time(); diff --git a/apps/sdlog/sdlog.c b/apps/sdlog/sdlog.c index 46b232c34d..84a9eb6ac5 100644 --- a/apps/sdlog/sdlog.c +++ b/apps/sdlog/sdlog.c @@ -444,7 +444,7 @@ int sdlog_thread_main(int argc, char *argv[]) struct vehicle_vicon_position_s vicon_pos; struct optical_flow_s flow; struct battery_status_s batt; - struct differential_pressure_s diff_pressure; + struct differential_pressure_s diff_pres; struct airspeed_s airspeed; } buf; memset(&buf, 0, sizeof(buf)); @@ -463,7 +463,7 @@ int sdlog_thread_main(int argc, char *argv[]) int vicon_pos_sub; int flow_sub; int batt_sub; - int diff_pressure_sub; + int diff_pres_sub; int airspeed_sub; } subs; @@ -561,8 +561,8 @@ int sdlog_thread_main(int argc, char *argv[]) /* --- DIFFERENTIAL PRESSURE --- */ /* subscribe to ORB for flow measurements */ - subs.diff_pressure_sub = orb_subscribe(ORB_ID(differential_pressure)); - fds[fdsc_count].fd = subs.diff_pressure_sub; + subs.diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); + fds[fdsc_count].fd = subs.diff_pres_sub; fds[fdsc_count].events = POLLIN; fdsc_count++; @@ -664,7 +664,7 @@ int sdlog_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(vehicle_attitude), subs.att_sub, &buf.att); orb_copy(ORB_ID(vehicle_vicon_position), subs.vicon_pos_sub, &buf.vicon_pos); orb_copy(ORB_ID(optical_flow), subs.flow_sub, &buf.flow); - orb_copy(ORB_ID(differential_pressure), subs.diff_pressure_sub, &buf.diff_pressure); + orb_copy(ORB_ID(differential_pressure), subs.diff_pres_sub, &buf.diff_pres); orb_copy(ORB_ID(airspeed), subs.airspeed_sub, &buf.airspeed); orb_copy(ORB_ID(battery_status), subs.batt_sub, &buf.batt); @@ -702,7 +702,7 @@ int sdlog_thread_main(int argc, char *argv[]) .vicon = {buf.vicon_pos.x, buf.vicon_pos.y, buf.vicon_pos.z, buf.vicon_pos.roll, buf.vicon_pos.pitch, buf.vicon_pos.yaw}, .control_effective = {buf.act_controls_effective.control_effective[0], buf.act_controls_effective.control_effective[1], buf.act_controls_effective.control_effective[2], buf.act_controls_effective.control_effective[3]}, .flow = {buf.flow.flow_raw_x, buf.flow.flow_raw_y, buf.flow.flow_comp_x_m, buf.flow.flow_comp_y_m, buf.flow.ground_distance_m, buf.flow.quality}, - .diff_pressure = buf.diff_pressure.differential_pressure_pa, + .diff_pressure = buf.diff_pres.differential_pressure_pa, .ind_airspeed = buf.airspeed.indicated_airspeed_m_s, .true_airspeed = buf.airspeed.true_airspeed_m_s }; diff --git a/apps/sensors/sensor_params.c b/apps/sensors/sensor_params.c index a1ef9d136e..da2dfcca67 100644 --- a/apps/sensors/sensor_params.c +++ b/apps/sensors/sensor_params.c @@ -64,7 +64,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); -PARAM_DEFINE_FLOAT(SENS_VAIR_OFF, 2.5f); +PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 2.5f); PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index 2cf3b92ef7..ab8818b40c 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -158,7 +158,7 @@ private: int _rc_sub; /**< raw rc channels data subscription */ int _baro_sub; /**< raw baro data subscription */ int _airspeed_sub; /**< airspeed subscription */ - int _differential_pressure_sub; /**< raw differential pressure subscription */ + int _diff_pres_sub; /**< raw differential pressure subscription */ int _vstatus_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ int _manual_control_sub; /**< notification of manual control updates */ @@ -168,14 +168,14 @@ private: orb_advert_t _rc_pub; /**< raw r/c control topic */ orb_advert_t _battery_pub; /**< battery status */ orb_advert_t _airspeed_pub; /**< airspeed */ - orb_advert_t _differential_pressure_pub; /**< differential_pressure */ + orb_advert_t _diff_pres_pub; /**< differential_pressure */ perf_counter_t _loop_perf; /**< loop performance counter */ struct rc_channels_s _rc; /**< r/c channel data */ struct battery_status_s _battery_status; /**< battery status */ struct baro_report _barometer; /**< barometer data */ - struct differential_pressure_s _differential_pressure; + struct differential_pressure_s _diff_pres; struct airspeed_s _airspeed; struct { @@ -341,7 +341,7 @@ private: * @param raw Combined sensor data structure into which * data should be returned. */ - void differential_pressure_poll(struct sensor_combined_s &raw); + void diff_pres_poll(struct sensor_combined_s &raw); /** * Check for changes in vehicle status. @@ -411,7 +411,7 @@ Sensors::Sensors() : _rc_pub(-1), _battery_pub(-1), _airspeed_pub(-1), - _differential_pressure_pub(-1), + _diff_pres_pub(-1), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "sensor task update")) @@ -496,8 +496,8 @@ Sensors::Sensors() : _parameter_handles.mag_scale[1] = param_find("SENS_MAG_YSCALE"); _parameter_handles.mag_scale[2] = param_find("SENS_MAG_ZSCALE"); - /*Airspeed offset */ - _parameter_handles.airspeed_offset = param_find("SENS_VAIR_OFF"); + /* Differential pressure offset */ + _parameter_handles.airspeed_offset = param_find("SENS_DPRES_OFF"); _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); @@ -902,22 +902,22 @@ Sensors::baro_poll(struct sensor_combined_s &raw) } void -Sensors::differential_pressure_poll(struct sensor_combined_s &raw) +Sensors::diff_pres_poll(struct sensor_combined_s &raw) { bool updated; - orb_check(_differential_pressure_sub, &updated); + orb_check(_diff_pres_sub, &updated); if (updated) { - orb_copy(ORB_ID(differential_pressure), _differential_pressure_sub, &_differential_pressure); + orb_copy(ORB_ID(differential_pressure), _diff_pres_sub, &_diff_pres); - float airspeed_true = calc_true_airspeed(_differential_pressure.differential_pressure_pa + raw.baro_pres_mbar*1e2f, + float airspeed_true = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f, raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa // XXX HACK - true temperature is much less than indicated temperature in baro, // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB - float airspeed_indicated = calc_indicated_airspeed(_differential_pressure.differential_pressure_pa); + float airspeed_indicated = calc_indicated_airspeed(_diff_pres.differential_pressure_pa); - raw.differential_pressure_pa = _differential_pressure.differential_pressure_pa; + raw.differential_pressure_pa = _diff_pres.differential_pressure_pa; raw.differential_pressure_counter++; } } @@ -1082,16 +1082,16 @@ Sensors::adc_poll(struct sensor_combined_s &raw) float diff_pres_pa = voltage * 1000.0f - _parameters.airspeed_offset; //for MPXV7002DP sensor - _differential_pressure.timestamp = hrt_absolute_time(); - _differential_pressure.differential_pressure_pa = diff_pres_pa; - _differential_pressure.voltage = voltage; + _diff_pres.timestamp = hrt_absolute_time(); + _diff_pres.differential_pressure_pa = diff_pres_pa; + _diff_pres.voltage = voltage; /* announce the airspeed if needed, just publish else */ - if (_differential_pressure_pub > 0) { - orb_publish(ORB_ID(differential_pressure), _differential_pressure_pub, &_differential_pressure); + if (_diff_pres_pub > 0) { + orb_publish(ORB_ID(differential_pressure), _diff_pres_pub, &_diff_pres); } else { - _differential_pressure_pub = orb_advertise(ORB_ID(differential_pressure), &_differential_pressure); + _diff_pres_pub = orb_advertise(ORB_ID(differential_pressure), &_diff_pres); } } } @@ -1356,7 +1356,7 @@ Sensors::task_main() gyro_poll(raw); mag_poll(raw); baro_poll(raw); - differential_pressure_poll(raw); + diff_pres_poll(raw); parameter_update_poll(true /* forced */); diff --git a/apps/uORB/topics/sensor_combined.h b/apps/uORB/topics/sensor_combined.h index ad88e4b6e1..9a76b51829 100644 --- a/apps/uORB/topics/sensor_combined.h +++ b/apps/uORB/topics/sensor_combined.h @@ -103,7 +103,7 @@ struct sensor_combined_s { float mcu_temp_celcius; /**< Internal temperature measurement of MCU */ uint32_t baro_counter; /**< Number of raw baro measurements taken */ - float differential_pressure_pa; /**< Airspeed sensor differential pressure */ + float differential_pressure_pa; /**< Airspeed sensor differential pressure */ uint32_t differential_pressure_counter; /**< Number of raw differential pressure measurements taken */ }; From 853ba612b132f0a8f41fae1dbadc68ef3960f0d0 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 19 Apr 2013 18:28:47 +0200 Subject: [PATCH 009/102] Add missing uORB topic --- apps/uORB/topics/airspeed.h | 67 +++++++++++++++++++++++++++++++++++++ 1 file changed, 67 insertions(+) create mode 100644 apps/uORB/topics/airspeed.h diff --git a/apps/uORB/topics/airspeed.h b/apps/uORB/topics/airspeed.h new file mode 100644 index 0000000000..a3da3758fd --- /dev/null +++ b/apps/uORB/topics/airspeed.h @@ -0,0 +1,67 @@ +/**************************************************************************** + * + * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file airspeed.h + * + * Definition of airspeed topic + */ + +#ifndef TOPIC_AIRSPEED_H_ +#define TOPIC_AIRSPEED_H_ + +#include "../uORB.h" +#include + +/** + * @addtogroup topics + * @{ + */ + +/** + * Airspeed + */ +struct airspeed_s { + uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ + float indicated_airspeed_m_s; /**< indicated airspeed in meters per second, -1 if unknown */ + float true_airspeed_m_s; /**< true airspeed in meters per second, -1 if unknown */ +}; + +/** + * @} + */ + +/* register this as object request broker structure */ +ORB_DECLARE(airspeed); + +#endif From 48f815860b5900f3770486d88aea9084c75441e0 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Sun, 21 Apr 2013 01:29:07 +0200 Subject: [PATCH 010/102] Debugging, cleanup and added airspeed to HoTT telemetry. --- apps/drivers/ets_airspeed/ets_airspeed.cpp | 31 ++++++++++++++++------ apps/hott_telemetry/messages.c | 12 +++++++++ apps/sensors/sensor_params.c | 2 +- apps/sensors/sensors.cpp | 30 +++++++++++++++------ apps/uORB/topics/differential_pressure.h | 7 ++--- 5 files changed, 62 insertions(+), 20 deletions(-) diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 943848d438..276f4bf593 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -81,7 +81,11 @@ #define READ_CMD 0x07 /* Read the data */ /* Max measurement rate is 100Hz */ -#define CONVERSION_INTERVAL (1000000 / 10) /* microseconds */ +#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ + +/* The Eagle Tree Airspeed V3 can only provide accurate readings + for speeds from 15km/h upwards. */ +#define MIN_ACCURATE_DIFF_PRES_PA 12 /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -222,6 +226,8 @@ ETS_AIRSPEED::init() /* allocate basic report buffers */ _num_reports = 2; _reports = new struct differential_pressure_s[_num_reports]; + for (int i = 0; i < _num_reports; i++) + _reports[i].max_differential_pressure_pa = 0; if (_reports == nullptr) goto out; @@ -235,8 +241,6 @@ ETS_AIRSPEED::init() if (_airspeed_pub < 0) debug("failed to create airspeed sensor object. Did you start uOrb?"); - param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); - ret = OK; /* sensor is ok, but we don't really know if it is within range */ _sensor_ok = true; @@ -454,13 +458,24 @@ ETS_AIRSPEED::collect() uint16_t diff_pres_pa = val[1] << 8 | val[0]; - /* adjust if necessary */ - diff_pres_pa -= _diff_pres_offset; - //log("measurement: %0.2f m/s", calc_indicated_airspeed((float)_reports[_next_report].diff_pressure)); + param_get(param_find("SENS_DPRES_OFF"), &_diff_pres_offset); + if (diff_pres_pa < _diff_pres_offset + MIN_ACCURATE_DIFF_PRES_PA) { + diff_pres_pa = 0; + } else { + diff_pres_pa -= _diff_pres_offset; + } + + // XXX we may want to smooth out the readings to remove noise. + _reports[_next_report].timestamp = hrt_absolute_time(); _reports[_next_report].differential_pressure_pa = diff_pres_pa; + // Track maximum differential pressure measured (so we can work out top speed). + if (diff_pres_pa > _reports[_next_report].max_differential_pressure_pa) { + _reports[_next_report].max_differential_pressure_pa = diff_pres_pa; + } + /* announce the airspeed if needed, just publish else */ orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &_reports[_next_report]); @@ -684,7 +699,7 @@ test() err(1, "immediate read failed"); warnx("single read"); - warnx("diff pressure: %0.3f pa", (double) report.differential_pressure_pa); + warnx("diff pressure: %d pa", report.differential_pressure_pa); /* start the sensor polling at 2Hz */ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) @@ -709,7 +724,7 @@ test() err(1, "periodic read failed"); warnx("periodic read %u", i); - warnx("diff pressure: %0.3f pa", (double) report.differential_pressure_pa); + warnx("diff pressure: %d pa", report.differential_pressure_pa); } errx(0, "PASS"); diff --git a/apps/hott_telemetry/messages.c b/apps/hott_telemetry/messages.c index 8bfb997737..0e466e8209 100644 --- a/apps/hott_telemetry/messages.c +++ b/apps/hott_telemetry/messages.c @@ -42,9 +42,11 @@ #include #include #include +#include #include #include +static int airspeed_sub = -1; static int battery_sub = -1; static int sensor_sub = -1; @@ -52,6 +54,7 @@ void messages_init(void) { battery_sub = orb_subscribe(ORB_ID(battery_status)); sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); + airspeed_sub = orb_subscribe(ORB_ID(airspeed)); } void build_eam_response(uint8_t *buffer, int *size) @@ -81,6 +84,15 @@ void build_eam_response(uint8_t *buffer, int *size) msg.altitude_L = (uint8_t)alt & 0xff; msg.altitude_H = (uint8_t)(alt >> 8) & 0xff; + /* get a local copy of the current sensor values */ + struct airspeed_s airspeed; + memset(&airspeed, 0, sizeof(airspeed)); + orb_copy(ORB_ID(airspeed), airspeed_sub, &airspeed); + + uint16_t speed = (uint16_t)(airspeed.indicated_airspeed_m_s * 3.6); + msg.speed_L = (uint8_t)speed & 0xff; + msg.speed_H = (uint8_t)(speed >> 8) & 0xff; + msg.stop = STOP_BYTE; memcpy(buffer, &msg, *size); diff --git a/apps/sensors/sensor_params.c b/apps/sensors/sensor_params.c index da2dfcca67..0bab992a78 100644 --- a/apps/sensors/sensor_params.c +++ b/apps/sensors/sensor_params.c @@ -64,7 +64,7 @@ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); -PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 2.5f); +PARAM_DEFINE_INT32(SENS_DPRES_OFF, 1667); PARAM_DEFINE_FLOAT(RC1_MIN, 1000.0f); PARAM_DEFINE_FLOAT(RC1_TRIM, 1500.0f); diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index ab8818b40c..fcd1d869f9 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -192,7 +192,7 @@ private: float mag_scale[3]; float accel_offset[3]; float accel_scale[3]; - float airspeed_offset; + int diff_pres_offset_pa; int rc_type; @@ -241,7 +241,7 @@ private: param_t accel_scale[3]; param_t mag_offset[3]; param_t mag_scale[3]; - param_t airspeed_offset; + param_t diff_pres_offset_pa; param_t rc_map_roll; param_t rc_map_pitch; @@ -497,7 +497,7 @@ Sensors::Sensors() : _parameter_handles.mag_scale[2] = param_find("SENS_MAG_ZSCALE"); /* Differential pressure offset */ - _parameter_handles.airspeed_offset = param_find("SENS_DPRES_OFF"); + _parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF"); _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); @@ -707,7 +707,7 @@ Sensors::parameters_update() param_get(_parameter_handles.mag_scale[2], &(_parameters.mag_scale[2])); /* Airspeed offset */ - param_get(_parameter_handles.airspeed_offset, &(_parameters.airspeed_offset)); + param_get(_parameter_handles.diff_pres_offset_pa, &(_parameters.diff_pres_offset_pa)); /* scaling of ADC ticks to battery voltage */ if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) { @@ -910,15 +910,26 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw) if (updated) { orb_copy(ORB_ID(differential_pressure), _diff_pres_sub, &_diff_pres); + raw.differential_pressure_pa = _diff_pres.differential_pressure_pa; + raw.differential_pressure_counter++; + float airspeed_true = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f, raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa // XXX HACK - true temperature is much less than indicated temperature in baro, // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB float airspeed_indicated = calc_indicated_airspeed(_diff_pres.differential_pressure_pa); - - raw.differential_pressure_pa = _diff_pres.differential_pressure_pa; - raw.differential_pressure_counter++; + + _airspeed.indicated_airspeed_m_s = airspeed_indicated; + _airspeed.true_airspeed_m_s = airspeed_true; + + /* announce the airspeed if needed, just publish else */ + if (_airspeed_pub > 0) { + orb_publish(ORB_ID(airspeed), _airspeed_pub, &_airspeed); + + } else { + _airspeed_pub = orb_advertise(ORB_ID(airspeed), &_airspeed); + } } } @@ -1080,7 +1091,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw) */ if (voltage > 0.4f) { - float diff_pres_pa = voltage * 1000.0f - _parameters.airspeed_offset; //for MPXV7002DP sensor + float diff_pres_pa = voltage * 1000.0f - _parameters.diff_pres_offset_pa; //for MPXV7002DP sensor _diff_pres.timestamp = hrt_absolute_time(); _diff_pres.differential_pressure_pa = diff_pres_pa; @@ -1330,6 +1341,7 @@ Sensors::task_main() _mag_sub = orb_subscribe(ORB_ID(sensor_mag)); _rc_sub = orb_subscribe(ORB_ID(input_rc)); _baro_sub = orb_subscribe(ORB_ID(sensor_baro)); + _diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _manual_control_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); @@ -1405,6 +1417,8 @@ Sensors::task_main() /* check battery voltage */ adc_poll(raw); + diff_pres_poll(raw); + /* Inform other processes that new data is available to copy */ if (_publishing) orb_publish(ORB_ID(sensor_combined), _sensor_pub, &raw); diff --git a/apps/uORB/topics/differential_pressure.h b/apps/uORB/topics/differential_pressure.h index ac52206192..8ce85213be 100644 --- a/apps/uORB/topics/differential_pressure.h +++ b/apps/uORB/topics/differential_pressure.h @@ -52,9 +52,10 @@ * Differential pressure. */ struct differential_pressure_s { - uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ - float differential_pressure_pa; /**< Differential pressure reading */ - float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */ + uint64_t timestamp; /**< microseconds since system boot, needed to integrate */ + uint16_t differential_pressure_pa; /**< Differential pressure reading */ + uint16_t max_differential_pressure_pa; /**< Maximum differential pressure reading */ + float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */ }; From 715e3e2ebe0546edfa8c053ff90f4f1fdc521da7 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Mon, 22 Apr 2013 08:51:49 +0200 Subject: [PATCH 011/102] Cleanup --- apps/drivers/drv_airspeed.h | 14 -------------- apps/drivers/ets_airspeed/ets_airspeed.cpp | 17 ++++++++++------- apps/sensors/sensors.cpp | 18 +++++++++--------- 3 files changed, 19 insertions(+), 30 deletions(-) diff --git a/apps/drivers/drv_airspeed.h b/apps/drivers/drv_airspeed.h index 269ee45591..54213c0754 100644 --- a/apps/drivers/drv_airspeed.h +++ b/apps/drivers/drv_airspeed.h @@ -46,20 +46,6 @@ #define AIRSPEED_DEVICE_PATH "/dev/airspeed" -/** - * Airspeed report structure. Reads from the device must be in multiples of this - * structure. - */ -//struct airspeed_report { -// uint64_t timestamp; -// uint8_t diff_pressure; /** differential pressure in Pa */ -//}; - -/* - * ObjDev tag for raw range finder data. - */ -//ORB_DECLARE(sensor_differential_pressure); - /* * ioctl() definitions * diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 276f4bf593..88e0fbb13f 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -74,20 +74,22 @@ #include /* Configuration Constants */ -#define I2C_BUS PX4_I2C_BUS_ESC +#define I2C_BUS PX4_I2C_BUS_ESC // XXX Replace with PX4_I2C_BUS_EXPANSION before submitting. #define I2C_ADDRESS 0x75 /* ETS_AIRSPEED Registers addresses */ #define READ_CMD 0x07 /* Read the data */ -/* Max measurement rate is 100Hz */ +/* Measurement rate is 100Hz */ #define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ -/* The Eagle Tree Airspeed V3 can only provide accurate readings - for speeds from 15km/h upwards. */ +/** + * The Eagle Tree Airspeed V3 can only provide accurate readings + * for speeds from 15km/h upwards. + */ #define MIN_ACCURATE_DIFF_PRES_PA 12 -/* oddly, ERROR is not defined for c++ */ +/* Oddly, ERROR is not defined for C++ */ #ifdef ERROR # undef ERROR #endif @@ -109,8 +111,8 @@ public: virtual int ioctl(struct file *filp, int cmd, unsigned long arg); /** - * Diagnostics - print some basic information about the driver. - */ + * Diagnostics - print some basic information about the driver. + */ void print_info(); protected: @@ -163,6 +165,7 @@ private: void cycle(); int measure(); int collect(); + /** * Static trampoline from the workq context; because we don't have a * generic workq wrapper yet. diff --git a/apps/sensors/sensors.cpp b/apps/sensors/sensors.cpp index fcd1d869f9..8b6f184737 100644 --- a/apps/sensors/sensors.cpp +++ b/apps/sensors/sensors.cpp @@ -99,6 +99,12 @@ #define BAT_VOL_LOWPASS_2 0.01f #define VOLTAGE_BATTERY_IGNORE_THRESHOLD_VOLTS 3.5f +/** + * HACK - true temperature is much less than indicated temperature in baro, + * subtract 5 degrees in an attempt to account for the electrical upheating of the PCB + */ +#define PCB_TEMP_ESTIMATE_DEG 5.0f + #define PPM_INPUT_TIMEOUT_INTERVAL 50000 /**< 50 ms timeout / 20 Hz */ #define limit_minus_one_to_one(arg) (arg < -1.0f) ? -1.0f : ((arg > 1.0f) ? 1.0f : arg) @@ -913,15 +919,9 @@ Sensors::diff_pres_poll(struct sensor_combined_s &raw) raw.differential_pressure_pa = _diff_pres.differential_pressure_pa; raw.differential_pressure_counter++; - float airspeed_true = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f, - raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - 5.0f); //factor 1e2 for conversion from mBar to Pa - // XXX HACK - true temperature is much less than indicated temperature in baro, - // subtract 5 degrees in an attempt to account for the electrical upheating of the PCB - - float airspeed_indicated = calc_indicated_airspeed(_diff_pres.differential_pressure_pa); - - _airspeed.indicated_airspeed_m_s = airspeed_indicated; - _airspeed.true_airspeed_m_s = airspeed_true; + _airspeed.indicated_airspeed_m_s = calc_indicated_airspeed(_diff_pres.differential_pressure_pa); + _airspeed.true_airspeed_m_s = calc_true_airspeed(_diff_pres.differential_pressure_pa + raw.baro_pres_mbar*1e2f, + raw.baro_pres_mbar*1e2f, raw.baro_temp_celcius - PCB_TEMP_ESTIMATE_DEG); /* announce the airspeed if needed, just publish else */ if (_airspeed_pub > 0) { From ad212ee628cd08c5c063757e4a5a2edc82392f3b Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Mon, 22 Apr 2013 15:00:15 +0200 Subject: [PATCH 012/102] More cleanups --- apps/drivers/ets_airspeed/ets_airspeed.cpp | 65 +++++++++++++++------- 1 file changed, 45 insertions(+), 20 deletions(-) diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 88e0fbb13f..cede0534d1 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -73,22 +73,23 @@ #include #include -/* Configuration Constants */ -#define I2C_BUS PX4_I2C_BUS_ESC // XXX Replace with PX4_I2C_BUS_EXPANSION before submitting. -#define I2C_ADDRESS 0x75 +/* Default I2C bus */ +#define PX4_I2C_BUS_DEFAULT PX4_I2C_BUS_EXPANSION -/* ETS_AIRSPEED Registers addresses */ -#define READ_CMD 0x07 /* Read the data */ +/* I2C bus address */ +#define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ + +/* Register address */ +#define READ_CMD 0x07 /* Read the data */ -/* Measurement rate is 100Hz */ -#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ - /** - * The Eagle Tree Airspeed V3 can only provide accurate readings - * for speeds from 15km/h upwards. + * The Eagle Tree Airspeed V3 cannot provide accurate reading below speeds of 15km/h. */ #define MIN_ACCURATE_DIFF_PRES_PA 12 +/* Measurement rate is 100Hz */ +#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ + /* Oddly, ERROR is not defined for C++ */ #ifdef ERROR # undef ERROR @@ -102,7 +103,7 @@ static const int ERROR = -1; class ETS_AIRSPEED : public device::I2C { public: - ETS_AIRSPEED(int bus = I2C_BUS, int address = I2C_ADDRESS); + ETS_AIRSPEED(int bus, int address = I2C_ADDRESS); virtual ~ETS_AIRSPEED(); virtual int init(); @@ -194,11 +195,11 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), + _diff_pres_offset(0), _airspeed_pub(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")), - _diff_pres_offset(0) + _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")) { // enable debug() calls _debug_enabled = true; @@ -229,7 +230,7 @@ ETS_AIRSPEED::init() /* allocate basic report buffers */ _num_reports = 2; _reports = new struct differential_pressure_s[_num_reports]; - for (int i = 0; i < _num_reports; i++) + for (unsigned i = 0; i < _num_reports; i++) _reports[i].max_differential_pressure_pa = 0; if (_reports == nullptr) @@ -613,7 +614,7 @@ const int ERROR = -1; ETS_AIRSPEED *g_dev; -void start(); +void start(int i2c_bus); void stop(); void test(); void reset(); @@ -623,7 +624,7 @@ void info(); * Start the driver. */ void -start() +start(int i2c_bus) { int fd; @@ -631,7 +632,7 @@ start() errx(1, "already started"); /* create the driver */ - g_dev = new ETS_AIRSPEED(I2C_BUS); + g_dev = new ETS_AIRSPEED(i2c_bus); if (g_dev == nullptr) goto fail; @@ -664,7 +665,8 @@ fail: /** * Stop the driver */ -void stop() +void +stop() { if (g_dev != nullptr) { @@ -770,14 +772,36 @@ info() } // namespace + +static void +ets_airspeed_usage() +{ + fprintf(stderr, "usage: ets_airspeed [options] command\n"); + fprintf(stderr, "options:\n"); + fprintf(stderr, "\t-b --bus i2cbus (%d)\n", PX4_I2C_BUS_DEFAULT); + fprintf(stderr, "command:\n"); + fprintf(stderr, "\tstart|stop|reset|test|info\n"); +} + int ets_airspeed_main(int argc, char *argv[]) { + int i2c_bus = PX4_I2C_BUS_DEFAULT; + + int i; + for (i = 1; i < argc; i++) { + if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { + if (argc > i + 1) { + i2c_bus = atoi(argv[i + 1]); + } + } + } + /* * Start/load the driver. */ if (!strcmp(argv[1], "start")) - ets_airspeed::start(); + ets_airspeed::start(i2c_bus); /* * Stop the driver @@ -803,5 +827,6 @@ ets_airspeed_main(int argc, char *argv[]) if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) ets_airspeed::info(); - errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); + ets_airspeed_usage(); + exit(0); } From 24630f15b6d0b465bd62f1105def4e96ffc92e10 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Mon, 22 Apr 2013 21:30:20 +0200 Subject: [PATCH 013/102] Yet more cleanups. --- apps/drivers/drv_airspeed.h | 1 + apps/drivers/ets_airspeed/Makefile | 2 +- apps/drivers/ets_airspeed/ets_airspeed.cpp | 8 ++++---- apps/px4io/controls.c | 2 +- 4 files changed, 7 insertions(+), 6 deletions(-) diff --git a/apps/drivers/drv_airspeed.h b/apps/drivers/drv_airspeed.h index 54213c0754..bffc35c62c 100644 --- a/apps/drivers/drv_airspeed.h +++ b/apps/drivers/drv_airspeed.h @@ -33,6 +33,7 @@ /** * @file Airspeed driver interface. + * @author Simon Wilks */ #ifndef _DRV_AIRSPEED_H diff --git a/apps/drivers/ets_airspeed/Makefile b/apps/drivers/ets_airspeed/Makefile index 9089d97af2..f6639b470c 100644 --- a/apps/drivers/ets_airspeed/Makefile +++ b/apps/drivers/ets_airspeed/Makefile @@ -37,6 +37,6 @@ APPNAME = ets_airspeed PRIORITY = SCHED_PRIORITY_DEFAULT -STACKSIZE = 2048 +STACKSIZE = 1024 include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index cede0534d1..5bff4c7203 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file airspeed.cpp + * @file ets_airspeed.cpp * @author Simon Wilks * * Driver for the Eagle Tree Airspeed V3 connected via I2C. @@ -197,9 +197,9 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : _collect_phase(false), _diff_pres_offset(0), _airspeed_pub(-1), - _sample_perf(perf_alloc(PC_ELAPSED, "ETS_AIRSPEED_read")), - _comms_errors(perf_alloc(PC_COUNT, "ETS_AIRSPEED_comms_errors")), - _buffer_overflows(perf_alloc(PC_COUNT, "ETS_AIRSPEED_buffer_overflows")) + _sample_perf(perf_alloc(PC_ELAPSED, "ets_airspeed_read")), + _comms_errors(perf_alloc(PC_COUNT, "ets_airspeed_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "ets_airspeed_buffer_overflows")) { // enable debug() calls _debug_enabled = true; diff --git a/apps/px4io/controls.c b/apps/px4io/controls.c index e519830710..dc36f6c934 100644 --- a/apps/px4io/controls.c +++ b/apps/px4io/controls.c @@ -70,7 +70,7 @@ controls_init(void) unsigned base = PX4IO_P_RC_CONFIG_STRIDE * i; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_OPTIONS] = 0; - r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 950; + r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MIN] = 1000; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_CENTER] = 1500; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_MAX] = 2000; r_page_rc_input_config[base + PX4IO_P_RC_CONFIG_DEADZONE] = 30; From 5b60991c63b0c6b87632369fde73236263670448 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 23 Apr 2013 08:49:33 +0200 Subject: [PATCH 014/102] Style fix: ETS_AIRSPEED > ETSAirspeed --- apps/drivers/ets_airspeed/ets_airspeed.cpp | 46 +++++++++++----------- 1 file changed, 23 insertions(+), 23 deletions(-) diff --git a/apps/drivers/ets_airspeed/ets_airspeed.cpp b/apps/drivers/ets_airspeed/ets_airspeed.cpp index 5bff4c7203..e50395e479 100644 --- a/apps/drivers/ets_airspeed/ets_airspeed.cpp +++ b/apps/drivers/ets_airspeed/ets_airspeed.cpp @@ -100,11 +100,11 @@ static const int ERROR = -1; # error This requires CONFIG_SCHED_WORKQUEUE. #endif -class ETS_AIRSPEED : public device::I2C +class ETSAirspeed : public device::I2C { public: - ETS_AIRSPEED(int bus, int address = I2C_ADDRESS); - virtual ~ETS_AIRSPEED(); + ETSAirspeed(int bus, int address = I2C_ADDRESS); + virtual ~ETSAirspeed(); virtual int init(); @@ -186,8 +186,8 @@ private: */ extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]); -ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : - I2C("ETS_AIRSPEED", AIRSPEED_DEVICE_PATH, bus, address, 100000), +ETSAirspeed::ETSAirspeed(int bus, int address) : + I2C("ETSAirspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), _num_reports(0), _next_report(0), _oldest_report(0), @@ -208,7 +208,7 @@ ETS_AIRSPEED::ETS_AIRSPEED(int bus, int address) : memset(&_work, 0, sizeof(_work)); } -ETS_AIRSPEED::~ETS_AIRSPEED() +ETSAirspeed::~ETSAirspeed() { /* make sure we are truly inactive */ stop(); @@ -219,7 +219,7 @@ ETS_AIRSPEED::~ETS_AIRSPEED() } int -ETS_AIRSPEED::init() +ETSAirspeed::init() { int ret = ERROR; @@ -253,13 +253,13 @@ out: } int -ETS_AIRSPEED::probe() +ETSAirspeed::probe() { return measure(); } int -ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) +ETSAirspeed::ioctl(struct file *filp, int cmd, unsigned long arg) { switch (cmd) { @@ -363,7 +363,7 @@ ETS_AIRSPEED::ioctl(struct file *filp, int cmd, unsigned long arg) } ssize_t -ETS_AIRSPEED::read(struct file *filp, char *buffer, size_t buflen) +ETSAirspeed::read(struct file *filp, char *buffer, size_t buflen) { unsigned count = buflen / sizeof(struct differential_pressure_s); int ret = 0; @@ -422,7 +422,7 @@ ETS_AIRSPEED::read(struct file *filp, char *buffer, size_t buflen) } int -ETS_AIRSPEED::measure() +ETSAirspeed::measure() { int ret; @@ -444,7 +444,7 @@ ETS_AIRSPEED::measure() } int -ETS_AIRSPEED::collect() +ETSAirspeed::collect() { int ret = -EIO; @@ -503,14 +503,14 @@ ETS_AIRSPEED::collect() } void -ETS_AIRSPEED::start() +ETSAirspeed::start() { /* reset the report ring and state machine */ _collect_phase = false; _oldest_report = _next_report = 0; /* schedule a cycle to start things */ - work_queue(HPWORK, &_work, (worker_t)&ETS_AIRSPEED::cycle_trampoline, this, 1); + work_queue(HPWORK, &_work, (worker_t)&ETSAirspeed::cycle_trampoline, this, 1); /* notify about state change */ struct subsystem_info_s info = { @@ -528,21 +528,21 @@ ETS_AIRSPEED::start() } void -ETS_AIRSPEED::stop() +ETSAirspeed::stop() { work_cancel(HPWORK, &_work); } void -ETS_AIRSPEED::cycle_trampoline(void *arg) +ETSAirspeed::cycle_trampoline(void *arg) { - ETS_AIRSPEED *dev = (ETS_AIRSPEED *)arg; + ETSAirspeed *dev = (ETSAirspeed *)arg; dev->cycle(); } void -ETS_AIRSPEED::cycle() +ETSAirspeed::cycle() { /* collection phase? */ if (_collect_phase) { @@ -566,7 +566,7 @@ ETS_AIRSPEED::cycle() /* schedule a fresh cycle call when we are ready to measure again */ work_queue(HPWORK, &_work, - (worker_t)&ETS_AIRSPEED::cycle_trampoline, + (worker_t)&ETSAirspeed::cycle_trampoline, this, _measure_ticks - USEC2TICK(CONVERSION_INTERVAL)); @@ -584,13 +584,13 @@ ETS_AIRSPEED::cycle() /* schedule a fresh cycle call when the measurement is done */ work_queue(HPWORK, &_work, - (worker_t)&ETS_AIRSPEED::cycle_trampoline, + (worker_t)&ETSAirspeed::cycle_trampoline, this, USEC2TICK(CONVERSION_INTERVAL)); } void -ETS_AIRSPEED::print_info() +ETSAirspeed::print_info() { perf_print_counter(_sample_perf); perf_print_counter(_comms_errors); @@ -612,7 +612,7 @@ namespace ets_airspeed #endif const int ERROR = -1; -ETS_AIRSPEED *g_dev; +ETSAirspeed *g_dev; void start(int i2c_bus); void stop(); @@ -632,7 +632,7 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver */ - g_dev = new ETS_AIRSPEED(i2c_bus); + g_dev = new ETSAirspeed(i2c_bus); if (g_dev == nullptr) goto fail; From e37f471ac4ce52e724b0d89714d9db6e1d16ee8e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 25 Apr 2013 23:59:46 +0400 Subject: [PATCH 015/102] 6-point accelerometer calibration implemented --- apps/commander/accelerometer_calibration.c | 414 +++++++++++++++++++++ apps/commander/accelerometer_calibration.h | 19 + apps/commander/commander.c | 125 +------ 3 files changed, 435 insertions(+), 123 deletions(-) create mode 100644 apps/commander/accelerometer_calibration.c create mode 100644 apps/commander/accelerometer_calibration.h diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c new file mode 100644 index 0000000000..f950398815 --- /dev/null +++ b/apps/commander/accelerometer_calibration.c @@ -0,0 +1,414 @@ +/* + * accelerometer_calibration.c + * + * Copyright (C) 2013 Anton Babushkin. All rights reserved. + * Author: Anton Babushkin + * + * Transform acceleration vector to true orientation and scale + * + * * * * Model * * * + * accel_corr = accel_T * (accel_raw - accel_offs) + * + * accel_corr[3] - fully corrected acceleration vector in body frame + * accel_T[3][3] - accelerometers transform matrix, rotation and scaling transform + * accel_raw[3] - raw acceleration vector + * accel_offs[3] - acceleration offset vector + * + * * * * Calibration * * * + * + * Reference vectors + * accel_corr_ref[6][3] = [ g 0 0 ] // nose up + * | -g 0 0 | // nose down + * | 0 g 0 | // left side down + * | 0 -g 0 | // right side down + * | 0 0 g | // on back + * [ 0 0 -g ] // level + * accel_raw_ref[6][3] + * + * accel_corr_ref[i] = accel_T * (accel_raw_ref[i] - accel_offs), i = 0...5 + * + * 6 reference vectors * 3 axes = 18 equations + * 9 (accel_T) + 3 (accel_offs) = 12 unknown constants + * + * Find accel_offs + * + * accel_offs[i] = (accel_raw_ref[i*2][i] + accel_raw_ref[i*2+1][i]) / 2 + * + * + * Find accel_T + * + * 9 unknown constants + * need 9 equations -> use 3 of 6 measurements -> 3 * 3 = 9 equations + * + * accel_corr_ref[i*2] = accel_T * (accel_raw_ref[i*2] - accel_offs), i = 0...2 + * + * Solve separate system for each row of accel_T: + * + * accel_corr_ref[j*2][i] = accel_T[i] * (accel_raw_ref[j*2] - accel_offs), j = 0...2 + * + * A * x = b + * + * x = [ accel_T[0][i] ] + * | accel_T[1][i] | + * [ accel_T[2][i] ] + * + * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough + * | accel_corr_ref[2][i] | + * [ accel_corr_ref[4][i] ] + * + * a[i][j] = accel_raw_ref[i][j] - accel_offs[j], i = 0;2;4, j = 0...2 + * + * Matrix A is common for all three systems: + * A = [ a[0][0] a[0][1] a[0][2] ] + * | a[2][0] a[2][1] a[2][2] | + * [ a[4][0] a[4][1] a[4][2] ] + * + * x = A^-1 * b + * + * accel_T = A^-1 * g + * g = 9.80665 + */ + +#include "accelerometer_calibration.h" + +#include +#include +#include +#include +#include +#include + +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { + /* announce change */ + mavlink_log_info(mavlink_fd, "accelerometer calibration started"); + /* set to accel calibration mode */ + status->flag_preflight_accel_calibration = true; + state_machine_publish(status_pub, status, mavlink_fd); + + float accel_offs_scaled[3]; + float accel_scale[3]; + int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs_scaled, accel_scale); + if (res == OK) { + /* measurements complete successfully, set parameters */ + if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs_scaled[0])) + || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs_scaled[1])) + || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs_scaled[2])) + || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) + || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) + || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { + mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); + } + + int fd = open(ACCEL_DEVICE_PATH, 0); + struct accel_scale ascale = { + accel_offs_scaled[0], + accel_scale[0], + accel_offs_scaled[1], + accel_scale[1], + accel_offs_scaled[2], + accel_scale[2], + }; + + if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) + warn("WARNING: failed to set scale / offsets for accel"); + + close(fd); + + /* auto-save to EEPROM */ + int save_ret = param_save_default(); + + if (save_ret != 0) { + warn("WARNING: auto-save of params to storage failed"); + } + + mavlink_log_info(mavlink_fd, "accel calibration done"); + + tune_confirm(); + sleep(2); + tune_confirm(); + sleep(2); + /* third beep by cal end routine */ + } else { + /* measurements error */ + mavlink_log_info(mavlink_fd, "accel calibration aborted"); + tune_error(); + sleep(2); + } + + /* exit accel calibration mode */ + status->flag_preflight_accel_calibration = false; + state_machine_publish(status_pub, status, mavlink_fd); +} + +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { + const int samples_num = 2500; + + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); + + int16_t accel_raw_ref[6][3]; + bool data_collected[6] = { false, false, false, false, false, false }; + const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + while (true) { + bool done = true; + char str[80]; + int str_ptr; + str_ptr = sprintf(str, "keep vehicle still:"); + for (int i = 0; i < 6; i++) { + if (!data_collected[i]) { + str_ptr += sprintf(&(str[str_ptr]), " %s", orientation_strs[i]); + done = false; + } + } + if (done) { + mavlink_log_info(mavlink_fd, "all accel measurements complete"); + break; + } else { + mavlink_log_info(mavlink_fd, str); + int orient = detect_orientation(mavlink_fd, sensor_combined_sub); + if (orient < 0) { + sprintf(str, "orientation detection error: %i", orient); + mavlink_log_info(mavlink_fd, str); + return ERROR; + } + mavlink_log_info(mavlink_fd, "accel measurement started"); + read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); + //mavlink_log_info(mavlink_fd, "accel measurement complete"); + str_ptr = sprintf(str, "complete: %i [ %i %i %i ]", orient, accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + mavlink_log_info(mavlink_fd, str); + data_collected[orient] = true; + tune_confirm(); + } + } + close(sensor_combined_sub); + + /* calculate offsets and rotation+scale matrix */ + int16_t accel_offs[3]; + float accel_T[3][3]; + int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); + if (res != 0) { + mavlink_log_info(mavlink_fd, "calibration values calculation error"); + return ERROR; + } + + char str[80]; + sprintf(str, "accel offsets: [ %i %i %i ]", accel_offs[0], accel_offs[1], accel_offs[2]); + mavlink_log_info(mavlink_fd, str); + //mavlink_log_info(mavlink_fd, "accel transform matrix:"); + for (int i = 0; i < 3; i++) { + //sprintf(str, "\t[ %0.6f %0.6f %0.6f ]", accel_T[i][0], accel_T[i][1], accel_T[i][2]); + //mavlink_log_info(mavlink_fd, str); + } + + /* convert raw accel offset to scaled and transform matrix to scales + * rotation part of transform matrix is not used by now */ + for (int i = 0; i < 3; i++) { + accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; + accel_scale[i] = accel_T[i][i]; + } + + return OK; +} + +/* + * Wait for vehicle become still and detect it's orientation. + * + * @return 0..5 according to orientation when vehicle is still and ready for measurements, + * ERROR if vehicle is not still after 10s or orientation error is more than 20% + */ +int detect_orientation(int mavlink_fd, int sub_sensor_combined) { + struct sensor_combined_s sensor; + /* exponential moving average of accel */ + float accel_ema[3] = { 0.0f, 0.0f, 0.0f }; + /* max-hold dispersion of accel */ + float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; + float accel_len2 = 0.0f; + /* EMA time constant in seconds*/ + float ema_len = 0.2f; + /* set "still" threshold to 0.005 m/s^2 */ + float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); + /* set accel error threshold to 20% of accel vector length */ + float accel_err_thr = 0.2f; + /* still time required in us */ + int64_t still_time = 2000000; + struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; + + hrt_abstime t_start = hrt_absolute_time(); + /* set deadline to 20s */ + hrt_abstime timeout = 20000000; + hrt_abstime t_timeout = t_start + timeout; + hrt_abstime t = t_start; + hrt_abstime t_prev = t_start; + hrt_abstime t_still = 0; + while (true) { + /* wait blocking for new data */ + int poll_ret = poll(fds, 1, 1000); + if (poll_ret) { + orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &sensor); + t = hrt_absolute_time(); + float dt = (t - t_prev) / 1000000.0f; + t_prev = t; + float w = dt / ema_len; + for (int i = 0; i < 3; i++) { + accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_raw[i] * w; + float d = (float) sensor.accelerometer_raw[i] - accel_ema[i]; + d = d * d; + accel_disp[i] = accel_disp[i] * (1.0f - w); + if (d > accel_disp[i]) + accel_disp[i] = d; + } + accel_len2 = accel_ema[0] * accel_ema[0] + accel_ema[1] * accel_ema[1] + accel_ema[2] * accel_ema[2]; + float still_thr_raw2 = still_thr2 * accel_len2; + if ( accel_disp[0] < still_thr_raw2 && + accel_disp[1] < still_thr_raw2 && + accel_disp[2] < still_thr_raw2 ) { + /* is still now */ + if (t_still == 0) { + /* first time */ + mavlink_log_info(mavlink_fd, "still"); + t_still = t; + t_timeout = t + timeout; + } else { + /* still since t_still */ + if ((int64_t) t - (int64_t) t_still > still_time) { + /* vehicle is still, exit from the loop to detection of its orientation */ + break; + } + } + } else { + /* not still, reset still start time */ + if (t_still != 0) { + mavlink_log_info(mavlink_fd, "moving"); + t_still = 0; + } + } + } else if (poll_ret == 0) { + /* any poll failure for 1s is a reason to abort */ + mavlink_log_info(mavlink_fd, "ERROR: poll failure"); + return -3; + } + if (t > t_timeout) { + mavlink_log_info(mavlink_fd, "ERROR: timeout"); + return -1; + } + } + float accel_len = sqrt(accel_len2); + float accel_err_thr_raw = accel_len * accel_err_thr; + char str[80]; + sprintf(str, "ema: [ %.1f %.1f %.1f ]", accel_ema[0], accel_ema[1], accel_ema[2]); + mavlink_log_info(mavlink_fd, str); + sprintf(str, "disp: [ %.1f %.1f %.1f ]", accel_disp[0], accel_disp[1], accel_disp[2]); + mavlink_log_info(mavlink_fd, str); + if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 0; // [ g, 0, 0 ] + if ( fabs(accel_ema[0] + accel_len) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 1; // [ -g, 0, 0 ] + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1] - accel_len) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 2; // [ 0, g, 0 ] + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && + fabs(accel_ema[2]) < accel_err_thr_raw ) + return 3; // [ 0, -g, 0 ] + if ( abs(accel_ema[0]) < accel_err_thr_raw && + abs(accel_ema[1]) < accel_err_thr_raw && + abs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + return 4; // [ 0, 0, g ] + if ( abs(accel_ema[0]) < accel_err_thr_raw && + abs(accel_ema[1]) < accel_err_thr_raw && + abs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + return 5; // [ 0, 0, -g ] + mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); + return -2; // Can't detect orientation +} + +/* + * Read specified number of accelerometer samples, calculate average and dispersion. + */ +int read_accelerometer_raw_avg(int sensor_combined_sub, int16_t accel_avg[3], int samples_num) { + struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } }; + int count = 0; + int32_t accel_sum[3] = { 0, 0, 0 }; + while (count < samples_num) { + int poll_ret = poll(fds, 1, 1000); + if (poll_ret == 1) { + struct sensor_combined_s sensor; + orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor); + for (int i = 0; i < 3; i++) { + accel_sum[i] += sensor.accelerometer_raw[i]; + } + count++; + } else { + return ERROR; + } + } + for (int i = 0; i < 3; i++) { + accel_avg[i] = (accel_sum[i] + count / 2) / count; + } + /* calculate dispersion */ + return OK; +} + +/* + * Convert raw values from accelerometers to m/s^2. + */ +void acceleration_raw_to_m_s2(float accel_corr[3], int16_t accel_raw[3], + float accel_T[3][3], int16_t accel_offs[3]) { + for (int i = 0; i < 3; i++) { + accel_corr[i] = 0.0f; + for (int j = 0; j < 3; j++) { + accel_corr[i] += accel_T[i][j] * (accel_raw[j] - accel_offs[j]); + } + } +} + +int mat_invert3(float src[3][3], float dst[3][3]) { + float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) - + src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + + src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); + if (det == 0.0) + return -1; // Singular matrix + dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det; + dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det; + dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det; + dst[0][1] = (src[0][2] * src[2][1] - src[0][1] * src[2][2]) / det; + dst[1][1] = (src[0][0] * src[2][2] - src[0][2] * src[2][0]) / det; + dst[2][1] = (src[0][1] * src[2][0] - src[0][0] * src[2][1]) / det; + dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det; + dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det; + dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det; + return 0; +} + +int calculate_calibration_values(int16_t accel_raw_ref[6][3], + float accel_T[3][3], int16_t accel_offs[3], float g) { + /* calculate raw offsets */ + for (int i = 0; i < 3; i++) { + accel_offs[i] = (int16_t) (((int32_t) (accel_raw_ref[i * 2][i]) + + (int32_t) (accel_raw_ref[i * 2 + 1][i])) / 2); + } + /* fill matrix A for linear equations system*/ + float mat_A[3][3]; + memset(mat_A, 0, sizeof(mat_A)); + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + float a = (accel_raw_ref[i * 2][j] - accel_offs[j]); + mat_A[i][j] = a; + } + } + /* calculate inverse matrix for A */ + float mat_A_inv[3][3]; + mat_invert3(mat_A, mat_A_inv); + for (int i = 0; i < 3; i++) { + /* copy results to accel_T */ + for (int j = 0; j < 3; j++) { + /* simplify matrices mult because b has only one non-zero element == g at index i */ + accel_T[j][i] = mat_A_inv[j][i] * g; + } + } + return 0; +} diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h new file mode 100644 index 0000000000..acf45b6b6e --- /dev/null +++ b/apps/commander/accelerometer_calibration.h @@ -0,0 +1,19 @@ +/* + * accelerometer_calibration.h + * + * Created on: 25.04.2013 + * Author: ton + */ + +#ifndef ACCELEROMETER_CALIBRATION_H_ +#define ACCELEROMETER_CALIBRATION_H_ + +#include +#include + +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); +int detect_orientation(int mavlink_fd, int sub_sensor_combined); +int mat_invert3(float src[3][3], float dst[3][3]); +int calculate_calibration_values(int16_t accel_raw_ref[6][3], float accel_T[3][3], int16_t accel_offs[3], float g); + +#endif /* ACCELEROMETER_CALIBRATION_H_ */ diff --git a/apps/commander/commander.c b/apps/commander/commander.c index 7c0a25f862..0f18d6cef5 100644 --- a/apps/commander/commander.c +++ b/apps/commander/commander.c @@ -94,7 +94,7 @@ #include #include "calibration_routines.h" - +#include "accelerometer_calibration.h" PARAM_DEFINE_INT32(SYS_FAILSAVE_LL, 0); /**< Go into low-level failsafe after 0 ms */ //PARAM_DEFINE_INT32(SYS_FAILSAVE_HL, 0); /**< Go into high-level failsafe after 0 ms */ @@ -158,7 +158,6 @@ static int led_off(int led); static void do_gyro_calibration(int status_pub, struct vehicle_status_s *status); static void do_mag_calibration(int status_pub, struct vehicle_status_s *status); static void do_rc_calibration(int status_pub, struct vehicle_status_s *status); -static void do_accel_calibration(int status_pub, struct vehicle_status_s *status); static void handle_command(int status_pub, struct vehicle_status_s *current_status, struct vehicle_command_s *cmd); int trigger_audio_alarm(uint8_t old_mode, uint8_t old_state, uint8_t new_mode, uint8_t new_state); @@ -666,126 +665,6 @@ void do_gyro_calibration(int status_pub, struct vehicle_status_s *status) close(sub_sensor_combined); } -void do_accel_calibration(int status_pub, struct vehicle_status_s *status) -{ - /* announce change */ - - mavlink_log_info(mavlink_fd, "keep it level and still"); - /* set to accel calibration mode */ - status->flag_preflight_accel_calibration = true; - state_machine_publish(status_pub, status, mavlink_fd); - - const int calibration_count = 2500; - - int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined)); - struct sensor_combined_s raw; - - int calibration_counter = 0; - float accel_offset[3] = {0.0f, 0.0f, 0.0f}; - - int fd = open(ACCEL_DEVICE_PATH, 0); - struct accel_scale ascale_null = { - 0.0f, - 1.0f, - 0.0f, - 1.0f, - 0.0f, - 1.0f, - }; - - if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null)) - warn("WARNING: failed to set scale / offsets for accel"); - - close(fd); - - while (calibration_counter < calibration_count) { - - /* wait blocking for new data */ - struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; - - int poll_ret = poll(fds, 1, 1000); - - if (poll_ret) { - orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw); - accel_offset[0] += raw.accelerometer_m_s2[0]; - accel_offset[1] += raw.accelerometer_m_s2[1]; - accel_offset[2] += raw.accelerometer_m_s2[2]; - calibration_counter++; - - } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_info(mavlink_fd, "acceleration calibration aborted"); - return; - } - } - - accel_offset[0] = accel_offset[0] / calibration_count; - accel_offset[1] = accel_offset[1] / calibration_count; - accel_offset[2] = accel_offset[2] / calibration_count; - - if (isfinite(accel_offset[0]) && isfinite(accel_offset[1]) && isfinite(accel_offset[2])) { - - /* add the removed length from x / y to z, since we induce a scaling issue else */ - float total_len = sqrtf(accel_offset[0] * accel_offset[0] + accel_offset[1] * accel_offset[1] + accel_offset[2] * accel_offset[2]); - - /* if length is correct, zero results here */ - accel_offset[2] = accel_offset[2] + total_len; - - float scale = 9.80665f / total_len; - - if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offset[0])) - || param_set(param_find("SENS_ACC_YOFF"), &(accel_offset[1])) - || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offset[2])) - || param_set(param_find("SENS_ACC_XSCALE"), &(scale)) - || param_set(param_find("SENS_ACC_YSCALE"), &(scale)) - || param_set(param_find("SENS_ACC_ZSCALE"), &(scale))) { - mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); - } - - fd = open(ACCEL_DEVICE_PATH, 0); - struct accel_scale ascale = { - accel_offset[0], - scale, - accel_offset[1], - scale, - accel_offset[2], - scale, - }; - - if (OK != ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale)) - warn("WARNING: failed to set scale / offsets for accel"); - - close(fd); - - /* auto-save to EEPROM */ - int save_ret = param_save_default(); - - if (save_ret != 0) { - warn("WARNING: auto-save of params to storage failed"); - } - - //char buf[50]; - //sprintf(buf, "[cmd] accel cal: x:%8.4f y:%8.4f z:%8.4f\n", (double)accel_offset[0], (double)accel_offset[1], (double)accel_offset[2]); - //mavlink_log_info(mavlink_fd, buf); - mavlink_log_info(mavlink_fd, "accel calibration done"); - - tune_confirm(); - sleep(2); - tune_confirm(); - sleep(2); - /* third beep by cal end routine */ - - } else { - mavlink_log_info(mavlink_fd, "accel calibration FAILED (NaN)"); - } - - /* exit accel calibration mode */ - status->flag_preflight_accel_calibration = false; - state_machine_publish(status_pub, status, mavlink_fd); - - close(sub_sensor_combined); -} - void do_airspeed_calibration(int status_pub, struct vehicle_status_s *status) { /* announce change */ @@ -1040,7 +919,7 @@ void handle_command(int status_pub, struct vehicle_status_s *current_vehicle_sta if (current_status.state_machine == SYSTEM_STATE_PREFLIGHT) { mavlink_log_info(mavlink_fd, "CMD starting accel cal"); tune_confirm(); - do_accel_calibration(status_pub, ¤t_status); + do_accel_calibration(status_pub, ¤t_status, mavlink_fd); tune_confirm(); mavlink_log_info(mavlink_fd, "CMD finished accel cal"); do_state_update(status_pub, ¤t_status, mavlink_fd, SYSTEM_STATE_STANDBY); From 593e3252dd90b2437862aba1c8a54b5c6edb5600 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 26 Apr 2013 13:52:25 +0400 Subject: [PATCH 016/102] Added hysteresis to still detector --- apps/commander/accelerometer_calibration.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index f950398815..9e7a3b99e0 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -274,7 +274,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { break; } } - } else { + } else if ( accel_disp[0] > still_thr_raw2 * 2.0f || + accel_disp[1] > still_thr_raw2 * 2.0f || + accel_disp[2] > still_thr_raw2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { mavlink_log_info(mavlink_fd, "moving"); From 26f9a1d42c6402a283a679e66236f247fd274cd2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 26 Apr 2013 15:25:17 +0400 Subject: [PATCH 017/102] abs/fabs bugfix, logging cleanup --- apps/commander/accelerometer_calibration.c | 80 ++++++++-------------- 1 file changed, 29 insertions(+), 51 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 9e7a3b99e0..f607b6da69 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -80,7 +80,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { /* announce change */ - mavlink_log_info(mavlink_fd, "accelerometer calibration started"); + mavlink_log_info(mavlink_fd, "accel calibration started"); /* set to accel calibration mode */ status->flag_preflight_accel_calibration = true; state_machine_publish(status_pub, status, mavlink_fd); @@ -96,7 +96,7 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { - mavlink_log_critical(mavlink_fd, "Setting offs or scale failed!"); + mavlink_log_critical(mavlink_fd, "ERROR: setting offs or scale failed"); } int fd = open(ACCEL_DEVICE_PATH, 0); @@ -122,7 +122,6 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m } mavlink_log_info(mavlink_fd, "accel calibration done"); - tune_confirm(); sleep(2); tune_confirm(); @@ -142,12 +141,11 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { const int samples_num = 2500; - - int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); - int16_t accel_raw_ref[6][3]; bool data_collected[6] = { false, false, false, false, false, false }; const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); while (true) { bool done = true; char str[80]; @@ -159,25 +157,21 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], done = false; } } - if (done) { - mavlink_log_info(mavlink_fd, "all accel measurements complete"); + if (done) break; - } else { - mavlink_log_info(mavlink_fd, str); - int orient = detect_orientation(mavlink_fd, sensor_combined_sub); - if (orient < 0) { - sprintf(str, "orientation detection error: %i", orient); - mavlink_log_info(mavlink_fd, str); - return ERROR; - } - mavlink_log_info(mavlink_fd, "accel measurement started"); - read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); - //mavlink_log_info(mavlink_fd, "accel measurement complete"); - str_ptr = sprintf(str, "complete: %i [ %i %i %i ]", orient, accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); - mavlink_log_info(mavlink_fd, str); - data_collected[orient] = true; - tune_confirm(); - } + mavlink_log_info(mavlink_fd, str); + + int orient = detect_orientation(mavlink_fd, sensor_combined_sub); + if (orient < 0) + return ERROR; + + sprintf(str, "meas started: %s", orientation_strs[orient]); + mavlink_log_info(mavlink_fd, str); + read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); + str_ptr = sprintf(str, "meas result for %s: [ %i %i %i ]", orientation_strs[orient], accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + mavlink_log_info(mavlink_fd, str); + data_collected[orient] = true; + tune_confirm(); } close(sensor_combined_sub); @@ -186,26 +180,16 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_T[3][3]; int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); if (res != 0) { - mavlink_log_info(mavlink_fd, "calibration values calculation error"); + mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error"); return ERROR; } - char str[80]; - sprintf(str, "accel offsets: [ %i %i %i ]", accel_offs[0], accel_offs[1], accel_offs[2]); - mavlink_log_info(mavlink_fd, str); - //mavlink_log_info(mavlink_fd, "accel transform matrix:"); - for (int i = 0; i < 3; i++) { - //sprintf(str, "\t[ %0.6f %0.6f %0.6f ]", accel_T[i][0], accel_T[i][1], accel_T[i][2]); - //mavlink_log_info(mavlink_fd, str); - } - /* convert raw accel offset to scaled and transform matrix to scales * rotation part of transform matrix is not used by now */ for (int i = 0; i < 3; i++) { accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; accel_scale[i] = accel_T[i][i]; } - return OK; } @@ -226,8 +210,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float ema_len = 0.2f; /* set "still" threshold to 0.005 m/s^2 */ float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); - /* set accel error threshold to 20% of accel vector length */ - float accel_err_thr = 0.2f; + /* set accel error threshold to 30% of accel vector length */ + float accel_err_thr = 0.3f; /* still time required in us */ int64_t still_time = 2000000; struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; @@ -264,7 +248,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { /* is still now */ if (t_still == 0) { /* first time */ - mavlink_log_info(mavlink_fd, "still"); + mavlink_log_info(mavlink_fd, "still..."); t_still = t; t_timeout = t + timeout; } else { @@ -279,7 +263,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { accel_disp[2] > still_thr_raw2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { - mavlink_log_info(mavlink_fd, "moving"); + mavlink_log_info(mavlink_fd, "moving..."); t_still = 0; } } @@ -289,17 +273,11 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { return -3; } if (t > t_timeout) { - mavlink_log_info(mavlink_fd, "ERROR: timeout"); return -1; } } float accel_len = sqrt(accel_len2); float accel_err_thr_raw = accel_len * accel_err_thr; - char str[80]; - sprintf(str, "ema: [ %.1f %.1f %.1f ]", accel_ema[0], accel_ema[1], accel_ema[2]); - mavlink_log_info(mavlink_fd, str); - sprintf(str, "disp: [ %.1f %.1f %.1f ]", accel_disp[0], accel_disp[1], accel_disp[2]); - mavlink_log_info(mavlink_fd, str); if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && fabs(accel_ema[1]) < accel_err_thr_raw && fabs(accel_ema[2]) < accel_err_thr_raw ) @@ -316,13 +294,13 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && fabs(accel_ema[2]) < accel_err_thr_raw ) return 3; // [ 0, -g, 0 ] - if ( abs(accel_ema[0]) < accel_err_thr_raw && - abs(accel_ema[1]) < accel_err_thr_raw && - abs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2] - accel_len) < accel_err_thr_raw ) return 4; // [ 0, 0, g ] - if ( abs(accel_ema[0]) < accel_err_thr_raw && - abs(accel_ema[1]) < accel_err_thr_raw && - abs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr_raw && + fabs(accel_ema[1]) < accel_err_thr_raw && + fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); return -2; // Can't detect orientation From d9f9ecb084e862bd72528d118c570533deb6eccd Mon Sep 17 00:00:00 2001 From: marco Date: Sat, 27 Apr 2013 14:46:25 +0200 Subject: [PATCH 018/102] BLCtrl 2.0 testing - currently only 8 Bit resolution - ppm added --- apps/drivers/mkblctrl/mkblctrl.cpp | 36 +++++++++++++++++++++++++++--- 1 file changed, 33 insertions(+), 3 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index c14fdfd1d8..664271bee5 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -62,9 +62,9 @@ #include #include #include - #include #include +#include #include #include @@ -76,6 +76,7 @@ #include #include +#include #define I2C_BUS_SPEED 400000 #define UPDATE_RATE 400 @@ -83,7 +84,7 @@ #define BLCTRL_BASE_ADDR 0x29 #define BLCTRL_OLD 0 #define BLCTRL_NEW 1 -#define BLCTRL_MIN_VALUE -0.984F +#define BLCTRL_MIN_VALUE -0.920F #define MOTOR_STATE_PRESENT_MASK 0x80 #define MOTOR_STATE_ERROR_MASK 0x7F #define MOTOR_SPINUP_COUNTER 2500 @@ -494,6 +495,14 @@ MK::task_main() fds[0].events = POLLIN; fds[1].fd = _t_armed; fds[1].events = POLLIN; + + // rc input, published to ORB + struct rc_input_values rc_in; + orb_advert_t to_input_rc = 0; + + memset(&rc_in, 0, sizeof(rc_in)); + rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; + log("starting"); long update_rate_in_us = 0; @@ -608,6 +617,27 @@ MK::task_main() ////up_pwm_servo_arm(aa.armed && !aa.lockdown); mk_servo_arm(aa.armed && !aa.lockdown); } + + // see if we have new PPM input data + if (ppm_last_valid_decode != rc_in.timestamp) { + // we have a new PPM frame. Publish it. + rc_in.channel_count = ppm_decoded_channels; + if (rc_in.channel_count > RC_INPUT_MAX_CHANNELS) { + rc_in.channel_count = RC_INPUT_MAX_CHANNELS; + } + for (uint8_t i=0; i Date: Sun, 28 Apr 2013 18:04:54 +0400 Subject: [PATCH 019/102] Reset offsets/scales before calibration and use prescaled values in m/s^2 instead of raw values. --- apps/commander/accelerometer_calibration.c | 128 ++++++++++++--------- apps/commander/accelerometer_calibration.h | 3 - 2 files changed, 76 insertions(+), 55 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index f607b6da69..1807369080 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -78,6 +78,13 @@ #include #include +void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]); +int detect_orientation(int mavlink_fd, int sub_sensor_combined); +int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num); +int mat_invert3(float src[3][3], float dst[3][3]); +int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g); + void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd) { /* announce change */ mavlink_log_info(mavlink_fd, "accel calibration started"); @@ -85,14 +92,16 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m status->flag_preflight_accel_calibration = true; state_machine_publish(status_pub, status, mavlink_fd); - float accel_offs_scaled[3]; + /* measure and calculate offsets & scales */ + float accel_offs[3]; float accel_scale[3]; - int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs_scaled, accel_scale); + int res = do_accel_calibration_mesurements(mavlink_fd, accel_offs, accel_scale); + if (res == OK) { /* measurements complete successfully, set parameters */ - if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs_scaled[0])) - || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs_scaled[1])) - || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs_scaled[2])) + if (param_set(param_find("SENS_ACC_XOFF"), &(accel_offs[0])) + || param_set(param_find("SENS_ACC_YOFF"), &(accel_offs[1])) + || param_set(param_find("SENS_ACC_ZOFF"), &(accel_offs[2])) || param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale[0])) || param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale[1])) || param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale[2]))) { @@ -101,11 +110,11 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m int fd = open(ACCEL_DEVICE_PATH, 0); struct accel_scale ascale = { - accel_offs_scaled[0], + accel_offs[0], accel_scale[0], - accel_offs_scaled[1], + accel_offs[1], accel_scale[1], - accel_offs_scaled[2], + accel_offs[2], accel_scale[2], }; @@ -139,12 +148,30 @@ void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int m state_machine_publish(status_pub, status, mavlink_fd); } -int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], float accel_scale[3]) { +int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float accel_scale[3]) { const int samples_num = 2500; - int16_t accel_raw_ref[6][3]; + float accel_ref[6][3]; bool data_collected[6] = { false, false, false, false, false, false }; const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + /* reset existing calibration */ + int fd = open(ACCEL_DEVICE_PATH, 0); + struct accel_scale ascale_null = { + 0.0f, + 1.0f, + 0.0f, + 1.0f, + 0.0f, + 1.0f, + }; + int ioctl_res = ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale_null); + close(fd); + + if (OK != ioctl_res) { + warn("ERROR: failed to set scale / offsets for accel"); + return ERROR; + } + int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); while (true) { bool done = true; @@ -167,8 +194,8 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], sprintf(str, "meas started: %s", orientation_strs[orient]); mavlink_log_info(mavlink_fd, str); - read_accelerometer_raw_avg(sensor_combined_sub, &(accel_raw_ref[orient][0]), samples_num); - str_ptr = sprintf(str, "meas result for %s: [ %i %i %i ]", orientation_strs[orient], accel_raw_ref[orient][0], accel_raw_ref[orient][1], accel_raw_ref[orient][2]); + read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num); + str_ptr = sprintf(str, "meas result for %s: [ %.2f %.2f %.2f ]", orientation_strs[orient], accel_ref[orient][0], accel_ref[orient][1], accel_ref[orient][2]); mavlink_log_info(mavlink_fd, str); data_collected[orient] = true; tune_confirm(); @@ -176,20 +203,20 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs_scaled[3], close(sensor_combined_sub); /* calculate offsets and rotation+scale matrix */ - int16_t accel_offs[3]; float accel_T[3][3]; - int res = calculate_calibration_values(accel_raw_ref, accel_T, accel_offs, CONSTANTS_ONE_G); + int res = calculate_calibration_values(accel_ref, accel_T, accel_offs, CONSTANTS_ONE_G); if (res != 0) { mavlink_log_info(mavlink_fd, "ERROR: calibration values calc error"); return ERROR; } - /* convert raw accel offset to scaled and transform matrix to scales - * rotation part of transform matrix is not used by now */ + /* convert accel transform matrix to scales, + * rotation part of transform matrix is not used by now + */ for (int i = 0; i < 3; i++) { - accel_offs_scaled[i] = accel_offs[i] * accel_T[i][i]; accel_scale[i] = accel_T[i][i]; } + return OK; } @@ -233,8 +260,8 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { t_prev = t; float w = dt / ema_len; for (int i = 0; i < 3; i++) { - accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_raw[i] * w; - float d = (float) sensor.accelerometer_raw[i] - accel_ema[i]; + accel_ema[i] = accel_ema[i] * (1.0f - w) + sensor.accelerometer_m_s2[i] * w; + float d = (float) sensor.accelerometer_m_s2[i] - accel_ema[i]; d = d * d; accel_disp[i] = accel_disp[i] * (1.0f - w); if (d > accel_disp[i]) @@ -273,9 +300,11 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { return -3; } if (t > t_timeout) { + mavlink_log_info(mavlink_fd, "ERROR: timeout"); return -1; } } + float accel_len = sqrt(accel_len2); float accel_err_thr_raw = accel_len * accel_err_thr; if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && @@ -302,56 +331,47 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { fabs(accel_ema[1]) < accel_err_thr_raw && fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) return 5; // [ 0, 0, -g ] + mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); + return -2; // Can't detect orientation } /* * Read specified number of accelerometer samples, calculate average and dispersion. */ -int read_accelerometer_raw_avg(int sensor_combined_sub, int16_t accel_avg[3], int samples_num) { +int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num) { struct pollfd fds[1] = { { .fd = sensor_combined_sub, .events = POLLIN } }; int count = 0; - int32_t accel_sum[3] = { 0, 0, 0 }; + float accel_sum[3] = { 0.0f, 0.0f, 0.0f }; + while (count < samples_num) { int poll_ret = poll(fds, 1, 1000); if (poll_ret == 1) { struct sensor_combined_s sensor; orb_copy(ORB_ID(sensor_combined), sensor_combined_sub, &sensor); - for (int i = 0; i < 3; i++) { - accel_sum[i] += sensor.accelerometer_raw[i]; - } + for (int i = 0; i < 3; i++) + accel_sum[i] += sensor.accelerometer_m_s2[i]; count++; } else { return ERROR; } } - for (int i = 0; i < 3; i++) { - accel_avg[i] = (accel_sum[i] + count / 2) / count; - } - /* calculate dispersion */ - return OK; -} -/* - * Convert raw values from accelerometers to m/s^2. - */ -void acceleration_raw_to_m_s2(float accel_corr[3], int16_t accel_raw[3], - float accel_T[3][3], int16_t accel_offs[3]) { for (int i = 0; i < 3; i++) { - accel_corr[i] = 0.0f; - for (int j = 0; j < 3; j++) { - accel_corr[i] += accel_T[i][j] * (accel_raw[j] - accel_offs[j]); - } + accel_avg[i] = accel_sum[i] / count; } + + return OK; } int mat_invert3(float src[3][3], float dst[3][3]) { float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) - - src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + - src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); + src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + + src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]); if (det == 0.0) - return -1; // Singular matrix + return ERROR; // Singular matrix + dst[0][0] = (src[1][1] * src[2][2] - src[1][2] * src[2][1]) / det; dst[1][0] = (src[1][2] * src[2][0] - src[1][0] * src[2][2]) / det; dst[2][0] = (src[1][0] * src[2][1] - src[1][1] * src[2][0]) / det; @@ -361,34 +381,38 @@ int mat_invert3(float src[3][3], float dst[3][3]) { dst[0][2] = (src[0][1] * src[1][2] - src[0][2] * src[1][1]) / det; dst[1][2] = (src[0][2] * src[1][0] - src[0][0] * src[1][2]) / det; dst[2][2] = (src[0][0] * src[1][1] - src[0][1] * src[1][0]) / det; - return 0; + + return OK; } -int calculate_calibration_values(int16_t accel_raw_ref[6][3], - float accel_T[3][3], int16_t accel_offs[3], float g) { - /* calculate raw offsets */ +int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], float accel_offs[3], float g) { + /* calculate offsets */ for (int i = 0; i < 3; i++) { - accel_offs[i] = (int16_t) (((int32_t) (accel_raw_ref[i * 2][i]) - + (int32_t) (accel_raw_ref[i * 2 + 1][i])) / 2); + accel_offs[i] = (accel_ref[i * 2][i] + accel_ref[i * 2 + 1][i]) / 2; } + /* fill matrix A for linear equations system*/ float mat_A[3][3]; memset(mat_A, 0, sizeof(mat_A)); for (int i = 0; i < 3; i++) { for (int j = 0; j < 3; j++) { - float a = (accel_raw_ref[i * 2][j] - accel_offs[j]); + float a = accel_ref[i * 2][j] - accel_offs[j]; mat_A[i][j] = a; } } + /* calculate inverse matrix for A */ float mat_A_inv[3][3]; - mat_invert3(mat_A, mat_A_inv); + if (mat_invert3(mat_A, mat_A_inv) != OK) + return ERROR; + + /* copy results to accel_T */ for (int i = 0; i < 3; i++) { - /* copy results to accel_T */ for (int j = 0; j < 3; j++) { /* simplify matrices mult because b has only one non-zero element == g at index i */ accel_T[j][i] = mat_A_inv[j][i] * g; } } - return 0; + + return OK; } diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h index acf45b6b6e..c0169c2a13 100644 --- a/apps/commander/accelerometer_calibration.h +++ b/apps/commander/accelerometer_calibration.h @@ -12,8 +12,5 @@ #include void do_accel_calibration(int status_pub, struct vehicle_status_s *status, int mavlink_fd); -int detect_orientation(int mavlink_fd, int sub_sensor_combined); -int mat_invert3(float src[3][3], float dst[3][3]); -int calculate_calibration_values(int16_t accel_raw_ref[6][3], float accel_T[3][3], int16_t accel_offs[3], float g); #endif /* ACCELEROMETER_CALIBRATION_H_ */ From 525cc1a37c0c03edbda1ecbf9fdbc00f1b1bf0f8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 28 Apr 2013 18:21:06 +0200 Subject: [PATCH 020/102] Added docs --- Documentation/control_flow.graffle | 16650 +++++++++++++++++++++++++++ 1 file changed, 16650 insertions(+) create mode 100644 Documentation/control_flow.graffle diff --git a/Documentation/control_flow.graffle b/Documentation/control_flow.graffle new file mode 100644 index 0000000000..2535231108 --- /dev/null +++ b/Documentation/control_flow.graffle @@ -0,0 +1,16650 @@ + + + + + ApplicationVersion + + com.omnigroup.OmniGraffle + 139.16.0.171715 + + CreationDate + 2013-02-22 17:51:02 +0000 + Creator + Lorenz Meier + GraphDocumentVersion + 8 + GuidesLocked + NO + GuidesVisible + YES + ImageCounter + 1 + LinksVisible + NO + MagnetsVisible + NO + MasterSheets + + ModificationDate + 2013-04-20 15:38:47 +0000 + Modifier + Lorenz Meier + NotesVisible + NO + OriginVisible + NO + PageBreaks + YES + PrintInfo + + NSBottomMargin + + float + 41 + + NSHorizonalPagination + + coded + BAtzdHJlYW10eXBlZIHoA4QBQISEhAhOU051bWJlcgCEhAdOU1ZhbHVlAISECE5TT2JqZWN0AIWEASqEhAFxlwCG + + NSLeftMargin + + float + 18 + + NSPaperName + + string + iso-a3 + + NSPaperSize + + size + {842, 1191} + + NSPrintReverseOrientation + + int + 0 + + NSRightMargin + + float + 18 + + NSTopMargin + + float + 18 + + + ReadOnly + NO + Sheets + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{320.41170773935767, 646.55758982070449}, {100, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 46 + Line + + ID + 45 + Position + 0.49247664213180542 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 limited / checked} + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 44 + + ID + 45 + Points + + {283.47949897905681, 658.66217570036315} + {459.99996984645378, 658.44980851233595} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 29 + + + + Bounds + {{460.49996948242188, 640.30001831054688}, {248.00003051757812, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 44 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_CONTROLS_EFFECTIVE_0} + + + + Bounds + {{324, 353.1875}, {120, 28}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 43 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Align + 0 + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf2 MAVLink:\ +'MANUAL_CONTROL'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{324, 174.5}, {129, 28}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 42 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Align + 0 + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural + +\f0\fs24 \cf2 MAVLink:\ +'RC_CHANNELS_RAW'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{114.97958374023438, 786}, {191, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 40 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf2 MAVLink: 'SERVO_OUTPUT_RAW'} + VerticalPad + 0 + + Wrap + NO + + + Bounds + {{528.5, 689}, {112, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 39 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;\red68\green147\blue53;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf2 MAVLink: 'ctrl eff 0-3'} + VerticalPad + 0 + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 11 + + ID + 38 + Points + + {584.52245687751122, 125.49999965650382} + {584.56069426576869, 157.00000090441219} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 37 + + + + Bounds + {{448.5, 89}, {272, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 37 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 VEHICLE_GLOBAL_POSITION_SETPOINT /\ +VEHICLE_LOCAL_POSITION_SETPOINT} + + + + Class + LineGraphic + Head + + ID + 27 + + ID + 34 + Points + + {210.47275259888471, 495.87499981747118} + {210.43193555768113, 543.06250166479344} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 10 + + + + Bounds + {{108, 737.9375}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 33 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_OUTPUTS} + + + + Class + LineGraphic + Head + + ID + 29 + + ID + 32 + Points + + {210.46968123779743, 580.06249992316259} + {210.44442316539605, 627.25000030102035} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 27 + + + + Class + LineGraphic + Head + + ID + 33 + + ID + 30 + Points + + {210.48620562018775, 690.25} + {210.49612530146715, 737.4375} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 29 + + + + Bounds + {{137.97958374023438, 627.75}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 29 + Shape + RoundRect + Style + + fill + + Color + + b + 1 + g + 0.814996 + r + 0.627106 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Actuator Mixer} + VerticalPad + 0 + + + + Bounds + {{107.97958374023438, 543.5625}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 27 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 ACTUATOR_CONTROLS_0} + + + + Bounds + {{394.22506405270201, 452.15000309396282}, {89, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 25 + Line + + ID + 22 + Position + 0.5900501012802124 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 if in auto mode} + + Wrap + NO + + + Bounds + {{152.49994329565658, 397.00120984204113}, {116, 24}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + FontInfo + + Color + + w + 0 + + Font + Helvetica + Size + 12 + + ID + 24 + Line + + ID + 17 + Position + 0.49406537413597107 + RotationType + 0 + + Shape + Rectangle + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 if in stabilized mode} + + Wrap + NO + + + Class + LineGraphic + Head + + ID + 21 + + ID + 23 + OrthogonalBarAutomatic + + OrthogonalBarPoint + {0, 0} + OrthogonalBarPosition + -1 + Points + + {584.49994992834695, 220} + {584.4997453697481, 348.6875000000008} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 2 + TailArrow + 0 + + + Tail + + ID + 11 + + + + Class + LineGraphic + Head + + ID + 10 + + ID + 22 + OrthogonalBarAutomatic + + OrthogonalBarPoint + {0, 0} + OrthogonalBarPosition + 33.206413269042969 + Points + + {583.83119320765968, 385.68717359526977} + {581, 464} + {283.49994000956832, 464.30111342104294} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 2 + Pattern + 2 + TailArrow + 0 + + + Tail + + ID + 21 + + + + Bounds + {{482, 349.1875}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 21 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 VEHICLE_ATTITUDE_SETPOINT} + + + + Class + LineGraphic + Head + + ID + 10 + + ID + 17 + Points + + {210.49997491180866, 385.6875} + {210.49991091996927, 432.875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + Pattern + 2 + TailArrow + 0 + + + Tail + + ID + 6 + + + + Class + LineGraphic + Head + + ID + 5 + + ID + 16 + Points + + {283.49999999999511, 270.00001907176534} + {339.50000000000028, 270.00001907176534} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 9 + + + + Class + LineGraphic + Head + + ID + 6 + + ID + 15 + Points + + {210.49998770563047, 301.5} + {210.49998770563047, 348.6875} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 9 + + + + Class + LineGraphic + Head + + ID + 9 + + ID + 13 + Points + + {210.49171354592596, 207} + {210.49498558851923, 238.4999999999998} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 4 + + + + Class + LineGraphic + Head + + ID + 4 + + ID + 12 + Points + + {210.49498558851246, 138.5000000000002} + {210.48997117702493, 170.00000000001342} + + Style + + stroke + + HeadArrow + FilledArrow + Legacy + + LineType + 1 + TailArrow + 0 + + + Tail + + ID + 8 + + + + Bounds + {{512, 157.5}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 11 + Shape + RoundRect + Style + + fill + + Color + + b + 0.999136 + g + 0.808554 + r + 0.587078 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Position Controller} + VerticalPad + 0 + + + + Bounds + {{138, 433.375}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 10 + Shape + RoundRect + Style + + fill + + Color + + b + 1 + g + 0.814996 + r + 0.627106 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 Attitude Controller} + VerticalPad + 0 + + + + Bounds + {{138, 239}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 9 + Shape + RoundRect + Style + + fill + + Color + + b + 0.366082 + g + 0.639788 + r + 1 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC scaling and function mapping} + VerticalPad + 0 + + + + Bounds + {{138, 76}, {145, 62}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 8 + Shape + RoundRect + Style + + fill + + Color + + b + 0.324773 + g + 0.632962 + r + 0.99252 + + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 RC Input\ +PX4IO or PX4FMU} + VerticalPad + 0 + + + + Bounds + {{108, 349.1875}, {205, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 6 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 MANUAL_CONTROL_SETPOINT} + + + + Bounds + {{340, 252}, {115, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 5 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 RC_CHANNELS} + + + + Bounds + {{108, 170.5}, {204.97958374023438, 36}} + Class + ShapedGraphic + FontInfo + + Font + Helvetica + Size + 12 + + ID + 4 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\i\fs24 \cf0 INPUT_RC} + + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Canvas 1 + UniqueID + 1 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{129, 170}, {83, 44}} + Class + ShapedGraphic + ID + 4 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Remote Control + UniqueID + 5 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Class + Group + Graphics + + + Bounds + {{575.98995971679688, 379}, {47, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1124 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 QUAD +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{576.13064904528869, 216.6250047923653}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1126 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{565.46398168220912, 200.5990128790099}, {72, 72}} + Class + ShapedGraphic + ID + 1127 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1125 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{684.97877057518497, 320.1208883952101}, {24, 24}} + Class + ShapedGraphic + ID + 1129 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1131 + Points + + {744.59415627118847, 308.1935744741462} + {742.38444757998036, 309.34262299357425} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{656.69108999710829, 361.8760779997491}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1132 + Rotation + 45 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{646.29122523639319, 281.66198172978545}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1133 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{643.54122523639319, 278.91198172978545}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1134 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1130 + Rotation + 315 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1136 + Points + + {649.54722336322868, 356.21791362626482} + {651.75693205443667, 355.0688651068366} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{721.45028963730863, 284.03541010066203}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1137 + Rotation + 225 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{646.35015439802385, 281.24950637062551}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1138 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{643.60015439802385, 278.49950637062551}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1139 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1135 + Rotation + 315 + + + Bounds + {{646.0670873832953, 281.20919655324775}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1140 + Rotation + 315 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1128 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{494.01518801866729, 320.05486147948341}, {24, 24}} + Class + ShapedGraphic + ID + 1142 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1144 + Points + + {458.75335031844725, 307.77399956263616} + {460.96305900965541, 308.92304808206421} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{530.65641659252742, 361.45650308823895}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1145 + Rotation + 135 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{455.55628135324292, 281.24240681827519}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1146 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{452.80628135324292, 278.49240681827519}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1147 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1143 + Rotation + 225 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1149 + Points + + {553.44673702887792, 356.15188491228344} + {551.23702833767004, 355.00283639285527} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{465.54367075479814, 283.96938138668088}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1150 + Rotation + 315 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{455.14380599408253, 281.1834776566443}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1151 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{452.39380599408253, 278.4334776566443}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1152 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1148 + Rotation + 225 + VFlip + YES + + + Bounds + {{455.10349617670488, 281.1431681805102}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1153 + Rotation + 225 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1141 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{684.74305392865585, 129.32699556949493}, {24, 24}} + Class + ShapedGraphic + ID + 1155 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1157 + Points + + {649.48121622843564, 117.04613365264774} + {651.69092491964352, 118.19518217207589} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{721.38428250251582, 170.72863717825052}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1158 + Rotation + 135 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{646.28414726323126, 90.514540908286847}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1159 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{643.53414726323126, 87.764540908286847}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1160 + Rotation + 45 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1156 + Rotation + 225 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1162 + Points + + {744.17460293886643, 165.42401900229501} + {741.96489424765866, 164.27497048286693} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{656.27153666478659, 93.241515476692427}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1163 + Rotation + 315 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{645.87167190407115, 90.455611746655876}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1164 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{643.12167190407115, 87.705611746655876}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1165 + Rotation + 225 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1161 + Rotation + 225 + VFlip + YES + + + Bounds + {{645.83136208669339, 90.415302270521892}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1166 + Rotation + 225 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1154 + Rotation + 315 + + + Class + Group + Graphics + + + Bounds + {{494.00811680064464, 129.15022794494948}, {24, 24}} + Class + ShapedGraphic + ID + 1168 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1170 + Points + + {553.62350249664826, 117.22291402388569} + {551.41379380544015, 118.37196254331369} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{465.72043622256808, 170.9054175494887}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1171 + Rotation + 45 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{455.32057146185286, 90.691321279524772}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1172 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{452.57057146185286, 87.941321279524772}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1173 + Rotation + 135 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1169 + Rotation + 315 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1175 + Points + + {458.57656958868847, 165.24725317600405} + {460.78627827989641, 164.09820465657594} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{530.47963586276819, 93.064749650401353}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1176 + Rotation + 225 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{455.37950062348352, 90.278845920365001}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1177 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{452.62950062348352, 87.528845920365001}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1178 + Rotation + 315 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1174 + Rotation + 315 + + + Bounds + {{455.09643360875504, 90.238536102987126}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1179 + Rotation + 315 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1167 + Rotation + 315 + + + Bounds + {{547.25939156789127, 219.8035943432547}, {8, 134}} + Class + ShapedGraphic + ID + 1180 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{647.66855809291212, 119.39442062517122}, {8, 134}} + Class + ShapedGraphic + ID + 1181 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{647.66855089985006, 219.80357636059938}, {8, 134}} + Class + ShapedGraphic + ID + 1182 + Rotation + 315 + Shape + Rectangle + + + Bounds + {{547.20046240626141, 119.33550225313491}, {8, 134}} + Class + ShapedGraphic + ID + 1183 + Rotation + 315 + Shape + Rectangle + + + ID + 1123 + + + Bounds + {{287.14883422851562, 373}, {46, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1121 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 QUAD +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{252.93672553699014, 864.96332065264312}, {24, 24}} + Class + ShapedGraphic + ID + 1186 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1188 + Points + + {248.68672172228349, 826.3749926090228} + {249.43672172228361, 828.7499926090228} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{252.68672172228372, 918.12499260902291}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1189 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{214.43672172228372, 826.3749926090228}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1190 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{211.68672172228372, 823.6249926090228}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1191 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1187 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1193 + Points + + {281.43672680854809, 927.54165927568897} + {280.6867268085482, 925.1666592756892} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{261.43672680854797, 817.2916592756892}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1194 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{214.18672680854797, 826.0416592756892}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1195 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{211.43672680854797, 823.2916592756892}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1196 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1192 + Rotation + 270 + VFlip + YES + + + Bounds + {{214.02503832182103, 826.05162629068673}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1197 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1185 + + + Class + Group + Graphics + + + Bounds + {{255.93671290080545, 636.38001505533919}, {24, 24}} + Class + ShapedGraphic + ID + 1199 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1201 + Points + + {251.6867090860988, 597.79168701171886} + {252.43670908609892, 600.16668701171886} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{255.68670908609903, 689.54168701171898}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1202 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{217.43670908609903, 597.79168701171886}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1203 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{214.68670908609903, 595.04168701171886}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1204 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1200 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1206 + Points + + {284.43671417236339, 698.95835367838504} + {283.68671417236351, 696.58335367838527} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{264.43671417236328, 588.70835367838527}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1207 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{217.18671417236328, 597.45835367838527}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1208 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{214.43671417236328, 594.70835367838527}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1209 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1205 + Rotation + 270 + VFlip + YES + + + Bounds + {{217.02502568563636, 597.46832069338279}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1210 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1198 + + + Class + Group + Graphics + + + Bounds + {{480.49999872844216, 864.96333555380545}, {24, 24}} + Class + ShapedGraphic + ID + 1212 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1214 + Points + + {476.24999491373552, 826.37500751018513} + {476.99999491373563, 828.75000751018513} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{480.24999491373575, 918.12500751018524}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1215 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.99999491373575, 826.37500751018513}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1216 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439.24999491373575, 823.62500751018513}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1217 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1213 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1219 + Points + + {509.00000000000011, 927.5416741768513} + {508.25000000000023, 925.16667417685153} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{489, 817.29167417685153}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1220 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.75, 826.04167417685153}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1221 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439, 823.29167417685153}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1222 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1218 + Rotation + 270 + VFlip + YES + + + Bounds + {{441.58831151327308, 826.05164119184906}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1223 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1211 + + + Class + Group + Graphics + + + Bounds + {{480.49999872844216, 636.38001505533896}, {24, 24}} + Class + ShapedGraphic + ID + 1225 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1227 + Points + + {476.24999491373552, 597.79168701171864} + {476.99999491373563, 600.16668701171864} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{480.24999491373575, 689.54168701171875}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1228 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.99999491373575, 597.79168701171864}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1229 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439.24999491373575, 595.04168701171864}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1230 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1226 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1232 + Points + + {509.00000000000011, 698.95835367838481} + {508.25000000000023, 696.58335367838504} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{489, 588.70835367838504}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1233 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.75, 597.45835367838504}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1234 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{439, 594.70835367838504}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1235 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1231 + Rotation + 270 + VFlip + YES + + + Bounds + {{441.58831151327308, 597.46832069338257}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1236 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1224 + + + Bounds + {{452.7625732421875, 947.72591400146473}, {45, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1237 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 OCTO +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{353.51001119036124, 739.42163658141953}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1239 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{342.8433593880041, 726.66665752440122}, {72, 72}} + Class + ShapedGraphic + ID + 1240 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1238 + + + Class + Group + Graphics + + + Bounds + {{366.83836873372331, 916.58333714803678}, {24, 24}} + Class + ShapedGraphic + ID + 1242 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1244 + Points + + {429.42669677734398, 945.3333333333303} + {427.05169677734398, 944.58333333333019} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{320.42669677734375, 924.08333333333019}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1245 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{327.92669677734398, 878.08333333333019}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1246 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.17669677734398, 875.33333333333019}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1247 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1243 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1249 + Points + + {328.26003011067723, 912.08333841959472} + {330.63503011067723, 912.83333841959472} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{421.26003011067723, 914.83333841959472}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1250 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{328.26003011067723, 877.83333841959472}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1251 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.51003011067723, 875.08333841959472}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1252 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1248 + + + Bounds + {{327.92668660481695, 877.67164993286758}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1253 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1241 + + + Class + Group + Graphics + + + Bounds + {{205.66167195637968, 750.54168065389615}, {24, 24}} + Class + ShapedGraphic + ID + 1255 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 7} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1257 + Points + + {268.25000000000023, 779.29167683918968} + {265.87500000000023, 778.54167683918956} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{159.24999999999994, 758.04167683918956}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1258 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{166.75, 712.04167683918956}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1259 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{164, 709.29167683918956}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1260 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1256 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1262 + Points + + {167.08333333333348, 746.0416819254541} + {169.45833333333348, 746.7916819254541} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{260.08333333333348, 748.7916819254541}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1263 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{167.08333333333348, 711.7916819254541}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1264 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{164.33333333333348, 709.0416819254541}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1265 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1261 + + + Bounds + {{166.74998982747337, 711.62999343872696}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1266 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1254 + + + Class + Group + Graphics + + + Bounds + {{528.01506551106706, 750.54168065389615}, {24, 24}} + Class + ShapedGraphic + ID + 1268 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 8} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1270 + Points + + {590.60339355468773, 779.29167683918968} + {588.22839355468773, 778.54167683918956} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{481.6033935546875, 758.04167683918956}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1271 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{489.10339355468773, 712.04167683918956}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1272 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{486.35339355468773, 709.29167683918956}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1273 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1269 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1275 + Points + + {489.43672688802098, 746.0416819254541} + {491.81172688802098, 746.7916819254541} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{582.43672688802098, 748.7916819254541}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1276 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{489.43672688802098, 711.7916819254541}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1277 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{486.68672688802098, 709.0416819254541}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1278 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1274 + + + Bounds + {{489.10338338216064, 711.62999343872696}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1279 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1267 + + + Bounds + {{306.14882584901056, 766.45459545146662}, {8, 134}} + Class + ShapedGraphic + ID + 1280 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{468.3533935546875, 695.66666666666504}, {8, 134}} + Class + ShapedGraphic + ID + 1281 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{440.55795213074884, 760.88380015384382}, {8, 134}} + Class + ShapedGraphic + ID + 1282 + Rotation + 135 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{366.83834838867119, 584.49999872844194}, {24, 24}} + Class + ShapedGraphic + ID + 1284 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1286 + Points + + {429.42667643229174, 613.24999491373558} + {427.05167643229174, 612.49999491373546} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{320.42667643229152, 591.99999491373546}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1287 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{327.92667643229174, 545.99999491373546}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1288 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.17667643229174, 543.24999491373546}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1289 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1285 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1291 + Points + + {328.26000976562511, 579.99999999999977} + {330.63500976562511, 580.74999999999977} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{421.260009765625, 582.74999999999977}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1292 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{328.26000976562523, 545.74999999999977}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1293 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{325.51000976562523, 542.99999999999977}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1294 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1290 + + + Bounds + {{327.92666625976494, 545.58831151327263}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1295 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1283 + + + Bounds + {{281.3533935546875, 695.66666666666504}, {8, 134}} + Class + ShapedGraphic + ID + 1296 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{442.5579845556756, 629.04542696963983}, {8, 134}} + Class + ShapedGraphic + ID + 1297 + Rotation + 225 + Shape + Rectangle + + + Bounds + {{374.84336344400776, 790.58333841959472}, {8, 134}} + Class + ShapedGraphic + ID + 1298 + Shape + Rectangle + + + Bounds + {{374.84335708617891, 600.24999491373535}, {8, 134}} + Class + ShapedGraphic + ID + 1299 + Shape + Rectangle + + + Bounds + {{309.12873002381525, 629.45457637798029}, {8, 134}} + Class + ShapedGraphic + ID + 1300 + Rotation + 135 + Shape + Rectangle + + + ID + 1184 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{181.15661763567644, 222.11968549092626}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1024 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{170.4899658333193, 209.364706433908}, {72, 72}} + Class + ShapedGraphic + ID + 1025 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1023 + + + Class + Group + Graphics + + + Bounds + {{194.48495483398159, 368.44802729289523}, {24, 24}} + Class + ShapedGraphic + ID + 1027 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1029 + Points + + {257.0732828776022, 397.19802347818882} + {254.69828287760208, 396.4480234781887} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{148.07328287760188, 375.9480234781887}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1030 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.57328287760205, 329.9480234781887}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1031 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{152.82328287760205, 327.1980234781887}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1032 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1028 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1034 + Points + + {155.90661621093548, 363.94802856445312} + {158.28161621093548, 364.69802856445312} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{248.90661621093545, 366.69802856445312}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1035 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.90661621093548, 329.69802856445312}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1036 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{153.15661621093548, 326.94802856445312}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1037 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1033 + + + Bounds + {{155.57327270507534, 329.53634007772598}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1038 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1026 + + + Class + Group + Graphics + + + Bounds + {{59.499998728441994, 233.36969502765339}, {24, 24}} + Class + ShapedGraphic + ID + 1040 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1042 + Points + + {55.249994913735321, 194.78136698403296} + {55.999994913735435, 197.1563669840329} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{59.249994913735435, 286.53136698403307}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1043 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{20.999994913735549, 194.78136698403301}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1044 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{18.249994913735549, 192.03136698403301}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1045 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1041 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1047 + Points + + {87.999999999999915, 295.9480336506993} + {87.250000000000028, 293.57303365069941} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{67.999999999999915, 185.69803365069959}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1048 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{20.749999999999915, 194.44803365069947}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1049 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{17.999999999999915, 191.69803365069947}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1050 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1046 + Rotation + 270 + VFlip + YES + + + Bounds + {{20.588311513272686, 194.45800066569694}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1051 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1039 + + + Class + Group + Graphics + + + Bounds + {{329.22993342082486, 233.36969502765339}, {24, 24}} + Class + ShapedGraphic + ID + 1053 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1055 + Points + + {324.97992960611816, 194.7813669840329} + {325.72992960611828, 197.15636698403287} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{328.97992960611828, 286.53136698403307}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1056 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{290.72992960611839, 194.78136698403301}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1057 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{287.97992960611839, 192.03136698403301}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1058 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1054 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1060 + Points + + {357.72993469238281, 295.9480336506993} + {356.97993469238293, 293.57303365069941} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{337.72993469238281, 185.69803365069953}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1061 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{290.47993469238281, 194.44803365069947}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1062 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{287.72993469238281, 191.69803365069947}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1063 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1059 + Rotation + 270 + VFlip + YES + + + Bounds + {{290.31824620565556, 194.45800066569686}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1064 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1052 + + + Class + Group + Graphics + + + Bounds + {{194.48495483398159, 92.448027292895233}, {24, 24}} + Class + ShapedGraphic + ID + 1066 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1068 + Points + + {257.0732828776022, 121.19802347818882} + {254.69828287760208, 120.4480234781887} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{148.07328287760188, 99.948023478188702}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1069 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.57328287760205, 53.948023478188688}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1070 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{152.82328287760205, 51.198023478188688}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1071 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1067 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1073 + Points + + {155.90661621093548, 87.948028564453111} + {158.28161621093548, 88.698028564453111} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{248.90661621093545, 90.698028564453111}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1074 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{155.90661621093548, 53.698028564453111}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1075 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{153.15661621093548, 50.948028564453111}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1076 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1072 + + + Bounds + {{155.57327270507534, 53.536340077725967}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1077 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1065 + + + Bounds + {{131.48995971679412, 178.36470031738281}, {8, 134}} + Class + ShapedGraphic + ID + 1078 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{273.48996988932043, 178.36469523111947}, {8, 134}} + Class + ShapedGraphic + ID + 1079 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{202.48996988932029, 249.36468505859375}, {8, 134}} + Class + ShapedGraphic + ID + 1080 + Shape + Rectangle + + + Bounds + {{202.48995971679412, 107.28136189778644}, {8, 134}} + Class + ShapedGraphic + ID + 1081 + Shape + Rectangle + + + ID + 1022 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignments + UniqueID + 2 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Bounds + {{479, 926}, {45, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1210 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 HEXA +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{323.13577025880016, 749.76557170439401}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1124 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{312.46911845644303, 737.01059264737569}, {72, 72}} + Class + ShapedGraphic + ID + 1125 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1123 + + + Class + Group + Graphics + + + Bounds + {{407.17230315305846, 883.72204834096681}, {24, 24}} + Class + ShapedGraphic + ID + 1127 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1129 + Points + + {379.80522301611819, 860.03627302756399} + {381.64224206895665, 861.71808336155198} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{432.69752786153174, 932.25483880979243}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1130 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{368.7196421785618, 844.9870622696244}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1131 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{365.9696421785618, 842.2370622696244}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1132 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1128 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1134 + Points + + {458.75089272822612, 931.27417383395721} + {456.91387367538789, 929.59236349996911} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{389.85858788281303, 840.55560805172911}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1135 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{368.33647356578285, 844.82338459189691}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1136 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{365.58647356578285, 842.07338459189691}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1137 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1133 + Rotation + 240 + VFlip + YES + + + Bounds + {{368.26061274159781, 844.81035428333826}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1138 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1126 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{267.75726457856609, 881.27816449485533}, {24, 24}} + Class + ShapedGraphic + ID + 1140 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1142 + Points + + {331.94303989196902, 882.48992268280176} + {329.51122955798087, 883.02790362996325} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{230.47447410974044, 913.3476178373885}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1143 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.99225064990861, 842.82550352035832}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1144 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{226.24225064990861, 840.07550352035832}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1145 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1141 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1147 + Points + + {227.70513908557558, 904.27791574513662} + {230.13694941956365, 903.73993479797491} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{313.17370486780385, 854.92022059054989}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1148 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{229.15592832763582, 842.44233490757972}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1149 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{226.40592832763582, 839.69233490757972}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1150 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1146 + Rotation + 330 + + + Bounds + {{228.84558214533197, 842.36647408339456}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1151 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1139 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{474.97119637474935, 761.64314519248808}, {24, 24}} + Class + ShapedGraphic + ID + 1153 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1155 + Points + + {539.15697168815223, 762.85490338043462} + {536.72516135416413, 763.39288432759611} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{437.68840590592367, 793.71259853502136}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1156 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{436.20618244609187, 723.19048421799118}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1157 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{433.45618244609187, 720.44048421799118}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1158 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1154 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1160 + Points + + {434.91907088175884, 784.64289644276937} + {437.35088121574688, 784.10491549560766} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{520.38763666398711, 735.28520128818252}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1161 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{436.36986012381902, 722.80731560521247}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1162 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{433.61986012381902, 720.05731560521247}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1163 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1159 + Rotation + 330 + + + Bounds + {{436.05951394151521, 722.73145478102731}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1164 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1152 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{197.82245308809811, 760.38763453076365}, {24, 24}} + Class + ShapedGraphic + ID + 1166 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1168 + Points + + {170.45537295115798, 736.70185921736106} + {172.29239200399638, 738.38366955134893} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{223.34767779657142, 808.92042499958939}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1169 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{159.36979211360145, 721.65264845942124}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1170 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{156.61979211360145, 718.90264845942124}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1171 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1167 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1173 + Points + + {249.4010426632658, 807.93976002375393} + {247.56402361042768, 806.25794968976606} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{180.50873781785265, 717.22119424152584}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1174 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{158.98662350082267, 721.48897078169387}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1175 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{156.23662350082267, 718.73897078169387}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1176 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1172 + Rotation + 240 + VFlip + YES + + + Bounds + {{158.91076267663743, 721.47594047313521}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1177 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1165 + Rotation + 330 + + + Class + Group + Graphics + + + Bounds + {{405.7864385681853, 642.051622339657}, {24, 24}} + Class + ShapedGraphic + ID + 1179 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1181 + Points + + {378.41935843124503, 618.36584702625407} + {380.25637748408349, 620.04765736024217} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{431.31166327665852, 690.58441280848263}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1182 + Rotation + 150 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{367.33377759368858, 603.3166362683146}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1183 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{364.58377759368858, 600.5666362683146}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1184 + Rotation + 60 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1180 + Rotation + 240 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1186 + Points + + {457.36502814335307, 689.6037478326474} + {455.52800909051496, 687.92193749865953} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{388.47272329793987, 598.8851820504193}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1187 + Rotation + 330 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{366.95060898090981, 603.15295859058722}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1188 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{364.20060898090981, 600.40295859058722}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1189 + Rotation + 240 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1185 + Rotation + 240 + VFlip + YES + + + Bounds + {{366.87474815672459, 603.13992828202845}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1190 + Rotation + 240 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1178 + Rotation + 330 + + + Bounds + {{416.05401025695778, 706.97194681357246}, {8, 134}} + Class + ShapedGraphic + ID + 1191 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{273.20840928884093, 706.24568349439642}, {8, 134}} + Class + ShapedGraphic + ID + 1192 + Rotation + 270 + Shape + Rectangle + + + Bounds + {{309.23428435411637, 768.64435011115415}, {8, 134}} + Class + ShapedGraphic + ID + 1193 + Rotation + 30 + Shape + Rectangle + + + Bounds + {{380.02813770004576, 644.57328454142464}, {8, 134}} + Class + ShapedGraphic + ID + 1194 + Rotation + 30 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{268.61421230672084, 643.49244485638758}, {24, 24}} + Class + ShapedGraphic + ID + 1196 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1198 + Points + + {332.79998762012377, 644.70420304433412} + {330.36817728613562, 645.24218399149561} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{231.33142183789516, 675.56189819892086}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1199 + Rotation + 60 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{229.84919837806336, 605.03978388189068}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1200 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{227.09919837806336, 602.28978388189068}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1201 + Rotation + 150 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1197 + Rotation + 330 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1203 + Points + + {228.56208681373033, 666.49219610666887} + {230.99389714771837, 665.95421515950716} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{314.03065259595854, 617.13450095208213}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1204 + Rotation + 240 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{230.01287605579051, 604.65661526911197}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1205 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{227.26287605579051, 601.90661526911197}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1206 + Rotation + 330 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1202 + Rotation + 330 + + + Bounds + {{229.7025298734867, 604.58075444492681}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1207 + Rotation + 330 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1195 + Rotation + 330 + + + Bounds + {{380.57688435489479, 768.55104482376805}, {8, 134}} + Class + ShapedGraphic + ID + 1208 + Rotation + 330 + Shape + Rectangle + + + Bounds + {{309.53521396482506, 645.50328259865807}, {8, 134}} + Class + ShapedGraphic + ID + 1209 + Rotation + 330 + Shape + Rectangle + + + ID + 1122 + Rotation + 330 + + + Bounds + {{431, 450}, {44, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1121 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 HEXA +\b0 +} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{326.15660523791308, 258.95613225301122}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 320 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{315.48995343555595, 246.20115319599296}, {72, 72}} + Class + ShapedGraphic + ID + 321 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 319 + + + Class + Group + Graphics + + + Bounds + {{339.36497966449247, 411.82398351031941}, {24, 24}} + Class + ShapedGraphic + ID + 323 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 325 + Points + + {335.11497584978588, 373.23565546669897} + {335.86497584978599, 375.61065546669897} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{339.11497584978599, 464.98565546669914}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 326 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{300.86497584978611, 373.23565546669909}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 327 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{298.11497584978611, 370.48565546669909}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 328 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 324 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 330 + Points + + {367.86498093605042, 474.40232213336532} + {367.11498093605053, 472.02732213336543} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{347.86498093605042, 364.15232213336554}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 331 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{300.61498093605042, 372.90232213336543}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 332 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{297.86498093605042, 370.15232213336543}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 333 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 329 + Rotation + 270 + VFlip + YES + + + Bounds + {{300.45329244932327, 372.91228914836296}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 334 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 322 + + + Class + Group + Graphics + + + Bounds + {{219.84995651245046, 339.99999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 336 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 338 + Points + + {282.43828455607104, 368.74999491373569} + {280.06328455607098, 367.99999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{173.43828455607076, 347.49999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 339 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{180.93828455607093, 301.49999491373558}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 340 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{178.18828455607093, 298.74999491373558}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 341 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 337 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 343 + Points + + {181.27161788940435, 335.5} + {183.64661788940435, 336.25} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{274.2716178894043, 338.25}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 344 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{181.27161788940435, 301.25}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 345 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{178.52161788940435, 298.5}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 346 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 342 + + + Bounds + {{180.93827438354421, 301.08831151327286}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 347 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 335 + + + Class + Group + Graphics + + + Bounds + {{459.11999511718477, 339.99999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 349 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 351 + Points + + {521.70832316080532, 368.74999491373569} + {519.33332316080532, 367.99999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{412.70832316080504, 347.49999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 352 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{420.20832316080521, 301.49999491373558}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 353 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{417.45832316080521, 298.74999491373558}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 354 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 350 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 356 + Points + + {420.54165649413864, 335.5} + {422.91665649413864, 336.25} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{513.54165649413858, 338.25}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 357 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{420.54165649413864, 301.25}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 358 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{417.79165649413864, 298.5}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 359 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 355 + + + Bounds + {{420.20831298827852, 301.08831151327286}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 360 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 348 + + + Class + Group + Graphics + + + Bounds + {{219.72989813487507, 200.33832295734095}, {24, 24}} + Class + ShapedGraphic + ID + 362 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 364 + Points + + {215.47989432016846, 161.74999491372051} + {216.22989432016857, 164.12499491372046} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{219.47989432016857, 253.49999491372063}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 365 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{181.22989432016868, 161.74999491372057}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 366 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{178.47989432016868, 158.99999491372057}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 367 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 363 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 369 + Points + + {248.22989940643305, 262.91666158038686} + {247.47989940643316, 260.54166158038697} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{228.22989940643305, 152.66666158038709}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 370 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{180.97989940643305, 161.41666158038697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 371 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{178.22989940643305, 158.66666158038697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 372 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 368 + Rotation + 270 + VFlip + YES + + + Bounds + {{180.81821091970582, 161.42662859538444}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 373 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 361 + + + Class + Group + Graphics + + + Bounds + {{458.99999872844205, 201.83832295734095}, {24, 24}} + Class + ShapedGraphic + ID + 375 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 377 + Points + + {454.74999491373541, 163.24999491372051} + {455.49999491373552, 165.62499491372046} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{458.74999491373552, 254.99999491372063}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 378 + Rotation + 180 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{420.49999491373563, 163.24999491372057}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 379 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{417.74999491373563, 160.49999491372057}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 380 + Rotation + 90 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 376 + Rotation + 270 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 382 + Points + + {487.5, 264.41666158038686} + {486.75000000000011, 262.04166158038697} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{467.5, 154.16666158038709}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 383 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{420.25, 162.91666158038697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 384 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{417.5, 160.16666158038697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 385 + Rotation + 270 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 381 + Rotation + 270 + VFlip + YES + + + Bounds + {{420.0883115132728, 162.92662859538444}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 386 + Rotation + 270 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 374 + + + Bounds + {{409.00361117886365, 251.82615622621091}, {8, 134}} + Class + ShapedGraphic + ID + 387 + Rotation + 300 + Shape + Rectangle + + + Bounds + {{285.65882358120746, 179.77439325790914}, {8, 134}} + Class + ShapedGraphic + ID + 388 + Rotation + 300 + Shape + Rectangle + + + Bounds + {{285.65881327292152, 251.82616124293514}, {8, 134}} + Class + ShapedGraphic + ID + 389 + Rotation + 60 + Shape + Rectangle + + + Bounds + {{409.00362148715112, 179.77439325790914}, {8, 134}} + Class + ShapedGraphic + ID + 390 + Rotation + 60 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{339.48495483398165, 134.49999872844211}, {24, 24}} + Class + ShapedGraphic + ID + 392 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 394 + Points + + {402.0732828776022, 163.24999491373569} + {399.69828287760214, 162.49999491373558} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{293.07328287760191, 141.99999491373558}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 395 + Rotation + 90 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{300.57328287760208, 95.999994913735577}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 396 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{297.82328287760208, 93.249994913735577}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 397 + Rotation + 180 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 393 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 399 + Points + + {300.90661621093551, 130} + {303.28161621093551, 130.75} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{393.90661621093545, 132.75}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 400 + Rotation + 270 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{300.90661621093551, 95.75}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 401 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{298.15661621093551, 93}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 402 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 398 + + + Bounds + {{300.5732727050754, 95.588311513272842}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 403 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 391 + + + Bounds + {{347.48996988932038, 287.41665649414062}, {8, 134}} + Class + ShapedGraphic + ID + 404 + Shape + Rectangle + + + Bounds + {{347.4899597167942, 145.33333333333331}, {8, 134}} + Class + ShapedGraphic + ID + 405 + Shape + Rectangle + + + ID + 318 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignment 2 + UniqueID + 3 + VPages + 1 + + + ActiveLayerIndex + 0 + AutoAdjust + + BackgroundGraphic + + Bounds + {{0, 0}, {806, 1132}} + Class + SolidGraphic + ID + 2 + Style + + shadow + + Draws + NO + + stroke + + Draws + NO + + + + BaseZoom + 0 + CanvasOrigin + {0, 0} + ColumnAlign + 1 + ColumnSpacing + 36 + DisplayScale + 1 0/72 in = 1.0000 in + GraphicsList + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{317.51000800051321, 240.42163882949882}, {50.666667938232422, 36}} + Class + ShapedGraphic + ID + 1417 + Rotation + 270 + Shape + HorizontalTriangle + Style + + fill + + Color + + b + 0.13195 + g + 0.165669 + r + 1 + + + + Text + + VerticalPad + 0 + + + + Bounds + {{306.84335619815613, 227.6666597724805}, {72, 72}} + Class + ShapedGraphic + ID + 1418 + Rotation + 45 + Shape + Rectangle + Style + + stroke + + CornerRadius + 9 + + + + + ID + 1416 + + + Class + Group + Graphics + + + Class + Group + Graphics + + + Bounds + {{181.87174317649047, 313.76849034719959}, {24, 24}} + Class + ShapedGraphic + ID + 1421 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 6} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1423 + Points + + {159.49938242361688, 285.249576623557} + {161.10116522486757, 287.15677793899749} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{201.23696348262672, 364.71920821881605}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1424 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{143.41457890258161, 275.07218626448082}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1425 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{140.66457890258161, 272.32218626448082}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1426 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1422 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1428 + Points + + {228.47124867019181, 366.1825051496383} + {226.8694658689414, 364.27530383419804} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{170.73366761118237, 268.21287355437971}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1429 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{143.05605219122737, 274.85989550871483}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1430 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{140.30605219122737, 272.10989550871483}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1431 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1427 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{142.96005354220407, 274.85679605657162}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1432 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1420 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{272.11841406704639, 103.73309829351469}, {24, 24}} + Class + ShapedGraphic + ID + 1434 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 5} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1436 + Points + + {249.74605331417285, 75.214184569872145} + {251.34783611542343, 77.121385885312606} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{291.48363437318255, 154.68381616513099}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1437 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{233.66124979313764, 65.036794210795819}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1438 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{230.91124979313764, 62.286794210795819}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1439 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1435 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1441 + Points + + {318.71791956074799, 156.14711309595339} + {317.11613675949758, 154.23991178051318} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{260.98033850173846, 58.177481500694711}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1442 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{233.30272308178348, 64.824503455029671}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1443 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{230.55272308178348, 62.074503455029671}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1444 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1440 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{233.20672443276007, 64.821404002886837}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1445 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1433 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{392.11278792691934, 400.85319857921803}, {24, 24}} + Class + ShapedGraphic + ID + 1447 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 4} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1449 + Points + + {369.74042717404592, 372.33428485557562} + {371.34220997529656, 374.24148617101616} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{411.47800823305562, 451.80391645083449}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1450 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{353.65562365301071, 362.15689449649926}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1451 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{350.90562365301071, 359.40689449649926}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1452 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1448 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1454 + Points + + {438.71229342062088, 453.26721338165692} + {437.11051061937059, 451.36001206621654} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{380.97471236161118, 355.29758178639815}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1455 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{353.29709694165621, 361.94460374073327}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1456 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{350.54709694165621, 359.19460374073327}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1457 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1453 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{353.20109829263305, 361.94150428859024}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1458 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1446 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{479.58783759318999, 189.66974728965576}, {24, 24}} + Class + ShapedGraphic + ID + 1460 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 3} + VerticalPad + 0 + + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1462 + Points + + {457.21547665220845, 161.15083366194582} + {458.81725945345897, 163.05803497738634} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{498.95305771121809, 240.62046525720473}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1463 + Rotation + 157.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{441.13067313117307, 150.9734433028697}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1464 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{438.38067313117307, 148.2234433028697}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1465 + Rotation + 67.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1461 + Rotation + 247.5 + VFlip + YES + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1467 + Points + + {526.18734328198354, 242.08376201128482} + {524.58556048073308, 240.17656069584442} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{468.44976222297396, 144.11413041602617}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1468 + Rotation + 337.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + Bounds + {{440.77214680301904, 150.76115237036112}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1469 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + Bounds + {{438.02214680301904, 148.01115237036112}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1470 + Rotation + 247.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + VFlip + YES + + + ID + 1466 + Rotation + 247.5 + VFlip + YES + + + Bounds + {{440.67614795890404, 150.75805299902771}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1471 + Rotation + 247.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.673128 + g + 0.534129 + r + 0.217952 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + VFlip + YES + + + ID + 1459 + Rotation + 337.5 + + + Bounds + {{324.9947377700048, 478.76189426912856}, {46, 14}} + Class + ShapedGraphic + FitText + YES + Flow + Resize + ID + 1472 + Shape + Rectangle + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + Pad + 0 + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\b\fs24 \cf0 OCTO +\b0 X} + VerticalPad + 0 + + Wrap + NO + + + Class + Group + Graphics + + + Bounds + {{267.24952227247923, 404.95559172255122}, {24, 24}} + Class + ShapedGraphic + ID + 1474 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 2} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1476 + Points + + {332.396988909622, 413.07125181593568} + {329.91576246001244, 413.28721548361688} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{226.49295677281663, 431.38573061302958}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1477 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.4458262787623, 366.49842726410935}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1478 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{225.6958262787623, 363.74842726410935}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1479 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1475 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1481 + Points + + {226.20695455654064, 421.06707636999505} + {228.68818100615007, 420.8511127023138} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{316.11098669334581, 384.25259757290121}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1482 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{228.65811718740025, 366.13990092182132}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1483 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{225.90811718740025, 363.38990092182132}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1484 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1480 + Rotation + 337.5 + + + Bounds + {{228.33784007224426, 366.04390208826476}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1485 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1473 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{181.88306202487647, 189.87345220332375}, {24, 24}} + Class + ShapedGraphic + ID + 1487 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 7} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1489 + Points + + {247.03052866201915, 197.98911229670802} + {244.5493022124096, 198.20507596438921} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{141.12649652521372, 216.30359109380208}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1490 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{143.07936603115925, 151.41628774488177}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1491 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{140.32936603115925, 148.66628774488177}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1492 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1488 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1494 + Points + + {140.84049430893771, 205.98493685076758} + {143.32172075854714, 205.76897318308625} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{230.74452644574279, 169.17045805367366}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1495 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{143.29165693979732, 151.05776140259383}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1496 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{140.54165693979732, 148.30776140259383}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1497 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1493 + Rotation + 337.5 + + + Bounds + {{142.97137982464162, 150.96176256903718}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1498 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1486 + Rotation + 337.5 + + + Class + Group + Graphics + + + Bounds + {{479.69876456560792, 313.23275528336626}, {24, 24}} + Class + ShapedGraphic + ID + 1500 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 8} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1502 + Points + + {544.84623120275069, 321.34841537675055} + {542.36500475314142, 321.56437904443163} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{438.94219906594537, 339.66289417384445}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1503 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{440.89506857189104, 274.77559082492428}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1504 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{438.14506857189104, 272.02559082492428}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1505 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1501 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1507 + Points + + {438.65619684966936, 329.34423993081015} + {441.13742329927879, 329.12827626312878} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{528.56022898647439, 292.52976113371614}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1508 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{441.107359480529, 274.41706448263619}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1509 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{438.357359480529, 271.66706448263619}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1510 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1506 + Rotation + 337.5 + + + Bounds + {{440.78708236537307, 274.3210656490798}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1511 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1499 + Rotation + 337.5 + + + Bounds + {{248.28852278518417, 235.77792148758147}, {8, 134}} + Class + ShapedGraphic + ID + 1512 + Rotation + 247.5 + Shape + Rectangle + + + Bounds + {{425.23537052568395, 232.45140364934065}, {8, 134}} + Class + ShapedGraphic + ID + 1513 + Rotation + 292.50006103515625 + Shape + Rectangle + + + Bounds + {{374.59821460510483, 282.06732351898592}, {8, 134}} + Class + ShapedGraphic + ID + 1514 + Rotation + 157.5 + Shape + Rectangle + + + Class + Group + Graphics + + + Bounds + {{394.33229525377027, 98.150584482954116}, {24, 24}} + Class + ShapedGraphic + ID + 1516 + Shape + Circle + Style + + shadow + + Draws + NO + + + Text + + Text + {\rtf1\ansi\ansicpg1252\cocoartf1187\cocoasubrtf370 +\cocoascreenfonts1{\fonttbl\f0\fswiss\fcharset0 Helvetica;} +{\colortbl;\red255\green255\blue255;} +\pard\tx560\tx1120\tx1680\tx2240\tx2800\tx3360\tx3920\tx4480\tx5040\tx5600\tx6160\tx6720\pardirnatural\qc + +\f0\fs24 \cf0 1} + VerticalPad + 0 + + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1518 + Points + + {459.47976189091298, 106.26624457633855} + {456.99853544130355, 106.48220824401977} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{353.57572975410767, 124.58072337343253}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1519 + Rotation + 67.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{355.52859926005328, 59.693420024512235}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1520 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{352.77859926005328, 56.943420024512235}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1521 + Rotation + 157.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1517 + Rotation + 337.5 + + + Class + Group + Graphics + + + Class + LineGraphic + ID + 1523 + Points + + {353.28972753783154, 114.26206913039776} + {355.77095398744109, 114.04610546271654} + + Style + + stroke + + HeadArrow + 0 + Legacy + + TailArrow + 0 + + + + + Bounds + {{443.19375967463657, 77.447590333303964}, {16, 18.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1524 + Rotation + 247.5 + Shape + HorizontalTriangle + Style + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + + + Bounds + {{355.74089016869129, 59.33489368222402}, {101.5, 101.5}} + Class + ShapedGraphic + HFlip + YES + ID + 1525 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + Bounds + {{352.99089016869129, 56.58489368222402}, {107, 107}} + Class + ShapedGraphic + HFlip + YES + ID + 1526 + Rotation + 337.5 + Shape + AdjustableArc + ShapeData + + endAngle + 72 + startAngle + 281 + + Style + + fill + + Draws + NO + + shadow + + Draws + NO + + + Text + + VerticalPad + 0 + + TextRelativeArea + {{0.10000000000000001, 0.14999999999999999}, {0.80000000000000004, 0.69999999999999996}} + + + ID + 1522 + Rotation + 337.5 + + + Bounds + {{355.42061305353548, 59.238894848667528}, {101.82337649086284, 101.82337649086284}} + Class + ShapedGraphic + ID + 1527 + Rotation + 337.5 + Shape + Circle + Style + + fill + + Color + + a + 0.78 + b + 0.234512 + g + 0.673128 + r + 0.148947 + + + shadow + + Draws + NO + + stroke + + Draws + NO + + + Text + + VerticalPad + 0 + + + + ID + 1515 + Rotation + 337.5 + + + Bounds + {{252.46989794607327, 160.88960179706885}, {8, 134}} + Class + ShapedGraphic + ID + 1528 + Rotation + 292.50006103515625 + Shape + Rectangle + + + Bounds + {{426.89836479441431, 161.02992820772749}, {8, 134}} + Class + ShapedGraphic + ID + 1529 + Rotation + 247.5 + Shape + Rectangle + + + Bounds + {{302.52032988683095, 284.35823469264687}, {8, 134}} + Class + ShapedGraphic + ID + 1530 + Rotation + 22.500026702880859 + Shape + Rectangle + + + Bounds + {{375.35774119930903, 108.51315184010758}, {8, 134}} + Class + ShapedGraphic + ID + 1531 + Rotation + 22.500026702880859 + Shape + Rectangle + + + Bounds + {{303.4692327942559, 110.3467678696648}, {8, 134}} + Class + ShapedGraphic + ID + 1532 + Rotation + 157.5 + Shape + Rectangle + + + ID + 1419 + Rotation + 45 + + + ID + 1415 + + + GridInfo + + HPages + 1 + KeepToScale + + Layers + + + Lock + NO + Name + Layer 1 + Print + YES + View + YES + + + LayoutInfo + + Animate + NO + circoMinDist + 18 + circoSeparation + 0.0 + layoutEngine + dot + neatoSeparation + 0.0 + twopiSeparation + 0.0 + + Orientation + 2 + PrintOnePage + + RowAlign + 1 + RowSpacing + 36 + SheetTitle + Rotor Assignment 3 + UniqueID + 4 + VPages + 1 + + + SmartAlignmentGuidesActive + YES + SmartDistanceGuidesActive + YES + UseEntirePage + + WindowInfo + + CurrentSheet + 4 + ExpandedCanvases + + + name + Canvas 1 + + + Frame + {{96, 56}, {1043, 822}} + ListView + + OutlineWidth + 142 + RightSidebar + + ShowRuler + + Sidebar + + SidebarWidth + 120 + VisibleRegion + {{-51, -33}, {908, 683}} + Zoom + 1 + ZoomValues + + + Canvas 1 + 1 + 0.5 + + + Rotor Assignments + 1 + 4 + + + Rotor Assignment 2 + 1 + 4 + + + Rotor Assignment 3 + 1 + 1 + + + Remote Control + 1 + 1 + + + + + From edf96fc8085510765c503350d29c96a2789bdbc0 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 28 Apr 2013 12:47:34 -0700 Subject: [PATCH 021/102] Remove some naked command invocations. --- makefiles/module.mk | 2 +- makefiles/setup.mk | 2 ++ makefiles/upload.mk | 13 ++++++++----- 3 files changed, 11 insertions(+), 6 deletions(-) diff --git a/makefiles/module.mk b/makefiles/module.mk index 86810627b2..59c67f574d 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -153,7 +153,7 @@ $(MODULE_COMMAND_FILES): exclude = $(dir $@)COMMAND.$(command).* $(MODULE_COMMAND_FILES): $(GLOBAL_DEPS) @$(REMOVE) -f $(exclude) @$(MKDIR) -p $(dir $@) - @echo "CMD: $(command)" + @$(ECHO) "CMD: $(command)" $(Q) $(TOUCH) $@ endif diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 8072ec7915..1111930937 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -72,6 +72,8 @@ export TOUCH = touch export MKDIR = mkdir export ECHO = echo export UNZIP_CMD = unzip +export PYTHON = python +export OPENOCD = openocd # # Host-specific paths, hacks and fixups diff --git a/makefiles/upload.mk b/makefiles/upload.mk index f23d6ae41a..5ef92728fe 100644 --- a/makefiles/upload.mk +++ b/makefiles/upload.mk @@ -25,7 +25,10 @@ endif all: upload-$(METHOD)-$(BOARD) upload-serial-px4fmu: $(BUNDLE) $(UPLOADER) - @python -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) + $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) + +upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER) + $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE) # # JTAG firmware uploading with OpenOCD @@ -33,9 +36,9 @@ upload-serial-px4fmu: $(BUNDLE) $(UPLOADER) JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg upload-jtag-px4fmu: all - @echo Attempting to flash PX4FMU board via JTAG - @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown + @$(ECHO) Attempting to flash PX4FMU board via JTAG + $(Q) $(OPENOCD) -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown upload-jtag-px4io: all - @echo Attempting to flash PX4IO board via JTAG - @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown + @$(ECHO) Attempting to flash PX4IO board via JTAG + $(Q) $(OPENOCD) -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown From 8d3a738b7011ab77bab7ac89c5314fdc7c663890 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 28 Apr 2013 13:00:32 -0700 Subject: [PATCH 022/102] Remove some trash files. --- src/modules/position_estimator/.context | 0 src/modules/uORB/.context | 0 2 files changed, 0 insertions(+), 0 deletions(-) delete mode 100644 src/modules/position_estimator/.context delete mode 100644 src/modules/uORB/.context diff --git a/src/modules/position_estimator/.context b/src/modules/position_estimator/.context deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/modules/uORB/.context b/src/modules/uORB/.context deleted file mode 100644 index e69de29bb2..0000000000 From c6b7eb1224426d9ec2e6d59a3df4c7443449109a Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 28 Apr 2013 13:00:49 -0700 Subject: [PATCH 023/102] Remove obsoleted file. --- src/modules/attitude_estimator_ekf/Makefile | 57 --------------------- 1 file changed, 57 deletions(-) delete mode 100755 src/modules/attitude_estimator_ekf/Makefile diff --git a/src/modules/attitude_estimator_ekf/Makefile b/src/modules/attitude_estimator_ekf/Makefile deleted file mode 100755 index 46a54c6607..0000000000 --- a/src/modules/attitude_estimator_ekf/Makefile +++ /dev/null @@ -1,57 +0,0 @@ -############################################################################ -# -# Copyright (C) 2012 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ - -APPNAME = attitude_estimator_ekf -PRIORITY = SCHED_PRIORITY_DEFAULT -STACKSIZE = 2048 - -CXXSRCS = attitude_estimator_ekf_main.cpp - -CSRCS = attitude_estimator_ekf_params.c \ - codegen/eye.c \ - codegen/attitudeKalmanfilter.c \ - codegen/mrdivide.c \ - codegen/rdivide.c \ - codegen/attitudeKalmanfilter_initialize.c \ - codegen/attitudeKalmanfilter_terminate.c \ - codegen/rt_nonfinite.c \ - codegen/rtGetInf.c \ - codegen/rtGetNaN.c \ - codegen/norm.c \ - codegen/cross.c - - -# XXX this is *horribly* broken -INCLUDES += $(TOPDIR)/../mavlink/include/mavlink - -include $(APPDIR)/mk/app.mk From ca5dcc11a7754d38e3b5f63bcb708e106fb2a3cd Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 18:32:30 +0200 Subject: [PATCH 024/102] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default --- apps/drivers/mkblctrl/mkblctrl.cpp | 83 ++++++++++++++++++++---------- 1 file changed, 55 insertions(+), 28 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index 664271bee5..bcdb80b5d0 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -121,6 +121,7 @@ public: int set_motor_test(bool motortest); int set_px4mode(int px4mode); int set_frametype(int frametype); + unsigned int mk_check_for_blctrl(unsigned int count, unsigned int showOutput); private: static const unsigned _max_actuators = MAX_MOTORS; @@ -176,7 +177,6 @@ private: int gpio_ioctl(file *filp, int cmd, unsigned long arg); int mk_servo_arm(bool status); - int mk_check_for_blctrl(unsigned int count); int mk_servo_set(unsigned int chan, float val); int mk_servo_set_test(unsigned int chan, float val); int mk_servo_test(unsigned int chan); @@ -350,11 +350,11 @@ MK::set_mode(Mode mode) switch (mode) { case MODE_2PWM: if(_num_outputs == 4) { - debug("MODE_QUAD"); + //debug("MODE_QUAD"); } else if(_num_outputs == 6) { - debug("MODE_HEXA"); + //debug("MODE_HEXA"); } else if(_num_outputs == 8) { - debug("MODE_OCTO"); + //debug("MODE_OCTO"); } //up_pwm_servo_init(0x3); up_pwm_servo_deinit(); @@ -363,11 +363,11 @@ MK::set_mode(Mode mode) case MODE_4PWM: if(_num_outputs == 4) { - debug("MODE_QUADRO"); + //debug("MODE_QUADRO"); } else if(_num_outputs == 6) { - debug("MODE_HEXA"); + //debug("MODE_HEXA"); } else if(_num_outputs == 8) { - debug("MODE_OCTO"); + //debug("MODE_OCTO"); } //up_pwm_servo_init(0xf); up_pwm_servo_deinit(); @@ -447,8 +447,13 @@ MK::set_motor_count(unsigned count) memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); } - /* check for connected blctrls */ - mk_check_for_blctrl(_num_outputs); + if(_num_outputs == 4) { + fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); + } else if(_num_outputs == 6) { + fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); + } else if(_num_outputs == 8) { + fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); + } return OK; } @@ -502,7 +507,6 @@ MK::task_main() memset(&rc_in, 0, sizeof(rc_in)); rc_in.input_source = RC_INPUT_SOURCE_PX4FMU_PPM; - log("starting"); long update_rate_in_us = 0; @@ -666,10 +670,10 @@ MK::mk_servo_arm(bool status) } -int -MK::mk_check_for_blctrl(unsigned int count) +unsigned int +MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) { - _retries = 10; + _retries = 50; uint8_t foundMotorCount = 0; for(unsigned i=0; iset_frametype(frametype); + /* motortest if enabled */ + g_mk->set_motor_test(motortest); + + /* (re)set count of used motors */ - g_mk->set_motor_count(motorcount); + ////g_mk->set_motor_count(motorcount); + /* count used motors */ + + do { + if(g_mk->mk_check_for_blctrl(8, 0) != 0) { + shouldStop = 3; + } else { + shouldStop++; + } + sleep(1); + } while ( shouldStop != 3); + + g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); /* (re)set the PWM output mode */ g_mk->set_mode(servo_mode); - /* motortest if enabled */ - g_mk->set_motor_test(motortest); if ((servo_mode != MK::MODE_NONE) && (update_rate != 0)) g_mk->set_pwm_rate(update_rate); @@ -1335,15 +1359,19 @@ mkblctrl_main(int argc, char *argv[]) int motorcount = 0; int bus = 1; bool motortest = false; - int px4mode = MAPPING_MK; + int px4mode = MAPPING_PX4; int frametype = FRAME_PLUS; // + plus is default + new_mode = PORT_FULL_PWM; + motorcount = 8; + /* * Mode switches. * * XXX use getopt? */ for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + /* if (!strcmp(argv[i], "mode_quad")) { new_mode = PORT_FULL_PWM; motorcount = 4; @@ -1354,8 +1382,10 @@ mkblctrl_main(int argc, char *argv[]) new_mode = PORT_FULL_PWM; motorcount = 8; } + */ /* look for the optional update rate for the supported modes */ + /* if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { if (argc > i + 1) { pwm_update_rate_in_hz = atoi(argv[i + 1]); @@ -1365,6 +1395,7 @@ mkblctrl_main(int argc, char *argv[]) } } + */ /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { @@ -1376,9 +1407,10 @@ mkblctrl_main(int argc, char *argv[]) } /* look for the optional frame parameter */ - if (strcmp(argv[i], "-f") == 0 || strcmp(argv[i], "--frame") == 0) { + if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) { if (argc > i + 1) { if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { + px4mode = MAPPING_MK; if(strcmp(argv[i + 1], "+") == 0) { frametype = FRAME_PLUS; } else { @@ -1388,16 +1420,11 @@ mkblctrl_main(int argc, char *argv[]) errx(1, "only + or x for frametype supported !"); } } else { - errx(1, "missing argument for frametype (-f)"); + errx(1, "missing argument for mkmode (-mkmode)"); return 1; } } - /* look for the optional geometry parameter */ - if (strcmp(argv[i], "-px4mode") == 0) { - px4mode = MAPPING_PX4; - } - /* look for the optional test parameter */ if (strcmp(argv[i], "-t") == 0) { motortest = true; @@ -1407,7 +1434,7 @@ mkblctrl_main(int argc, char *argv[]) if(new_mode == PORT_MODE_UNSET) { fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); - fprintf(stderr, " mode_quad, mode_hexa, mode_octo [-b i2c_bus_number] [-u update_rate_in_hz] [-t motortest] [-px4mode] [-f frame{+/x}]\n"); + fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest]\n"); exit(1); } From 130c7a353055da628518f6de1bbd58c855fad5bd Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 19:56:50 +0200 Subject: [PATCH 025/102] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default - with safety shutdown --- apps/drivers/mkblctrl/mkblctrl.cpp | 42 +++++------------------------- 1 file changed, 6 insertions(+), 36 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index bcdb80b5d0..057ee2128d 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -311,9 +311,6 @@ MK::init(unsigned motors) /* reset GPIOs */ gpio_reset(); - /* check for connected blctrls */ - //mk_check_for_blctrl(_num_outputs); - /* start the IO interface task */ _task = task_spawn("mkblctrl", SCHED_DEFAULT, @@ -717,16 +714,13 @@ MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) for(unsigned i=0; i< count; i++) { fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i,Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature); } + + if(foundMotorCount == 0) { + _task_should_exit = true; + } } return foundMotorCount; - /* - if(foundMotorCount == count) { - return true; - } else { - return false; - } - */ } @@ -1302,12 +1296,12 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, do { if(g_mk->mk_check_for_blctrl(8, 0) != 0) { - shouldStop = 3; + shouldStop = 4; } else { shouldStop++; } sleep(1); - } while ( shouldStop != 3); + } while ( shouldStop < 3); g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); @@ -1371,31 +1365,7 @@ mkblctrl_main(int argc, char *argv[]) * XXX use getopt? */ for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ - /* - if (!strcmp(argv[i], "mode_quad")) { - new_mode = PORT_FULL_PWM; - motorcount = 4; - } else if (!strcmp(argv[i], "mode_hexa")) { - new_mode = PORT_FULL_PWM; - motorcount = 6; - } else if (!strcmp(argv[i], "mode_octo")) { - new_mode = PORT_FULL_PWM; - motorcount = 8; - } - */ - /* look for the optional update rate for the supported modes */ - /* - if (strcmp(argv[i], "-u") == 0 || strcmp(argv[i], "--update-rate") == 0) { - if (argc > i + 1) { - pwm_update_rate_in_hz = atoi(argv[i + 1]); - } else { - errx(1, "missing argument for update rate (-u)"); - return 1; - } - } - - */ /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { From ee4a93d668540dea3b7b33eafb94a888f802f466 Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 29 Apr 2013 20:42:06 +0200 Subject: [PATCH 026/102] BLCtrl 2.0 testing - currently only 8 Bit resolution - motor detection and px4 mode as default - with safety shutdown - fix --- apps/drivers/mkblctrl/mkblctrl.cpp | 89 ++++++++++++++++-------------- 1 file changed, 48 insertions(+), 41 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index 057ee2128d..e70bd16945 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -121,7 +121,7 @@ public: int set_motor_test(bool motortest); int set_px4mode(int px4mode); int set_frametype(int frametype); - unsigned int mk_check_for_blctrl(unsigned int count, unsigned int showOutput); + unsigned int mk_check_for_blctrl(unsigned int count, bool showOutput); private: static const unsigned _max_actuators = MAX_MOTORS; @@ -412,47 +412,54 @@ MK::set_frametype(int frametype) int MK::set_motor_count(unsigned count) { - _num_outputs = count; + if(count > 0) { - if(_px4mode == MAPPING_MK) { - if(_frametype == FRAME_PLUS) { - fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); - } else if(_frametype == FRAME_X) { - fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + _num_outputs = count; + + if(_px4mode == MAPPING_MK) { + if(_frametype == FRAME_PLUS) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: +\n"); + } else if(_frametype == FRAME_X) { + fprintf(stderr, "[mkblctrl] addresstanslator for Mikrokopter addressing used. Frametype: X\n"); + } + if(_num_outputs == 4) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); + } + } else if(_num_outputs == 6) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); + } + } else if(_num_outputs == 8) { + if(_frametype == FRAME_PLUS) { + memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); + } else if(_frametype == FRAME_X) { + memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); + } + } + } else { + fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); + memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); } + if(_num_outputs == 4) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_quad_plus, sizeof(blctrlAddr_quad_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_quad_x, sizeof(blctrlAddr_quad_x)); - } - } else if(_num_outputs == 6) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_hexa_plus, sizeof(blctrlAddr_hexa_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_hexa_x, sizeof(blctrlAddr_hexa_x)); - } - } else if(_num_outputs == 8) { - if(_frametype == FRAME_PLUS) { - memcpy(&addrTranslator, &blctrlAddr_octo_plus, sizeof(blctrlAddr_octo_plus)); - } else if(_frametype == FRAME_X) { - memcpy(&addrTranslator, &blctrlAddr_octo_x, sizeof(blctrlAddr_octo_x)); - } + fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); + } else if(_num_outputs == 6) { + fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); + } else if(_num_outputs == 8) { + fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); } + + return OK; + } else { - fprintf(stderr, "[mkblctrl] PX4 native addressing used.\n"); - memcpy(&addrTranslator, &blctrlAddr_px4, sizeof(blctrlAddr_px4)); + return -1; } - if(_num_outputs == 4) { - fprintf(stderr, "[mkblctrl] Quadrocopter Mode (4)\n"); - } else if(_num_outputs == 6) { - fprintf(stderr, "[mkblctrl] Hexacopter Mode (6)\n"); - } else if(_num_outputs == 8) { - fprintf(stderr, "[mkblctrl] Octocopter Mode (8)\n"); - } - - return OK; } int @@ -668,7 +675,7 @@ MK::mk_servo_arm(bool status) unsigned int -MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) +MK::mk_check_for_blctrl(unsigned int count, bool showOutput) { _retries = 50; uint8_t foundMotorCount = 0; @@ -709,13 +716,13 @@ MK::mk_check_for_blctrl(unsigned int count, unsigned int showOutput) } } - if(showOutput == 1) { + if(showOutput) { fprintf(stderr, "[mkblctrl] MotorsFound: %i\n",foundMotorCount); - for(unsigned i=0; i< count; i++) { + for(unsigned i=0; i< foundMotorCount; i++) { fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i,Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature); } - if(foundMotorCount == 0) { + if(foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) { _task_should_exit = true; } } @@ -1295,7 +1302,7 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, /* count used motors */ do { - if(g_mk->mk_check_for_blctrl(8, 0) != 0) { + if(g_mk->mk_check_for_blctrl(8, false) != 0) { shouldStop = 4; } else { shouldStop++; @@ -1303,7 +1310,7 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, sleep(1); } while ( shouldStop < 3); - g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, 1)); + g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true)); /* (re)set the PWM output mode */ g_mk->set_mode(servo_mode); From ddf1b27697dd5edd8e8282c24ad35cb938dbf3c8 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 2 May 2013 07:10:23 +0200 Subject: [PATCH 027/102] Added a config for quads with a wide arm config. --- ROMFS/Makefile | 3 ++- apps/systemlib/mixer/mixer.h | 1 + apps/systemlib/mixer/mixer_multirotor.cpp | 11 +++++++++++ apps/systemlib/mixer/multi_tables | 9 ++++++++- 4 files changed, 22 insertions(+), 2 deletions(-) diff --git a/ROMFS/Makefile b/ROMFS/Makefile index 11a4650fa6..ecd15d5e27 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -32,7 +32,8 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \ $(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \ $(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \ - $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ + $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ + $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_w.mix \ $(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \ $(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \ $(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \ diff --git a/apps/systemlib/mixer/mixer.h b/apps/systemlib/mixer/mixer.h index 40d37fce2b..bbfa130a9d 100644 --- a/apps/systemlib/mixer/mixer.h +++ b/apps/systemlib/mixer/mixer.h @@ -419,6 +419,7 @@ public: QUAD_X = 0, /**< quad in X configuration */ QUAD_PLUS, /**< quad in + configuration */ QUAD_V, /**< quad in V configuration */ + QUAD_WIDE, /**< quad in wide configuration */ HEX_X, /**< hex in X configuration */ HEX_PLUS, /**< hex in + configuration */ OCTA_X, diff --git a/apps/systemlib/mixer/mixer_multirotor.cpp b/apps/systemlib/mixer/mixer_multirotor.cpp index d79811c0ff..8ded0b05c1 100644 --- a/apps/systemlib/mixer/mixer_multirotor.cpp +++ b/apps/systemlib/mixer/mixer_multirotor.cpp @@ -88,6 +88,12 @@ const MultirotorMixer::Rotor _config_quad_v[] = { { 0.927184, 0.374607, -1.00 }, { -0.694658, -0.719340, -1.00 }, }; +const MultirotorMixer::Rotor _config_quad_wide[] = { + { -0.927184, 0.374607, 1.00 }, + { 0.777146, -0.629320, 1.00 }, + { 0.927184, 0.374607, -1.00 }, + { -0.777146, -0.629320, -1.00 }, +}; const MultirotorMixer::Rotor _config_hex_x[] = { { -1.000000, 0.000000, -1.00 }, { 1.000000, 0.000000, 1.00 }, @@ -128,6 +134,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME &_config_quad_x[0], &_config_quad_plus[0], &_config_quad_v[0], + &_config_quad_wide[0], &_config_hex_x[0], &_config_hex_plus[0], &_config_octa_x[0], @@ -137,6 +144,7 @@ const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = { 4, /* quad_x */ 4, /* quad_plus */ 4, /* quad_v */ + 4, /* quad_wide */ 6, /* hex_x */ 6, /* hex_plus */ 8, /* octa_x */ @@ -195,6 +203,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl } else if (!strcmp(geomname, "4v")) { geometry = MultirotorMixer::QUAD_V; + } else if (!strcmp(geomname, "4w")) { + geometry = MultirotorMixer::QUAD_WIDE; + } else if (!strcmp(geomname, "6+")) { geometry = MultirotorMixer::HEX_PLUS; diff --git a/apps/systemlib/mixer/multi_tables b/apps/systemlib/mixer/multi_tables index 19a8239a6d..683c630409 100755 --- a/apps/systemlib/mixer/multi_tables +++ b/apps/systemlib/mixer/multi_tables @@ -27,6 +27,13 @@ set quad_v { 136 CW } +set quad_wide { + 68 CCW + -129 CCW + -68 CW + 129 CW +} + set hex_x { 90 CW -90 CCW @@ -67,7 +74,7 @@ set octa_plus { 90 CW } -set tables {quad_x quad_plus quad_v hex_x hex_plus octa_x octa_plus} +set tables {quad_x quad_plus quad_v quad_wide hex_x hex_plus octa_x octa_plus} proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]} From d9da4352d590401ec5caeef926cf25109da393e9 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 2 May 2013 07:13:07 +0200 Subject: [PATCH 028/102] Makefile correction. --- ROMFS/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/Makefile b/ROMFS/Makefile index ecd15d5e27..e776684212 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -33,7 +33,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \ $(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \ $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ - $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_w.mix \ + $(SRCROOT)/mixers/FMU_quad_w.mix~mixers/FMU_quad_w.mix \ $(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \ $(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \ $(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \ From 1dbbdcfa48f8acbf4bed5c160ab3acd0cf293127 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 2 May 2013 08:41:02 +0200 Subject: [PATCH 029/102] Add the missing mixer file. --- ROMFS/mixers/FMU_quad_w.mix | 6 ++++++ 1 file changed, 6 insertions(+) create mode 100644 ROMFS/mixers/FMU_quad_w.mix diff --git a/ROMFS/mixers/FMU_quad_w.mix b/ROMFS/mixers/FMU_quad_w.mix new file mode 100644 index 0000000000..81b4af30b2 --- /dev/null +++ b/ROMFS/mixers/FMU_quad_w.mix @@ -0,0 +1,6 @@ +Multirotor mixer for PX4FMU +=========================== + +This file defines a single mixer for a quadrotor with a wide configuration. All controls are mixed 100%. + +R: 4w 10000 10000 10000 0 From b9b75a24045da332644ce397d2777d9d554ff39f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 2 May 2013 22:35:16 +0200 Subject: [PATCH 030/102] Hotfix: Provide a FMU + IO on quad start script --- ROMFS/Makefile | 3 +- ROMFS/scripts/rc.IO_QUAD | 107 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 109 insertions(+), 1 deletion(-) create mode 100644 ROMFS/scripts/rc.IO_QUAD diff --git a/ROMFS/Makefile b/ROMFS/Makefile index 11a4650fa6..5ff079a930 100644 --- a/ROMFS/Makefile +++ b/ROMFS/Makefile @@ -24,6 +24,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \ $(SRCROOT)/scripts/rc.usb~init.d/rc.usb \ $(SRCROOT)/scripts/rc.hil~init.d/rc.hil \ + $(SRCROOT)/scripts/rc.IO_QUAD~scripts/rc.IO_QUAD \ $(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \ $(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \ $(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \ @@ -32,7 +33,7 @@ ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \ $(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \ $(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \ $(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \ - $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ + $(SRCROOT)/mixers/FMU_quad_v.mix~mixers/FMU_quad_v.mix \ $(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \ $(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \ $(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \ diff --git a/ROMFS/scripts/rc.IO_QUAD b/ROMFS/scripts/rc.IO_QUAD new file mode 100644 index 0000000000..287cb0483b --- /dev/null +++ b/ROMFS/scripts/rc.IO_QUAD @@ -0,0 +1,107 @@ +#!nsh + +# Disable USB and autostart +set USB no +set MODE quad + +# +# Start the ORB (first app to start) +# +uorb start + +# +# Load microSD params +# +echo "[init] loading microSD params" +param select /fs/microsd/parameters +if [ -f /fs/microsd/parameters ] +then + param load /fs/microsd/parameters +fi + +# +# Force some key parameters to sane values +# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor +# see https://pixhawk.ethz.ch/mavlink/ +# +param set MAV_TYPE 2 + +# +# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell) +# +if [ -f /fs/microsd/px4io.bin ] +then + echo "PX4IO Firmware found. Checking Upgrade.." + if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + then + echo "No newer version, skipping upgrade." + else + echo "Loading /fs/microsd/px4io.bin" + if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log + then + cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current + echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log + else + echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log + echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode" + fi + fi +fi + +# +# Start MAVLink (depends on orb) +# +mavlink start -d /dev/ttyS1 -b 57600 +usleep 5000 + +# +# Start the commander (depends on orb, mavlink) +# +commander start + +# +# Start PX4IO interface (depends on orb, commander) +# +px4io start + +# +# Allow PX4IO to recover from midair restarts. +# this is very unlikely, but quite safe and robust. +px4io recovery + +# +# Start the sensors (depends on orb, px4io) +# +sh /etc/init.d/rc.sensors + +# +# Start GPS interface (depends on orb) +# +gps start + +# +# Start the attitude estimator (depends on orb) +# +attitude_estimator_ekf start + +# +# Load mixer and start controllers (depends on px4io) +# +mixer load /dev/pwm_output /etc/mixers/FMU_quad_+.mix +multirotor_att_control start + +# +# Start logging +# +#sdlog start -s 4 + +# +# Start system state +# +if blinkm start +then + echo "using BlinkM for state indication" + blinkm systemstate +else + echo "no BlinkM found, OK." +fi \ No newline at end of file From 6e8c1148d5fb6567974f3e5464e45637dc6ce68b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2013 11:42:31 +1000 Subject: [PATCH 031/102] build: allow absolute paths for module sources --- makefiles/module.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/module.mk b/makefiles/module.mk index 59c67f574d..0fe6f0ffec 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -183,7 +183,7 @@ module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES) # Locate sources (allows relative source paths in module.mk) # define SRC_SEARCH - $(abspath $(firstword $(wildcard $(MODULE_SRC)/$1) MISSING_$1)) + $(abspath $(firstword $(wildcard $1) $(wildcard $(MODULE_SRC)/$1) MISSING_$1)) endef ABS_SRCS ?= $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src))) From aa9275c29ce90644448f0260d782ea68f21eacc7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2013 11:42:56 +1000 Subject: [PATCH 032/102] build: allow additional flags to be passed via EXTRAFLAGS this allows for flags needed for the APM build --- makefiles/toolchain_gnu-arm-eabi.mk | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 5e6a5bf04b..32a2773732 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -189,7 +189,7 @@ DEP_INCLUDES = $(subst .o,.d,$(OBJS)) define COMPILE @$(ECHO) "CC: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2 + $(Q) $(CC) -MD -c $(CFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 endef # Compile C++ source $1 to $2 @@ -198,7 +198,7 @@ endef define COMPILEXX @$(ECHO) "CXX: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2 + $(Q) $(CXX) -MD -c $(CXXFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 endef # Assemble $1 into $2 @@ -206,7 +206,7 @@ endef define ASSEMBLE @$(ECHO) "AS: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2 + $(Q) $(CC) -c $(AFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 endef # Produce partially-linked $1 from files in $2 From d0122dccfc28869414f0e9cd2cb1d9f131c3fd20 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 4 May 2013 18:44:37 +1000 Subject: [PATCH 033/102] hmc5883: fixed use of onboard I2C compass --- src/drivers/hmc5883/hmc5883.cpp | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index c406a7588a..78eda327c3 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1225,19 +1225,25 @@ start() /* create the driver, attempt expansion bus first */ g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION); + if (g_dev != nullptr && OK != g_dev->init()) { + delete g_dev; + g_dev = nullptr; + } + #ifdef PX4_I2C_BUS_ONBOARD /* if this failed, attempt onboard sensor */ - if (g_dev == nullptr) + if (g_dev == nullptr) { g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD); + if (g_dev != nullptr && OK != g_dev->init()) { + goto fail; + } + } #endif if (g_dev == nullptr) goto fail; - if (OK != g_dev->init()) - goto fail; - /* set the poll rate to default, starts automatic data collection */ fd = open(MAG_DEVICE_PATH, O_RDONLY); From a627f6c0eba3cfb0471b0ff88652d85c6d7cb0ca Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Mar 2013 11:06:33 +1100 Subject: [PATCH 034/102] otgfsdev: removed a DEBUGASSERT() that causes a crash on windows reconnect when windows reconnects to a ACM device, this assert sometimes triggered. The case it is looking for is handled further down. --- nuttx/arch/arm/src/stm32/stm32_otgfsdev.c | 1 - 1 file changed, 1 deletion(-) diff --git a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c index 2c9ae4cacb..0fcd463e05 100644 --- a/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c +++ b/nuttx/arch/arm/src/stm32/stm32_otgfsdev.c @@ -1512,7 +1512,6 @@ static inline void stm32_ep0out_receive(FAR struct stm32_ep_s *privep, int bcnt) DEBUGASSERT(privep && privep->ep.priv); priv = (FAR struct stm32_usbdev_s *)privep->ep.priv; - DEBUGASSERT(priv->ep0state == EP0STATE_SETUP_OUT); ullvdbg("EP0: bcnt=%d\n", bcnt); usbtrace(TRACE_READ(EP0), bcnt); From b06098a5406cf3269a313362b43d7f47b160933b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 17 Apr 2013 21:19:19 +1000 Subject: [PATCH 035/102] libdtoa: fixed handling of NaN and Infinity otherwise we print thousands of 00000 characters --- nuttx/libc/stdio/lib_libdtoa.c | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/nuttx/libc/stdio/lib_libdtoa.c b/nuttx/libc/stdio/lib_libdtoa.c index 29f61fd76e..84e3ee50b7 100644 --- a/nuttx/libc/stdio/lib_libdtoa.c +++ b/nuttx/libc/stdio/lib_libdtoa.c @@ -43,6 +43,7 @@ /**************************************************************************** * Included Files ****************************************************************************/ +#include /**************************************************************************** * Pre-processor Definitions @@ -104,6 +105,13 @@ static void zeroes(FAR struct lib_outstream_s *obj, int nzeroes) * Private Functions ****************************************************************************/ +static void lib_dtoa_string(FAR struct lib_outstream_s *obj, const char *str) +{ + while (*str) { + obj->put(obj, *str++); + } +} + /**************************************************************************** * Name: lib_dtoa * @@ -138,8 +146,21 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, int dsgn; /* Unused sign indicator */ int i; - /* Non-zero... positive or negative */ + /* special handling for NaN and Infinity */ + if (isnan(value)) { + lib_dtoa_string(obj, "NaN"); + return; + } + if (isinf(value)) { + if (value < 0.0d) { + obj->put(obj, '-'); + } + lib_dtoa_string(obj, "Infinity"); + return; + } + /* Non-zero... positive or negative */ + if (value < 0) { value = -value; From 421253e6db6c5e716c84ac505a8caef679ea97ee Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 21 Apr 2013 14:28:56 +1000 Subject: [PATCH 036/102] px4io: allow set of output rates above 400 and below 50 let the IO board decide if the rate is reasonable, and limit it there this fixes the rates on ArduCopter, which try for 490 --- src/drivers/px4io/px4io.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 4c2f1736f9..d8b5c51c43 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1336,11 +1336,7 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) case PWM_SERVO_SET_UPDATE_RATE: /* set the requested alternate rate */ - if ((arg >= 50) && (arg <= 400)) { /* TODO: we could go higher for e.g. TurboPWM */ - ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE, arg); - } else { - ret = -EINVAL; - } + ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE, arg); break; case PWM_SERVO_SELECT_UPDATE_RATE: { From fc572906b7693d910ded443632e8608b200a7933 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 Apr 2013 20:11:25 +1000 Subject: [PATCH 037/102] px4io: ensure upload device is closed after use this should release it for PWM use --- src/drivers/px4io/uploader.cpp | 17 ++++++++++++++++- 1 file changed, 16 insertions(+), 1 deletion(-) diff --git a/src/drivers/px4io/uploader.cpp b/src/drivers/px4io/uploader.cpp index 9a67875e86..15524c3aeb 100644 --- a/src/drivers/px4io/uploader.cpp +++ b/src/drivers/px4io/uploader.cpp @@ -127,6 +127,8 @@ PX4IO_Uploader::upload(const char *filenames[]) if (ret != OK) { /* this is immediately fatal */ log("bootloader not responding"); + close(_io_fd); + _io_fd = -1; return -EIO; } @@ -145,18 +147,25 @@ PX4IO_Uploader::upload(const char *filenames[]) if (filename == NULL) { log("no firmware found"); + close(_io_fd); + _io_fd = -1; return -ENOENT; } struct stat st; if (stat(filename, &st) != 0) { log("Failed to stat %s - %d\n", filename, (int)errno); + close(_io_fd); + _io_fd = -1; return -errno; } fw_size = st.st_size; - if (_fw_fd == -1) + if (_fw_fd == -1) { + close(_io_fd); + _io_fd = -1; return -ENOENT; + } /* do the usual program thing - allow for failure */ for (unsigned retries = 0; retries < 1; retries++) { @@ -167,6 +176,8 @@ PX4IO_Uploader::upload(const char *filenames[]) if (ret != OK) { /* this is immediately fatal */ log("bootloader not responding"); + close(_io_fd); + _io_fd = -1; return -EIO; } } @@ -178,6 +189,8 @@ PX4IO_Uploader::upload(const char *filenames[]) log("found bootloader revision: %d", bl_rev); } else { log("found unsupported bootloader revision %d, exiting", bl_rev); + close(_io_fd); + _io_fd = -1; return OK; } } @@ -221,6 +234,8 @@ PX4IO_Uploader::upload(const char *filenames[]) } close(_fw_fd); + close(_io_fd); + _io_fd = -1; return ret; } From ff7712ca3e752141e54f3cbf15198a62429617f7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 Apr 2013 20:13:03 +1000 Subject: [PATCH 038/102] pwm: added -m option this allows setting of the channel mask directly, which is useful for testing --- src/systemcmds/pwm/pwm.c | 19 +++++++++++++++++-- 1 file changed, 17 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index de7a531993..08e6c88dfa 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -71,13 +71,14 @@ usage(const char *reason) warnx("%s", reason); errx(1, "usage:\n" - "pwm [-v] [-d ] [-u ] [-c ] [arm|disarm] [ ...]\n" + "pwm [-v] [-d ] [-u ] [-c ] [-m chanmask ] [arm|disarm] [ ...]\n" " -v Print information about the PWM device\n" " PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n" " PWM update rate for channels in \n" " Channel group that should update at the alternate rate (may be specified more than once)\n" " arm | disarm Arm or disarm the ouptut\n" " ... PWM output values in microseconds to assign to the PWM outputs\n" + " Directly supply alt rate channel mask\n" "\n" "When -c is specified, any channel groups not listed with -c will update at the default rate.\n" ); @@ -96,11 +97,12 @@ pwm_main(int argc, char *argv[]) int ret; char *ep; unsigned group; + int32_t set_mask = -1; if (argc < 2) usage(NULL); - while ((ch = getopt(argc, argv, "c:d:u:v")) != EOF) { + while ((ch = getopt(argc, argv, "c:d:u:vm:")) != EOF) { switch (ch) { case 'c': group = strtoul(optarg, &ep, 0); @@ -120,6 +122,12 @@ pwm_main(int argc, char *argv[]) usage("bad alt_rate value"); break; + case 'm': + set_mask = strtol(optarg, &ep, 0); + if (*ep != '\0') + usage("bad set_mask value"); + break; + case 'v': print_info = true; break; @@ -143,6 +151,13 @@ pwm_main(int argc, char *argv[]) err(1, "PWM_SERVO_SET_UPDATE_RATE (check rate for sanity)"); } + /* directly supplied channel mask */ + if (set_mask != -1) { + ret = ioctl(fd, PWM_SERVO_SELECT_UPDATE_RATE, set_mask); + if (ret != OK) + err(1, "PWM_SERVO_SELECT_UPDATE_RATE"); + } + /* assign alternate rate to channel groups */ if (alt_channels_set) { uint32_t mask = 0; From a153ee529f68e9b52805b8c77da1ec2bf0e54210 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 Apr 2013 22:22:16 +1000 Subject: [PATCH 039/102] libdtoa: don't print trailing zeros if no decimal is printed --- nuttx/libc/stdio/lib_libdtoa.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/nuttx/libc/stdio/lib_libdtoa.c b/nuttx/libc/stdio/lib_libdtoa.c index 84e3ee50b7..395a55b61b 100644 --- a/nuttx/libc/stdio/lib_libdtoa.c +++ b/nuttx/libc/stdio/lib_libdtoa.c @@ -145,6 +145,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, int nchars; /* Number of characters to print */ int dsgn; /* Unused sign indicator */ int i; + bool done_decimal_point = false; /* special handling for NaN and Infinity */ if (isnan(value)) { @@ -199,6 +200,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, if (prec > 0 || IS_ALTFORM(flags)) { obj->put(obj, '.'); + done_decimal_point = true; /* Always print at least one digit to the right of the decimal point. */ @@ -224,6 +226,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, /* Print the decimal point */ obj->put(obj, '.'); + done_decimal_point = true; /* Print any leading zeros to the right of the decimal point */ @@ -270,6 +273,7 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, /* Print the decimal point */ obj->put(obj, '.'); + done_decimal_point = true; /* Always print at least one digit to the right of the decimal * point. @@ -306,8 +310,9 @@ static void lib_dtoa(FAR struct lib_outstream_s *obj, int fmt, int prec, } /* Finally, print any trailing zeroes */ - - zeroes(obj, prec); + if (done_decimal_point) { + zeroes(obj, prec); + } /* Is this memory supposed to be freed or not? */ From 953acbe65014e2b2305c4338ca3711622fda3fdd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 25 Apr 2013 22:22:45 +1000 Subject: [PATCH 040/102] libvsprintf: fixed handling of "%f" to print precision 6 --- nuttx/libc/stdio/lib_libvsprintf.c | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/nuttx/libc/stdio/lib_libvsprintf.c b/nuttx/libc/stdio/lib_libvsprintf.c index 9a391610dc..3d26ff810e 100644 --- a/nuttx/libc/stdio/lib_libvsprintf.c +++ b/nuttx/libc/stdio/lib_libvsprintf.c @@ -1215,7 +1215,7 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a fmt = FMT_RJUST; width = 0; #ifdef CONFIG_LIBC_FLOATINGPOINT - trunc = 0; + trunc = 6; #endif #endif @@ -1245,6 +1245,9 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a { #ifndef CONFIG_NOPRINTF_FIELDWIDTH fmt = FMT_RJUST0; + if (IS_HASDOT(flags)) { + trunc = 0; + } #endif } #if 0 From 5b3844621ca1c0a6181e49166c5c12f3000f6802 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 28 Apr 2013 14:07:50 +1000 Subject: [PATCH 041/102] stdio: fixed build error for stdio on px4io --- nuttx/libc/stdio/lib_libvsprintf.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/nuttx/libc/stdio/lib_libvsprintf.c b/nuttx/libc/stdio/lib_libvsprintf.c index 3d26ff810e..2cc7950f7b 100644 --- a/nuttx/libc/stdio/lib_libvsprintf.c +++ b/nuttx/libc/stdio/lib_libvsprintf.c @@ -1245,9 +1245,11 @@ int lib_vsprintf(FAR struct lib_outstream_s *obj, FAR const char *src, va_list a { #ifndef CONFIG_NOPRINTF_FIELDWIDTH fmt = FMT_RJUST0; +#ifdef CONFIG_LIBC_FLOATINGPOINT if (IS_HASDOT(flags)) { trunc = 0; } +#endif #endif } #if 0 From 44015d69154062d42ecc3aa0c9b25d7019bd5a71 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 1 May 2013 15:06:13 +1000 Subject: [PATCH 042/102] px4io: return raw ADC value for current we don't know how to scale it as we have no info on what sensor is attached. As we are returning a uint16_t it is better to let the FMU sort it out or we'll just lose precision. --- src/modules/px4iofirmware/protocol.h | 4 +--- src/modules/px4iofirmware/registers.c | 16 ++++++++-------- 2 files changed, 9 insertions(+), 11 deletions(-) diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index 8d8b7e941b..b80551a077 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -115,7 +115,7 @@ #define PX4IO_P_STATUS_ALARMS_PWM_ERROR (1 << 6) /* PWM configuration or output was bad */ #define PX4IO_P_STATUS_VBATT 4 /* battery voltage in mV */ -#define PX4IO_P_STATUS_IBATT 5 /* battery current in cA */ +#define PX4IO_P_STATUS_IBATT 5 /* battery current (raw ADC) */ /* array of post-mix actuator outputs, -10000..10000 */ #define PX4IO_PAGE_ACTUATORS 2 /* 0..CONFIG_ACTUATOR_COUNT-1 */ @@ -155,8 +155,6 @@ #define PX4IO_P_SETUP_PWM_ALTRATE 4 /* 'high' PWM frame output rate in Hz */ #define PX4IO_P_SETUP_RELAYS 5 /* bitmask of relay/switch outputs, 0 = off, 1 = on */ #define PX4IO_P_SETUP_VBATT_SCALE 6 /* battery voltage correction factor (float) */ -#define PX4IO_P_SETUP_IBATT_SCALE 7 /* battery current scaling factor (float) */ -#define PX4IO_P_SETUP_IBATT_BIAS 8 /* battery current bias value */ #define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */ /* autopilot control values, -10000..10000 */ diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 6c09def9ee..9f9c50048d 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -138,8 +138,6 @@ volatile uint16_t r_page_setup[] = [PX4IO_P_SETUP_PWM_ALTRATE] = 200, [PX4IO_P_SETUP_RELAYS] = 0, [PX4IO_P_SETUP_VBATT_SCALE] = 10000, - [PX4IO_P_SETUP_IBATT_SCALE] = 0, - [PX4IO_P_SETUP_IBATT_BIAS] = 0, [PX4IO_P_SETUP_SET_DEBUG] = 0, }; @@ -516,12 +514,14 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val /* PX4IO_P_STATUS_IBATT */ { - unsigned counts = adc_measure(ADC_VBATT); - unsigned scaled = (counts * r_page_setup[PX4IO_P_SETUP_IBATT_SCALE]) / 10000; - int corrected = scaled + REG_TO_SIGNED(r_page_setup[PX4IO_P_SETUP_IBATT_BIAS]); - if (corrected < 0) - corrected = 0; - r_page_status[PX4IO_P_STATUS_IBATT] = corrected; + /* + note that we have no idea what sort of + current sensor is attached, so we just + return the raw 12 bit ADC value and let the + FMU sort it out, with user selectable + configuration for their sensor + */ + r_page_status[PX4IO_P_STATUS_IBATT] = adc_measure(ADC_IN5); } SELECT_PAGE(r_page_status); From af27101ffecf2ad4642b1ced23640ff133c7246f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 May 2013 21:27:20 +1000 Subject: [PATCH 043/102] px4io: changed adc_measure() to return 0xffff on error, and lower timeout the timeout of 1ms was far too long, and could impact flight performance Returning 0xffff on error matches the FMU code, and allows bad values to be discarded --- src/modules/px4iofirmware/adc.c | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/adc.c b/src/modules/px4iofirmware/adc.c index 670b8d635d..f744698be2 100644 --- a/src/modules/px4iofirmware/adc.c +++ b/src/modules/px4iofirmware/adc.c @@ -135,6 +135,9 @@ adc_init(void) return 0; } +/* + return one measurement, or 0xffff on error + */ uint16_t adc_measure(unsigned channel) { @@ -154,9 +157,10 @@ adc_measure(unsigned channel) while (!(rSR & ADC_SR_EOC)) { /* never spin forever - this will give a bogus result though */ - if (hrt_elapsed_time(&now) > 1000) { + if (hrt_elapsed_time(&now) > 100) { debug("adc timeout"); - break; + perf_end(adc_perf); + return 0xffff; } } @@ -165,4 +169,4 @@ adc_measure(unsigned channel) perf_end(adc_perf); return result; -} \ No newline at end of file +} From d7e04a361909fb65839fb8f2ab515ea17e5f6d77 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 May 2013 21:28:55 +1000 Subject: [PATCH 044/102] px4io: fixed voltage/current output and add discharged_mah calculation this integrates the current over time to calculate discharged_mah, and allows the scaling of the current and the bias to be set with the px4io command --- src/drivers/px4io/px4io.cpp | 70 ++++++++++++++++++++++++++++++------- 1 file changed, 58 insertions(+), 12 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index d8b5c51c43..b4703839bf 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -108,6 +108,14 @@ public: */ int set_update_rate(int rate); + /** + * Set the battery current scaling and bias + * + * @param amp_per_volt + * @param amp_bias + */ + void set_battery_current_scaling(float amp_per_volt, float amp_bias); + /** * Print the current status of IO */ @@ -151,6 +159,10 @@ private: bool _primary_pwm_device; ///< true if we are the default PWM output + float _battery_amp_per_volt; + float _battery_amp_bias; + float _battery_mamphour_total; + uint64_t _battery_last_timestamp; /** * Trampoline to the worker task @@ -314,6 +326,10 @@ PX4IO::PX4IO() : _to_actuators_effective(0), _to_outputs(0), _to_battery(0), + _battery_amp_per_volt(90.0f/5.0f), // this matches the 3DR current sensor + _battery_amp_bias(0), + _battery_mamphour_total(0), + _battery_last_timestamp(0), _primary_pwm_device(false) { /* we need this potentially before it could be set in task_main */ @@ -884,11 +900,22 @@ PX4IO::io_get_status() /* voltage is scaled to mV */ battery_status.voltage_v = regs[2] / 1000.0f; - /* current scaling should be to cA in order to avoid limiting at 65A */ - battery_status.current_a = regs[3] / 100.f; + /* + regs[3] contains the raw ADC count, as 12 bit ADC + value, with full range being 3.3v + */ + battery_status.current_a = regs[3] * (3.3f/4096.0f) * _battery_amp_per_volt; + battery_status.current_a += _battery_amp_bias; - /* this requires integration over time - not currently implemented */ - battery_status.discharged_mah = -1.0f; + /* + integrate battery over time to get total mAh used + */ + if (_battery_last_timestamp != 0) { + _battery_mamphour_total += battery_status.current_a * + (battery_status.timestamp - _battery_last_timestamp) * 1.0e-3f / 3600; + } + battery_status.discharged_mah = _battery_mamphour_total; + _battery_last_timestamp = battery_status.timestamp; /* lazily publish the battery voltage */ if (_to_battery > 0) { @@ -1245,9 +1272,14 @@ PX4IO::print_status() ((alarms & PX4IO_P_STATUS_ALARMS_FMU_LOST) ? " FMU_LOST" : ""), ((alarms & PX4IO_P_STATUS_ALARMS_RC_LOST) ? " RC_LOST" : ""), ((alarms & PX4IO_P_STATUS_ALARMS_PWM_ERROR) ? " PWM_ERROR" : "")); - printf("vbatt %u ibatt %u\n", - io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT), - io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT)); + printf("vbatt %u ibatt %u vbatt scale %u\n", + io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_VBATT), + io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT), + io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE)); + printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n", + _battery_amp_per_volt, + _battery_amp_bias, + _battery_mamphour_total); printf("actuators"); for (unsigned i = 0; i < _max_actuators; i++) printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i)); @@ -1288,10 +1320,6 @@ PX4IO::print_status() io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_DEFAULTRATE), io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_ALTRATE), io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_RELAYS)); - printf("vbatt scale %u ibatt scale %u ibatt bias %u\n", - io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE), - io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_IBATT_SCALE), - io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_IBATT_BIAS)); printf("debuglevel %u\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_SET_DEBUG)); printf("controls"); for (unsigned i = 0; i < _max_controls; i++) @@ -1521,6 +1549,12 @@ PX4IO::set_update_rate(int rate) return 0; } +void +PX4IO::set_battery_current_scaling(float amp_per_volt, float amp_bias) +{ + _battery_amp_per_volt = amp_per_volt; + _battery_amp_bias = amp_bias; +} extern "C" __EXPORT int px4io_main(int argc, char *argv[]); @@ -1658,6 +1692,18 @@ px4io_main(int argc, char *argv[]) exit(0); } + if (!strcmp(argv[1], "current")) { + if (g_dev != nullptr) { + if ((argc > 3)) { + g_dev->set_battery_current_scaling(atof(argv[2]), atof(argv[3])); + } else { + errx(1, "missing argument (apm_per_volt, amp_offset)"); + return 1; + } + } + exit(0); + } + if (!strcmp(argv[1], "recovery")) { if (g_dev != nullptr) { @@ -1785,5 +1831,5 @@ px4io_main(int argc, char *argv[]) monitor(); out: - errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit' or 'update'"); + errx(1, "need a command, try 'start', 'stop', 'status', 'test', 'monitor', 'debug', 'recovery', 'limit', 'current' or 'update'"); } From 5b75519925a46165b108f1a6d59b6325e1022adc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 May 2013 21:29:30 +1000 Subject: [PATCH 045/102] px4io: handle errors from adc_measure() don't update the voltage/current values on error --- src/modules/px4iofirmware/registers.c | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 9f9c50048d..4f3addfea8 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -506,10 +506,12 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val * Intercept corrected for best results @ 12V. */ unsigned counts = adc_measure(ADC_VBATT); - unsigned mV = (4150 + (counts * 46)) / 10 - 200; - unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000; + if (counts != 0xffff) { + unsigned mV = (4150 + (counts * 46)) / 10 - 200; + unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000; - r_page_status[PX4IO_P_STATUS_VBATT] = corrected; + r_page_status[PX4IO_P_STATUS_VBATT] = corrected; + } } /* PX4IO_P_STATUS_IBATT */ @@ -521,7 +523,10 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val FMU sort it out, with user selectable configuration for their sensor */ - r_page_status[PX4IO_P_STATUS_IBATT] = adc_measure(ADC_IN5); + unsigned counts = adc_measure(ADC_IN5); + if (counts != 0xffff) { + r_page_status[PX4IO_P_STATUS_IBATT] = counts; + } } SELECT_PAGE(r_page_status); From 1c4fc6cfb0b5d417011df11a0c8705dc344077b8 Mon Sep 17 00:00:00 2001 From: marco Date: Sat, 4 May 2013 20:37:22 +0200 Subject: [PATCH 046/102] Help Parameter added and some small fixes. This Version was flown several Hours without any Problems. --- apps/drivers/mkblctrl/mkblctrl.cpp | 59 ++++++++++++++++-------------- 1 file changed, 32 insertions(+), 27 deletions(-) diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/apps/drivers/mkblctrl/mkblctrl.cpp index e70bd16945..3a735e26fb 100644 --- a/apps/drivers/mkblctrl/mkblctrl.cpp +++ b/apps/drivers/mkblctrl/mkblctrl.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -219,7 +219,7 @@ struct MotorData_t // the following bytes must be exactly in that order! unsigned int Current; // in 0.1 A steps, read back from BL unsigned int MaxPWM; // read back from BL is less than 255 if BL is in current limit - unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in °C + unsigned int Temperature; // old BL-Ctrl will return a 255 here, the new version the temp. in unsigned int RoundCount; }; @@ -1355,28 +1355,26 @@ extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); int mkblctrl_main(int argc, char *argv[]) { - PortMode new_mode = PORT_MODE_UNSET; + PortMode port_mode = PORT_FULL_PWM; int pwm_update_rate_in_hz = UPDATE_RATE; - int motorcount = 0; + int motorcount = 8; int bus = 1; - bool motortest = false; int px4mode = MAPPING_PX4; int frametype = FRAME_PLUS; // + plus is default - - new_mode = PORT_FULL_PWM; - motorcount = 8; + bool motortest = false; + bool showHelp = false; + bool newMode = false; /* - * Mode switches. - * - * XXX use getopt? + * optional parameters */ - for (int i = 1; i < argc; i++) { /* argv[0] is "mk" */ + for (int i = 1; i < argc; i++) { /* look for the optional i2c bus parameter */ if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { if (argc > i + 1) { bus = atoi(argv[i + 1]); + newMode = true; } else { errx(1, "missing argument for i2c bus (-b)"); return 1; @@ -1388,6 +1386,7 @@ mkblctrl_main(int argc, char *argv[]) if (argc > i + 1) { if(strcmp(argv[i + 1], "+") == 0 || strcmp(argv[i + 1], "x") == 0 || strcmp(argv[i + 1], "X") == 0) { px4mode = MAPPING_MK; + newMode = true; if(strcmp(argv[i + 1], "+") == 0) { frametype = FRAME_PLUS; } else { @@ -1405,30 +1404,36 @@ mkblctrl_main(int argc, char *argv[]) /* look for the optional test parameter */ if (strcmp(argv[i], "-t") == 0) { motortest = true; + newMode = true; + } + + /* look for the optional -h --help parameter */ + if (strcmp(argv[i], "-h") == 0 || strcmp(argv[i], "--help") == 0) { + showHelp == true; } } - if(new_mode == PORT_MODE_UNSET) { - fprintf(stderr, "mkblctrl: unrecognised command, try:\n"); - fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest]\n"); + if(showHelp) { + fprintf(stderr, "mkblctrl: help:\n"); + fprintf(stderr, " [-mkmode frame{+/x}] [-b i2c_bus_number] [-t motortest] [-h / --help]\n"); exit(1); } - if (mk_start(bus, motorcount) != OK) - errx(1, "failed to start the MK-BLCtrl driver"); + + if (g_mk == nullptr) { + if (mk_start(bus, motorcount) != OK) { + errx(1, "failed to start the MK-BLCtrl driver"); + } else { + newMode = true; + } + } - /* was a new mode set? */ - if (new_mode != PORT_MODE_UNSET) { - - /* yes but it's the same mode */ - //if (new_mode == g_port_mode) - //return OK; - - /* switch modes */ - fprintf(stderr, "[mkblctrl] %iHz Update Rate\n",pwm_update_rate_in_hz); - return mk_new_mode(new_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); + /* parameter set ? */ + if (newMode) { + /* switch parameter */ + return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype); } /* test, etc. here g*/ From 8c6abe717db1f50c5d4b89f18e27f89608a9a1b8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 5 May 2013 11:24:31 +0200 Subject: [PATCH 047/102] Moved BLCTRL driver to new world --- makefiles/config_px4fmu_default.mk | 1 + {apps => src}/drivers/mkblctrl/mkblctrl.cpp | 0 .../Makefile => src/drivers/mkblctrl/module.mk | 10 ++++------ 3 files changed, 5 insertions(+), 6 deletions(-) rename {apps => src}/drivers/mkblctrl/mkblctrl.cpp (100%) rename apps/drivers/mkblctrl/Makefile => src/drivers/mkblctrl/module.mk (87%) diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 043c8af40a..07f9bdbc32 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -28,6 +28,7 @@ MODULES += drivers/gps MODULES += drivers/hil MODULES += drivers/hott_telemetry MODULES += drivers/blinkm +MODULES += drivers/mkblctrl MODULES += modules/sensors # diff --git a/apps/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp similarity index 100% rename from apps/drivers/mkblctrl/mkblctrl.cpp rename to src/drivers/mkblctrl/mkblctrl.cpp diff --git a/apps/drivers/mkblctrl/Makefile b/src/drivers/mkblctrl/module.mk similarity index 87% rename from apps/drivers/mkblctrl/Makefile rename to src/drivers/mkblctrl/module.mk index b3be2c4687..3ac263b002 100644 --- a/apps/drivers/mkblctrl/Makefile +++ b/src/drivers/mkblctrl/module.mk @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (C) 2012 PX4 Development Team. All rights reserved. +# Copyright (c) 2012,2013 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -35,10 +35,8 @@ # Interface driver for the Mikrokopter BLCtrl # -APPNAME = mkblctrl -PRIORITY = SCHED_PRIORITY_DEFAULT -STACKSIZE = 2048 +MODULE_COMMAND = mkblctrl -INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common +SRCS = mkblctrl.cpp -include $(APPDIR)/mk/app.mk +INCLUDE_DIRS += $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common From bb94847511e76c34cf0fbebe874ed4fd6efe1c0c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 5 May 2013 11:43:29 +0200 Subject: [PATCH 048/102] Allowed parsing of floating point params from scripts --- src/systemcmds/param/param.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 56f5317e39..60e61d07b6 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * Author: Lorenz Meier * * Redistribution and use in source and binary forms, with or without @@ -34,6 +34,7 @@ /** * @file param.c + * @author Lorenz Meier * * Parameter tool. */ @@ -262,7 +263,7 @@ do_set(const char* name, const char* val) switch (param_type(param)) { case PARAM_TYPE_INT32: if (!param_get(param, &i)) { - printf("old: %d", i); + printf("curr: %d", i); /* convert string */ char* end; @@ -276,14 +277,13 @@ do_set(const char* name, const char* val) case PARAM_TYPE_FLOAT: if (!param_get(param, &f)) { - printf("float values are not yet supported."); - // printf("old: %4.4f", (double)f); + printf("curr: %4.4f", (double)f); - // /* convert string */ - // char* end; - // f = strtof(val,&end); - // param_set(param, &f); - // printf(" -> new: %4.4f\n", f); + /* convert string */ + char* end; + f = strtod(val,&end); + param_set(param, &f); + printf(" -> new: %f\n", f); } From 3466006735123bfd27c94538d98af5b79f47d5a0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 5 May 2013 12:57:21 +0200 Subject: [PATCH 049/102] GPS velocity update rate validation for u-blox, WIP --- apps/drivers/gps/gps.cpp | 11 ++- apps/drivers/gps/gps_helper.cpp | 27 +++++- apps/drivers/gps/gps_helper.h | 19 +++- apps/drivers/gps/mtk.cpp | 4 + apps/drivers/gps/mtk.h | 6 +- apps/drivers/gps/ubx.cpp | 162 +++++++++++++++++++------------- apps/drivers/gps/ubx.h | 76 ++++++++++----- 7 files changed, 203 insertions(+), 102 deletions(-) diff --git a/apps/drivers/gps/gps.cpp b/apps/drivers/gps/gps.cpp index e35bdb944a..7db2578160 100644 --- a/apps/drivers/gps/gps.cpp +++ b/apps/drivers/gps/gps.cpp @@ -285,6 +285,11 @@ GPS::task_main() unlock(); if (_Helper->configure(_baudrate) == 0) { unlock(); + + // GPS is obviously detected successfully, reset statistics + _Helper->reset_update_rates(); + warnx("module configuration successful"); + while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) { // lock(); /* opportunistic publishing - else invalid data would end up on the bus */ @@ -372,7 +377,11 @@ GPS::print_info() warnx("position lock: %dD, last update %4.2f seconds ago", (int)_report.fix_type, (double)((float)(hrt_absolute_time() - _report.timestamp_position) / 1000000.0f)); warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); - warnx("update rate: %6.2f Hz", (double)_rate); + warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate()); + warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate()); + warnx("rate publication:\t%6.2f Hz", (double)_rate); + + _Helper->reset_update_rates(); } usleep(100000); diff --git a/apps/drivers/gps/gps_helper.cpp b/apps/drivers/gps/gps_helper.cpp index 9c1fad5691..b03cccb453 100644 --- a/apps/drivers/gps/gps_helper.cpp +++ b/apps/drivers/gps/gps_helper.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved. * Author: Thomas Gubler * Julian Oes * @@ -36,9 +36,32 @@ #include #include #include +#include #include "gps_helper.h" -/* @file gps_helper.cpp */ +/** + * @file gps_helper.cpp + */ + +float +GPS_Helper::get_position_update_rate() +{ + _rate_count_lat_lon / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); +} + +float +GPS_Helper::get_velocity_update_rate() +{ + _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); +} + +float +GPS_Helper::reset_update_rates() +{ + _rate_count_vel = 0; + _rate_count_lat_lon = 0; + _interval_rate_start = hrt_absolute_time(); +} int GPS_Helper::set_baudrate(const int &fd, unsigned baud) diff --git a/apps/drivers/gps/gps_helper.h b/apps/drivers/gps/gps_helper.h index f3d3bc40b3..7e456a6aae 100644 --- a/apps/drivers/gps/gps_helper.h +++ b/apps/drivers/gps/gps_helper.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * Author: Thomas Gubler * Julian Oes * @@ -33,7 +33,9 @@ * ****************************************************************************/ -/* @file gps_helper.h */ +/** + * @file gps_helper.h + */ #ifndef GPS_HELPER_H #define GPS_HELPER_H @@ -44,9 +46,18 @@ class GPS_Helper { public: - virtual int configure(unsigned &baud) = 0; + virtual int configure(unsigned &baud) = 0; virtual int receive(unsigned timeout) = 0; - int set_baudrate(const int &fd, unsigned baud); + int set_baudrate(const int &fd, unsigned baud); + float get_position_update_rate(); + float get_velocity_update_rate(); + float reset_update_rates(); + +protected: + uint8_t _rate_count_lat_lon; + uint8_t _rate_count_vel; + + uint64_t _interval_rate_start; }; #endif /* GPS_HELPER_H */ diff --git a/apps/drivers/gps/mtk.cpp b/apps/drivers/gps/mtk.cpp index 4762bd503a..62941d74b3 100644 --- a/apps/drivers/gps/mtk.cpp +++ b/apps/drivers/gps/mtk.cpp @@ -263,6 +263,10 @@ MTK::handle_message(gps_mtk_packet_t &packet) _gps_position->time_gps_usec += timeinfo_conversion_temp * 1e3; _gps_position->timestamp_position = _gps_position->timestamp_time = hrt_absolute_time(); + // Position and velocity update always at the same time + _rate_count_vel++; + _rate_count_lat_lon++; + return; } diff --git a/apps/drivers/gps/mtk.h b/apps/drivers/gps/mtk.h index d4e390b01b..b5cfbf0a6d 100644 --- a/apps/drivers/gps/mtk.h +++ b/apps/drivers/gps/mtk.h @@ -87,14 +87,14 @@ class MTK : public GPS_Helper public: MTK(const int &fd, struct vehicle_gps_position_s *gps_position); ~MTK(); - int receive(unsigned timeout); - int configure(unsigned &baudrate); + int receive(unsigned timeout); + int configure(unsigned &baudrate); private: /** * Parse the binary MTK packet */ - int parse_char(uint8_t b, gps_mtk_packet_t &packet); + int parse_char(uint8_t b, gps_mtk_packet_t &packet); /** * Handle the package once it has arrived diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index c150f52715..e887e8f7c1 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -60,7 +60,8 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) : _fd(fd), _gps_position(gps_position), -_waiting_for_ack(false) +_waiting_for_ack(false), +_disable_cmd_counter(0) { decode_init(); } @@ -144,7 +145,7 @@ UBX::configure(unsigned &baudrate) cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; send_config_packet(_fd, (uint8_t*)&cfg_rate_packet, sizeof(cfg_rate_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { + if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { /* try next baudrate */ continue; } @@ -164,74 +165,41 @@ UBX::configure(unsigned &baudrate) cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; send_config_packet(_fd, (uint8_t*)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { + if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { /* try next baudrate */ continue; } - type_gps_bin_cfg_msg_packet_t cfg_msg_packet; - memset(&cfg_msg_packet, 0, sizeof(cfg_msg_packet)); - - _clsID_needed = UBX_CLASS_CFG; - _msgID_needed = UBX_MESSAGE_CFG_MSG; - - cfg_msg_packet.clsID = UBX_CLASS_CFG; - cfg_msg_packet.msgID = UBX_MESSAGE_CFG_MSG; - cfg_msg_packet.length = UBX_CFG_MSG_LENGTH; - /* Choose fast 5Hz rate for all messages except SVINFO which is big and not important */ - cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_5HZ; - - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_POSLLH; - - send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { - /* try next baudrate */ - continue; - } - - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_TIMEUTC; - - send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { - /* try next baudrate */ - continue; - } - - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SVINFO; - /* For satelites info 1Hz is enough */ - cfg_msg_packet.rate[1] = UBX_CFG_MSG_PAYLOAD_RATE1_1HZ; - - send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { - /* try next baudrate */ - continue; - } - - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_SOL; - - send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { - /* try next baudrate */ - continue; - } - - cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; - cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_VELNED; - - send_config_packet(_fd, (uint8_t*)&cfg_msg_packet, sizeof(cfg_msg_packet)); - if (receive(UBX_CONFIG_TIMEOUT) < 0) { - /* try next baudrate */ - continue; - } -// cfg_msg_packet.msgClass_payload = UBX_CLASS_NAV; -// cfg_msg_packet.msgID_payload = UBX_MESSAGE_NAV_DOP; - -// cfg_msg_packet.msgClass_payload = UBX_CLASS_RXM; -// cfg_msg_packet.msgID_payload = UBX_MESSAGE_RXM_SVSI; + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, + UBX_CFG_MSG_PAYLOAD_RATE1_5HZ); + /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, + UBX_CFG_MSG_PAYLOAD_RATE1_05HZ); + // /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, + UBX_CFG_MSG_PAYLOAD_RATE1_05HZ); + // /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, + UBX_CFG_MSG_PAYLOAD_RATE1_5HZ); + // /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; + // configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_DOP, + // 0); + // /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, + 0); + // /* insist of receiving the ACK for this packet */ + // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) + // continue; _waiting_for_ack = false; return 0; @@ -239,6 +207,15 @@ UBX::configure(unsigned &baudrate) return -1; } +int +UBX::wait_for_ack(unsigned timeout) +{ + _waiting_for_ack = true; + int ret = receive(timeout); + _waiting_for_ack = false; + return ret; +} + int UBX::receive(unsigned timeout) { @@ -498,6 +475,8 @@ UBX::handle_message() _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m + _rate_count_lat_lon++; + /* Add timestamp to finish the report */ _gps_position->timestamp_position = hrt_absolute_time(); /* only return 1 when new position is available */ @@ -653,6 +632,8 @@ UBX::handle_message() _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f; _gps_position->vel_ned_valid = true; _gps_position->timestamp_velocity = hrt_absolute_time(); + + _rate_count_vel++; } break; @@ -693,6 +674,12 @@ UBX::handle_message() default: //we don't know the message warnx("UBX: Unknown message received: %d-%d\n",_message_class,_message_id); + if (_disable_cmd_counter++ == 0) { + // Don't attempt for every message to disable, some might not be disabled */ + warnx("Disabling message 0x%02x 0x%02x", (unsigned)_message_class, (unsigned)_message_id); + configure_message_rate(_message_class, _message_id, 0); + } + return ret; ret = -1; break; } @@ -736,6 +723,25 @@ UBX::add_checksum_to_message(uint8_t* message, const unsigned length) message[length-1] = ck_b; } +void +UBX::add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b) +{ + for (unsigned i = 0; i < length; i++) { + ck_a = ck_a + message[i]; + ck_b = ck_b + ck_a; + } +} + +void +UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) +{ + struct ubx_cfg_msg_rate msg; + msg.msg_class = msg_class; + msg.msg_id = msg_id; + msg.rate = rate; + send_message(CFG, UBX_CONFIG_STATE_RATE, &msg, sizeof(msg)); +} + void UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length) { @@ -753,3 +759,27 @@ UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length) if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning? warnx("ubx: config write fail"); } + +void +UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size) +{ + struct ubx_header header; + uint8_t ck_a=0, ck_b=0; + header.sync1 = UBX_SYNC1; + header.sync2 = UBX_SYNC2; + header.msg_class = msg_class; + header.msg_id = msg_id; + header.length = size; + + add_checksum((uint8_t *)&header.msg_class, sizeof(header)-2, ck_a, ck_b); + add_checksum((uint8_t *)msg, size, ck_a, ck_b); + + // Configure receive check + _clsID_needed = msg_class; + _msgID_needed = msg_id; + + write(_fd, (const char *)&header, sizeof(header)); + write(_fd, (const char *)msg, size); + write(_fd, (const char *)&ck_a, 1); + write(_fd, (const char *)&ck_b, 1); +} diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index e3dd1c7ea9..a6cd0685de 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -65,11 +65,11 @@ #define UBX_MESSAGE_CFG_RATE 0x08 #define UBX_CFG_PRT_LENGTH 20 -#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */ -#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ -#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */ -#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */ -#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */ +#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */ +#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ +#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< always choose 38400 as GPS baudrate */ +#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */ +#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */ #define UBX_CFG_RATE_LENGTH 6 #define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */ @@ -78,13 +78,14 @@ #define UBX_CFG_NAV5_LENGTH 36 -#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0001 /**< only update dynamic model and fix mode */ +#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0005 /**< XXX only update dynamic model and fix mode */ #define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */ -#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */ +#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */ #define UBX_CFG_MSG_LENGTH 8 #define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ #define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ +#define UBX_CFG_MSG_PAYLOAD_RATE1_05HZ 10 #define UBX_MAX_PAYLOAD_LENGTH 500 @@ -92,6 +93,14 @@ /** the structures of the binary packets */ #pragma pack(push, 1) +struct ubx_header { + uint8_t sync1; + uint8_t sync2; + uint8_t msg_class; + uint8_t msg_id; + uint16_t length; +}; + typedef struct { uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ int32_t lon; /**< Longitude * 1e-7, deg */ @@ -274,11 +283,17 @@ typedef struct { uint16_t length; uint8_t msgClass_payload; uint8_t msgID_payload; - uint8_t rate[6]; + uint8_t rate; uint8_t ck_a; uint8_t ck_b; } type_gps_bin_cfg_msg_packet_t; +struct ubx_cfg_msg_rate { + uint8_t msg_class; + uint8_t msg_id; + uint8_t rate; +}; + // END the structures of the binary packets // ************ @@ -341,55 +356,64 @@ class UBX : public GPS_Helper public: UBX(const int &fd, struct vehicle_gps_position_s *gps_position); ~UBX(); - int receive(unsigned timeout); - int configure(unsigned &baudrate); + int receive(unsigned timeout); + int configure(unsigned &baudrate); private: /** * Parse the binary MTK packet */ - int parse_char(uint8_t b); + int parse_char(uint8_t b); /** * Handle the package once it has arrived */ - int handle_message(void); + int handle_message(void); /** * Reset the parse state machine for a fresh start */ - void decode_init(void); + void decode_init(void); /** * While parsing add every byte (except the sync bytes) to the checksum */ - void add_byte_to_checksum(uint8_t); + void add_byte_to_checksum(uint8_t); /** * Add the two checksum bytes to an outgoing message */ - void add_checksum_to_message(uint8_t* message, const unsigned length); + void add_checksum_to_message(uint8_t* message, const unsigned length); /** * Helper to send a config packet */ - void send_config_packet(const int &fd, uint8_t *packet, const unsigned length); + void send_config_packet(const int &fd, uint8_t *packet, const unsigned length); - int _fd; + void configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate); + + void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size); + + void add_checksum(uint8_t* message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b); + + int wait_for_ack(unsigned timeout); + + int _fd; struct vehicle_gps_position_s *_gps_position; ubx_config_state_t _config_state; - bool _waiting_for_ack; - uint8_t _clsID_needed; - uint8_t _msgID_needed; + bool _waiting_for_ack; + uint8_t _clsID_needed; + uint8_t _msgID_needed; ubx_decode_state_t _decode_state; - uint8_t _rx_buffer[RECV_BUFFER_SIZE]; - unsigned _rx_count; - uint8_t _rx_ck_a; - uint8_t _rx_ck_b; - ubx_message_class_t _message_class; + uint8_t _rx_buffer[RECV_BUFFER_SIZE]; + unsigned _rx_count; + uint8_t _rx_ck_a; + uint8_t _rx_ck_b; + ubx_message_class_t _message_class; ubx_message_id_t _message_id; - unsigned _payload_size; + unsigned _payload_size; + uint8_t _disable_cmd_counter; }; #endif /* UBX_H_ */ From 1f800edc7676a6ea13127746ce38787a1e98b935 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 5 May 2013 15:51:16 +0400 Subject: [PATCH 050/102] Still threshold increased to 0.1m/s^2, and orientation error threshold to 5m/s^2. Timeout increased to 30s. --- apps/commander/accelerometer_calibration.c | 66 +++++++++++----------- 1 file changed, 32 insertions(+), 34 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 1807369080..991145d73c 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -224,7 +224,7 @@ int do_accel_calibration_mesurements(int mavlink_fd, float accel_offs[3], float * Wait for vehicle become still and detect it's orientation. * * @return 0..5 according to orientation when vehicle is still and ready for measurements, - * ERROR if vehicle is not still after 10s or orientation error is more than 20% + * ERROR if vehicle is not still after 30s or orientation error is more than 5m/s^2 */ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { struct sensor_combined_s sensor; @@ -235,17 +235,17 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float accel_len2 = 0.0f; /* EMA time constant in seconds*/ float ema_len = 0.2f; - /* set "still" threshold to 0.005 m/s^2 */ - float still_thr2 = pow(0.05f / CONSTANTS_ONE_G, 2); - /* set accel error threshold to 30% of accel vector length */ - float accel_err_thr = 0.3f; + /* set "still" threshold to 0.1 m/s^2 */ + float still_thr2 = pow(0.1f, 2); + /* set accel error threshold to 5m/s^2 */ + float accel_err_thr = 5.0f; /* still time required in us */ int64_t still_time = 2000000; struct pollfd fds[1] = { { .fd = sub_sensor_combined, .events = POLLIN } }; hrt_abstime t_start = hrt_absolute_time(); - /* set deadline to 20s */ - hrt_abstime timeout = 20000000; + /* set timeout to 30s */ + hrt_abstime timeout = 30000000; hrt_abstime t_timeout = t_start + timeout; hrt_abstime t = t_start; hrt_abstime t_prev = t_start; @@ -267,11 +267,10 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { if (d > accel_disp[i]) accel_disp[i] = d; } - accel_len2 = accel_ema[0] * accel_ema[0] + accel_ema[1] * accel_ema[1] + accel_ema[2] * accel_ema[2]; - float still_thr_raw2 = still_thr2 * accel_len2; - if ( accel_disp[0] < still_thr_raw2 && - accel_disp[1] < still_thr_raw2 && - accel_disp[2] < still_thr_raw2 ) { + /* still detector with hysteresis */ + if ( accel_disp[0] < still_thr2 && + accel_disp[1] < still_thr2 && + accel_disp[2] < still_thr2 ) { /* is still now */ if (t_still == 0) { /* first time */ @@ -285,9 +284,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { break; } } - } else if ( accel_disp[0] > still_thr_raw2 * 2.0f || - accel_disp[1] > still_thr_raw2 * 2.0f || - accel_disp[2] > still_thr_raw2 * 2.0f) { + } else if ( accel_disp[0] > still_thr2 * 2.0f || + accel_disp[1] > still_thr2 * 2.0f || + accel_disp[2] > still_thr2 * 2.0f) { /* not still, reset still start time */ if (t_still != 0) { mavlink_log_info(mavlink_fd, "moving..."); @@ -306,30 +305,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { } float accel_len = sqrt(accel_len2); - float accel_err_thr_raw = accel_len * accel_err_thr; - if ( fabs(accel_ema[0] - accel_len) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0] - accel_len) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 0; // [ g, 0, 0 ] - if ( fabs(accel_ema[0] + accel_len) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0] + accel_len) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 1; // [ -g, 0, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1] - accel_len) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1] - accel_len) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 2; // [ 0, g, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1] + accel_len) < accel_err_thr_raw && - fabs(accel_ema[2]) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1] + accel_len) < accel_err_thr && + fabs(accel_ema[2]) < accel_err_thr ) return 3; // [ 0, -g, 0 ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2] - accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2] - accel_len) < accel_err_thr ) return 4; // [ 0, 0, g ] - if ( fabs(accel_ema[0]) < accel_err_thr_raw && - fabs(accel_ema[1]) < accel_err_thr_raw && - fabs(accel_ema[2] + accel_len) < accel_err_thr_raw ) + if ( fabs(accel_ema[0]) < accel_err_thr && + fabs(accel_ema[1]) < accel_err_thr && + fabs(accel_ema[2] + accel_len) < accel_err_thr ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); From 27a25b5e172c972e4f9f31c2a30114498346bb08 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 5 May 2013 18:50:23 +0200 Subject: [PATCH 051/102] Improved update rate for velocity estimate, not yet where we want it to be --- apps/drivers/gps/gps_helper.cpp | 4 ++-- apps/drivers/gps/ubx.cpp | 10 +++++----- apps/drivers/gps/ubx.h | 2 +- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/apps/drivers/gps/gps_helper.cpp b/apps/drivers/gps/gps_helper.cpp index b03cccb453..54ac90dabd 100644 --- a/apps/drivers/gps/gps_helper.cpp +++ b/apps/drivers/gps/gps_helper.cpp @@ -46,13 +46,13 @@ float GPS_Helper::get_position_update_rate() { - _rate_count_lat_lon / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); + return _rate_count_lat_lon / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); } float GPS_Helper::get_velocity_update_rate() { - _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); + return _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); } float diff --git a/apps/drivers/gps/ubx.cpp b/apps/drivers/gps/ubx.cpp index e887e8f7c1..b3093b0f6f 100644 --- a/apps/drivers/gps/ubx.cpp +++ b/apps/drivers/gps/ubx.cpp @@ -140,7 +140,7 @@ UBX::configure(unsigned &baudrate) cfg_rate_packet.clsID = UBX_CLASS_CFG; cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE; cfg_rate_packet.length = UBX_CFG_RATE_LENGTH; - cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASRATE; + cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL; cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; @@ -176,17 +176,17 @@ UBX::configure(unsigned &baudrate) // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) // continue; configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, - UBX_CFG_MSG_PAYLOAD_RATE1_05HZ); + 1); // /* insist of receiving the ACK for this packet */ // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) // continue; configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, - UBX_CFG_MSG_PAYLOAD_RATE1_05HZ); + 1); // /* insist of receiving the ACK for this packet */ // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) // continue; configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, - UBX_CFG_MSG_PAYLOAD_RATE1_5HZ); + 1); // /* insist of receiving the ACK for this packet */ // if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) // continue; @@ -739,7 +739,7 @@ UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) msg.msg_class = msg_class; msg.msg_id = msg_id; msg.rate = rate; - send_message(CFG, UBX_CONFIG_STATE_RATE, &msg, sizeof(msg)); + send_message(CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg)); } void diff --git a/apps/drivers/gps/ubx.h b/apps/drivers/gps/ubx.h index a6cd0685de..5a433642ce 100644 --- a/apps/drivers/gps/ubx.h +++ b/apps/drivers/gps/ubx.h @@ -72,7 +72,7 @@ #define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */ #define UBX_CFG_RATE_LENGTH 6 -#define UBX_CFG_RATE_PAYLOAD_MEASRATE 200 /**< 200ms for 5Hz */ +#define UBX_CFG_RATE_PAYLOAD_MEASINTERVAL 200 /**< 200ms for 5Hz */ #define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */ #define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */ From 3bf26ac51f76389217cf2f604ca2420bcc050acf Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 5 May 2013 16:48:05 -0700 Subject: [PATCH 052/102] Obsolete bogus EXTRAFLAGS, add language-specific flags overrides. --- makefiles/toolchain_gnu-arm-eabi.mk | 23 ++++++++++++++++++----- 1 file changed, 18 insertions(+), 5 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 32a2773732..efb6b432a0 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -98,6 +98,14 @@ INSTRUMENTATIONDEFINES = -finstrument-functions \ ARCHCFLAGS = -std=gnu99 ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +# Compatibility +# XXX remove this once downstream users are fixed +# +ifneq ($(EXTRAFLAGS),) +$(warning EXTRAFLAGS is deprecated, use EXTRADEFINES for common pre-processor definitions. See also EXTRACFLAGS, EXTRACXXFLAGS and EXTRALDFLAGS.) +EXTRADEFINES += $(EXTRAFLAGS) +endif + # Generic warnings # ARCHWARNINGS = -Wall \ @@ -144,6 +152,7 @@ CFLAGS = $(ARCHCFLAGS) \ $(INSTRUMENTATIONDEFINES) \ $(ARCHDEFINES) \ $(EXTRADEFINES) \ + $(EXTRACFLAGS) \ -fno-common \ $(addprefix -I,$(INCLUDE_DIRS)) @@ -156,18 +165,22 @@ CXXFLAGS = $(ARCHCXXFLAGS) \ $(ARCHXXINCLUDES) \ $(INSTRUMENTATIONDEFINES) \ $(ARCHDEFINES) \ - $(EXTRADEFINES) \ -DCONFIG_WCHAR_BUILTIN \ + $(EXTRADEFINES) \ + $(EXTRACXXFLAGS) \ $(addprefix -I,$(INCLUDE_DIRS)) # Flags we pass to the assembler # -AFLAGS = $(CFLAGS) -D__ASSEMBLY__ +AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \ + $(EXTRADEFINES) \ + $(EXTRAAFLAGS) # Flags we pass to the linker # LDFLAGS += --warn-common \ --gc-sections \ + $(EXTRALDFLAGS) \ $(addprefix -T,$(LDSCRIPT)) \ $(addprefix -L,$(LIB_DIRS)) @@ -189,7 +202,7 @@ DEP_INCLUDES = $(subst .o,.d,$(OBJS)) define COMPILE @$(ECHO) "CC: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CC) -MD -c $(CFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 + $(Q) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2 endef # Compile C++ source $1 to $2 @@ -198,7 +211,7 @@ endef define COMPILEXX @$(ECHO) "CXX: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CXX) -MD -c $(CXXFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 + $(Q) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2 endef # Assemble $1 into $2 @@ -206,7 +219,7 @@ endef define ASSEMBLE @$(ECHO) "AS: $1" @$(MKDIR) -p $(dir $2) - $(Q) $(CC) -c $(AFLAGS) $(EXTRAFLAGS) $(abspath $1) -o $2 + $(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2 endef # Produce partially-linked $1 from files in $2 From 1ca535b94145c94db04d0655c2f4fb25c76a717a Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 5 May 2013 16:52:26 -0700 Subject: [PATCH 053/102] Fix whitespace damage, update help text to indicate the -m option is for debug use only. --- src/systemcmds/pwm/pwm.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 08e6c88dfa..ff733df52f 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -78,7 +78,7 @@ usage(const char *reason) " Channel group that should update at the alternate rate (may be specified more than once)\n" " arm | disarm Arm or disarm the ouptut\n" " ... PWM output values in microseconds to assign to the PWM outputs\n" - " Directly supply alt rate channel mask\n" + " Directly supply alt rate channel mask (debug use only)\n" "\n" "When -c is specified, any channel groups not listed with -c will update at the default rate.\n" ); From 3b65281f00150eaa29cfec1d4a4cb86fc83c326d Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 5 May 2013 17:19:23 -0700 Subject: [PATCH 054/102] Remove EXTRAFLAGS compatibility hack. --- makefiles/toolchain_gnu-arm-eabi.mk | 8 -------- 1 file changed, 8 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index efb6b432a0..0e651e53c8 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -98,14 +98,6 @@ INSTRUMENTATIONDEFINES = -finstrument-functions \ ARCHCFLAGS = -std=gnu99 ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -# Compatibility -# XXX remove this once downstream users are fixed -# -ifneq ($(EXTRAFLAGS),) -$(warning EXTRAFLAGS is deprecated, use EXTRADEFINES for common pre-processor definitions. See also EXTRACFLAGS, EXTRACXXFLAGS and EXTRALDFLAGS.) -EXTRADEFINES += $(EXTRAFLAGS) -endif - # Generic warnings # ARCHWARNINGS = -Wall \ From 41ec41cf8cc16309cf6f7e949d3ddad78e5f44a2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 6 May 2013 18:21:56 +0400 Subject: [PATCH 055/102] Accelerometer calibration bugfix --- apps/commander/accelerometer_calibration.c | 14 ++++++-------- apps/commander/accelerometer_calibration.h | 4 ++-- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/apps/commander/accelerometer_calibration.c b/apps/commander/accelerometer_calibration.c index 991145d73c..d79dd93dd0 100644 --- a/apps/commander/accelerometer_calibration.c +++ b/apps/commander/accelerometer_calibration.c @@ -232,7 +232,6 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { float accel_ema[3] = { 0.0f, 0.0f, 0.0f }; /* max-hold dispersion of accel */ float accel_disp[3] = { 0.0f, 0.0f, 0.0f }; - float accel_len2 = 0.0f; /* EMA time constant in seconds*/ float ema_len = 0.2f; /* set "still" threshold to 0.1 m/s^2 */ @@ -304,30 +303,29 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) { } } - float accel_len = sqrt(accel_len2); - if ( fabs(accel_ema[0] - accel_len) < accel_err_thr && + if ( fabs(accel_ema[0] - CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 0; // [ g, 0, 0 ] - if ( fabs(accel_ema[0] + accel_len) < accel_err_thr && + if ( fabs(accel_ema[0] + CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 1; // [ -g, 0, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && - fabs(accel_ema[1] - accel_len) < accel_err_thr && + fabs(accel_ema[1] - CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 2; // [ 0, g, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && - fabs(accel_ema[1] + accel_len) < accel_err_thr && + fabs(accel_ema[1] + CONSTANTS_ONE_G) < accel_err_thr && fabs(accel_ema[2]) < accel_err_thr ) return 3; // [ 0, -g, 0 ] if ( fabs(accel_ema[0]) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && - fabs(accel_ema[2] - accel_len) < accel_err_thr ) + fabs(accel_ema[2] - CONSTANTS_ONE_G) < accel_err_thr ) return 4; // [ 0, 0, g ] if ( fabs(accel_ema[0]) < accel_err_thr && fabs(accel_ema[1]) < accel_err_thr && - fabs(accel_ema[2] + accel_len) < accel_err_thr ) + fabs(accel_ema[2] + CONSTANTS_ONE_G) < accel_err_thr ) return 5; // [ 0, 0, -g ] mavlink_log_info(mavlink_fd, "ERROR: invalid orientation"); diff --git a/apps/commander/accelerometer_calibration.h b/apps/commander/accelerometer_calibration.h index c0169c2a13..a11cf93d3c 100644 --- a/apps/commander/accelerometer_calibration.h +++ b/apps/commander/accelerometer_calibration.h @@ -1,8 +1,8 @@ /* * accelerometer_calibration.h * - * Created on: 25.04.2013 - * Author: ton + * Copyright (C) 2013 Anton Babushkin. All rights reserved. + * Author: Anton Babushkin */ #ifndef ACCELEROMETER_CALIBRATION_H_ From f3e6e4bb50d9d5e63ee423a25713d9033adcebf4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 6 May 2013 22:59:45 +0400 Subject: [PATCH 056/102] Update servo arm only on real change. --- apps/drivers/px4fmu/fmu.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/apps/drivers/px4fmu/fmu.cpp b/apps/drivers/px4fmu/fmu.cpp index e547245367..761a23c426 100644 --- a/apps/drivers/px4fmu/fmu.cpp +++ b/apps/drivers/px4fmu/fmu.cpp @@ -505,7 +505,11 @@ PX4FMU::task_main() orb_copy(ORB_ID(actuator_armed), _t_armed, &aa); /* update PWM servo armed status if armed and not locked down */ - up_pwm_servo_arm(aa.armed && !aa.lockdown); + bool set_armed = aa.armed && !aa.lockdown; + if (set_armed != _armed) { + _armed = set_armed; + up_pwm_servo_arm(set_armed); + } } // see if we have new PPM input data From eac9e10a83ab2f897e4d0c2c6c8cd9f9f55b29cb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 6 May 2013 23:50:14 +0200 Subject: [PATCH 057/102] Moved calibration --- .../modules}/commander/accelerometer_calibration.c | 0 .../modules}/commander/accelerometer_calibration.h | 0 src/modules/commander/module.mk | 10 ++++++---- 3 files changed, 6 insertions(+), 4 deletions(-) rename {apps => src/modules}/commander/accelerometer_calibration.c (100%) rename {apps => src/modules}/commander/accelerometer_calibration.h (100%) diff --git a/apps/commander/accelerometer_calibration.c b/src/modules/commander/accelerometer_calibration.c similarity index 100% rename from apps/commander/accelerometer_calibration.c rename to src/modules/commander/accelerometer_calibration.c diff --git a/apps/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h similarity index 100% rename from apps/commander/accelerometer_calibration.h rename to src/modules/commander/accelerometer_calibration.h diff --git a/src/modules/commander/module.mk b/src/modules/commander/module.mk index 556d5c2df6..fe44e955ad 100644 --- a/src/modules/commander/module.mk +++ b/src/modules/commander/module.mk @@ -35,7 +35,9 @@ # Main system state machine # -MODULE_COMMAND = commander -SRCS = commander.c \ - state_machine_helper.c \ - calibration_routines.c +MODULE_COMMAND = commander +SRCS = commander.c \ + state_machine_helper.c \ + calibration_routines.c \ + accelerometer_calibration.c + From 100bcefc17cb77eff7085ef8c6c3055492c2ae32 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 16 Apr 2013 14:11:56 -0400 Subject: [PATCH 058/102] Added velocity adjustment to stabilization. --- apps/controllib/fixedwing.cpp | 54 +++++++++++++++++++---------- apps/controllib/fixedwing.hpp | 6 ++-- apps/examples/control_demo/params.c | 3 +- 3 files changed, 42 insertions(+), 21 deletions(-) diff --git a/apps/controllib/fixedwing.cpp b/apps/controllib/fixedwing.cpp index 1cc28b9dd9..6309a12255 100644 --- a/apps/controllib/fixedwing.cpp +++ b/apps/controllib/fixedwing.cpp @@ -56,9 +56,9 @@ BlockYawDamper::BlockYawDamper(SuperBlock *parent, const char *name) : BlockYawDamper::~BlockYawDamper() {}; -void BlockYawDamper::update(float rCmd, float r) +void BlockYawDamper::update(float rCmd, float r, float outputScale) { - _rudder = _r2Rdr.update(rCmd - + _rudder = outputScale*_r2Rdr.update(rCmd - _rWashout.update(_rLowPass.update(r))); } @@ -77,13 +77,13 @@ BlockStabilization::BlockStabilization(SuperBlock *parent, const char *name) : BlockStabilization::~BlockStabilization() {}; void BlockStabilization::update(float pCmd, float qCmd, float rCmd, - float p, float q, float r) + float p, float q, float r, float outputScale) { - _aileron = _p2Ail.update( + _aileron = outputScale*_p2Ail.update( pCmd - _pLowPass.update(p)); - _elevator = _q2Elv.update( + _elevator = outputScale*_q2Elv.update( qCmd - _qLowPass.update(q)); - _yawDamper.update(rCmd, r); + _yawDamper.update(rCmd, r, outputScale); } BlockWaypointGuidance::BlockWaypointGuidance(SuperBlock *parent, const char *name) : @@ -163,11 +163,11 @@ BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *par // guidance block _guide(this, ""), - // block params - _trimAil(this, "TRIM_ROLL", false), /* general roll trim (full name: TRIM_ROLL) */ - _trimElv(this, "TRIM_PITCH", false), /* general pitch trim */ - _trimRdr(this, "TRIM_YAW", false), /* general yaw trim */ - _trimThr(this, "TRIM_THR", true), /* FWB_ specific throttle trim (full name: FWB_TRIM_THR) */ + _trimAil(this, "TRIM_ROLL", false), /* general roll trim (full name: TRIM_ROLL) */ + _trimElv(this, "TRIM_PITCH", false), /* general pitch trim */ + _trimRdr(this, "TRIM_YAW", false), /* general yaw trim */ + _trimThr(this, "TRIM_THR"), /* FWB_ specific throttle trim (full name: FWB_TRIM_THR) */ + _trimV(this, "TRIM_V"), /* FWB_ specific trim velocity (full name : FWB_TRIM_V) */ _vCmd(this, "V_CMD"), _rocMax(this, "ROC_MAX"), @@ -228,7 +228,15 @@ void BlockMultiModeBacksideAutopilot::update() _guide.update(_pos, _att, _posCmd, _lastPosCmd); // calculate velocity, XXX should be airspeed, but using ground speed for now - float v = sqrtf(_pos.vx * _pos.vx + _pos.vy * _pos.vy + _pos.vz * _pos.vz); + // for the purpose of control we will limit the velocity feedback between + // the min/max velocity + float v = _vLimit.update(sqrtf( + _pos.vx * _pos.vx + + _pos.vy * _pos.vy + + _pos.vz * _pos.vz)); + + // limit velocity command between min/max velocity + float vCmd = _vLimit.update(_vCmd.get()); // altitude hold float dThrottle = _h2Thr.update(_posCmd.altitude - _pos.alt); @@ -240,16 +248,19 @@ void BlockMultiModeBacksideAutopilot::update() // velocity hold // negative sign because nose over to increase speed - float thetaCmd = _theLimit.update(-_v2Theta.update( - _vLimit.update(_vCmd.get()) - v)); + float thetaCmd = _theLimit.update(-_v2Theta.update(vCmd - v)); float qCmd = _theta2Q.update(thetaCmd - _att.pitch); // yaw rate cmd float rCmd = 0; // stabilization + float velocityRatio = _trimV.get()/v; + float outputScale = velocityRatio*velocityRatio; + // this term scales the output based on the dynamic pressure change from trim _stabilization.update(pCmd, qCmd, rCmd, - _att.rollspeed, _att.pitchspeed, _att.yawspeed); + _att.rollspeed, _att.pitchspeed, _att.yawspeed, + outputScale); // output _actuators.control[CH_AIL] = _stabilization.getAileron() + _trimAil.get(); @@ -280,7 +291,12 @@ void BlockMultiModeBacksideAutopilot::update() } else if (_status.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { // calculate velocity, XXX should be airspeed, but using ground speed for now - float v = sqrtf(_pos.vx * _pos.vx + _pos.vy * _pos.vy + _pos.vz * _pos.vz); + // for the purpose of control we will limit the velocity feedback between + // the min/max velocity + float v = _vLimit.update(sqrtf( + _pos.vx * _pos.vx + + _pos.vy * _pos.vy + + _pos.vz * _pos.vz)); // pitch channel -> rate of climb // TODO, might want to put a gain on this, otherwise commanding @@ -294,8 +310,10 @@ void BlockMultiModeBacksideAutopilot::update() // throttle channel -> velocity // negative sign because nose over to increase speed - float vCmd = _manual.throttle * (_vLimit.getMax() - _vLimit.getMin()) + _vLimit.getMin(); - float thetaCmd = _theLimit.update(-_v2Theta.update(_vLimit.update(vCmd) - v)); + float vCmd = _vLimit.update(_manual.throttle * + (_vLimit.getMax() - _vLimit.getMin()) + + _vLimit.getMin()); + float thetaCmd = _theLimit.update(-_v2Theta.update(vCmd - v)); float qCmd = _theta2Q.update(thetaCmd - _att.pitch); // yaw rate cmd diff --git a/apps/controllib/fixedwing.hpp b/apps/controllib/fixedwing.hpp index 281cbb4cb6..c908ea2371 100644 --- a/apps/controllib/fixedwing.hpp +++ b/apps/controllib/fixedwing.hpp @@ -193,7 +193,7 @@ public: * good idea to declare a member to store the temporary * variable. */ - void update(float rCmd, float r); + void update(float rCmd, float r, float outputScale = 1.0); /** * Rudder output value accessor @@ -226,7 +226,8 @@ public: BlockStabilization(SuperBlock *parent, const char *name); virtual ~BlockStabilization(); void update(float pCmd, float qCmd, float rCmd, - float p, float q, float r); + float p, float q, float r, + float outputScale = 1.0); float getAileron() { return _aileron; } float getElevator() { return _elevator; } float getRudder() { return _yawDamper.getRudder(); } @@ -322,6 +323,7 @@ private: BlockParam _trimElv; BlockParam _trimRdr; BlockParam _trimThr; + BlockParam _trimV; BlockParam _vCmd; BlockParam _rocMax; diff --git a/apps/examples/control_demo/params.c b/apps/examples/control_demo/params.c index 428b779b17..cce38c3ec3 100644 --- a/apps/examples/control_demo/params.c +++ b/apps/examples/control_demo/params.c @@ -68,4 +68,5 @@ PARAM_DEFINE_FLOAT(FWB_ROC2THR_D, 0.0f); PARAM_DEFINE_FLOAT(FWB_ROC2THR_D_LP, 0.0f); PARAM_DEFINE_FLOAT(FWB_ROC2THR_I_MAX, 0.0f); -PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) +PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) +PARAM_DEFINE_FLOAT(FWB_TRIM_V, 12.0f); // trim velocity, m/s From 3ed93430060228b64893119a439187725d35d7ec Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 14 Apr 2013 20:09:38 -0400 Subject: [PATCH 059/102] HIL pressure fix. --- apps/controllib/fixedwing.cpp | 10 +-- apps/controllib/fixedwing.hpp | 6 +- apps/examples/control_demo/params.c | 14 ++-- apps/mavlink/mavlink_receiver.c | 122 +--------------------------- 4 files changed, 17 insertions(+), 135 deletions(-) diff --git a/apps/controllib/fixedwing.cpp b/apps/controllib/fixedwing.cpp index 1cc28b9dd9..3836a1a0fc 100644 --- a/apps/controllib/fixedwing.cpp +++ b/apps/controllib/fixedwing.cpp @@ -156,9 +156,9 @@ BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *par _theLimit(this, "THE"), _vLimit(this, "V"), - // altitude/roc hold + // altitude/climb rate hold _h2Thr(this, "H2THR"), - _roc2Thr(this, "ROC2THR"), + _cr2Thr(this, "CR2THR"), // guidance block _guide(this, ""), @@ -170,7 +170,7 @@ BlockMultiModeBacksideAutopilot::BlockMultiModeBacksideAutopilot(SuperBlock *par _trimThr(this, "TRIM_THR", true), /* FWB_ specific throttle trim (full name: FWB_TRIM_THR) */ _vCmd(this, "V_CMD"), - _rocMax(this, "ROC_MAX"), + _crMax(this, "CR_MAX"), _attPoll(), _lastPosCmd(), _timeStamp(0) @@ -285,8 +285,8 @@ void BlockMultiModeBacksideAutopilot::update() // pitch channel -> rate of climb // TODO, might want to put a gain on this, otherwise commanding // from +1 -> -1 m/s for rate of climb - //float dThrottle = _roc2Thr.update( - //_rocMax.get()*_manual.pitch - _pos.vz); + //float dThrottle = _cr2Thr.update( + //_crMax.get()*_manual.pitch - _pos.vz); // roll channel -> bank angle float phiCmd = _phiLimit.update(_manual.roll * _phiLimit.getMax()); diff --git a/apps/controllib/fixedwing.hpp b/apps/controllib/fixedwing.hpp index 281cbb4cb6..4323beeb30 100644 --- a/apps/controllib/fixedwing.hpp +++ b/apps/controllib/fixedwing.hpp @@ -310,9 +310,9 @@ private: BlockLimit _theLimit; BlockLimit _vLimit; - // altitude/ roc hold + // altitude/ climb rate hold BlockPID _h2Thr; - BlockPID _roc2Thr; + BlockPID _cr2Thr; // guidance BlockWaypointGuidance _guide; @@ -323,7 +323,7 @@ private: BlockParam _trimRdr; BlockParam _trimThr; BlockParam _vCmd; - BlockParam _rocMax; + BlockParam _crMax; struct pollfd _attPoll; vehicle_global_position_setpoint_s _lastPosCmd; diff --git a/apps/examples/control_demo/params.c b/apps/examples/control_demo/params.c index 428b779b17..71eacf25c8 100644 --- a/apps/examples/control_demo/params.c +++ b/apps/examples/control_demo/params.c @@ -59,13 +59,13 @@ PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity // rate of climb // this is what rate of climb is commanded (in m/s) // when the pitch stick is fully defelcted in simple mode -PARAM_DEFINE_FLOAT(FWB_ROC_MAX, 1.0f); +PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f); -// rate of climb -> thr -PARAM_DEFINE_FLOAT(FWB_ROC2THR_P, 0.01f); // rate of climb to throttle PID -PARAM_DEFINE_FLOAT(FWB_ROC2THR_I, 0.0f); -PARAM_DEFINE_FLOAT(FWB_ROC2THR_D, 0.0f); -PARAM_DEFINE_FLOAT(FWB_ROC2THR_D_LP, 0.0f); -PARAM_DEFINE_FLOAT(FWB_ROC2THR_I_MAX, 0.0f); +// climb rate -> thr +PARAM_DEFINE_FLOAT(FWB_CR2THR_P, 0.01f); // rate of climb to throttle PID +PARAM_DEFINE_FLOAT(FWB_CR2THR_I, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_D_LP, 0.0f); +PARAM_DEFINE_FLOAT(FWB_CR2THR_I_MAX, 0.0f); PARAM_DEFINE_FLOAT(FWB_TRIM_THR, 0.8f); // trim throttle (0,1) diff --git a/apps/mavlink/mavlink_receiver.c b/apps/mavlink/mavlink_receiver.c index 22c2fcdade..2ebfc5a10d 100644 --- a/apps/mavlink/mavlink_receiver.c +++ b/apps/mavlink/mavlink_receiver.c @@ -308,82 +308,6 @@ handle_message(mavlink_message_t *msg) uint64_t timestamp = hrt_absolute_time(); - /* TODO, set ground_press/ temp during calib */ - static const float ground_press = 1013.25f; // mbar - static const float ground_tempC = 21.0f; - static const float ground_alt = 0.0f; - static const float T0 = 273.15; - static const float R = 287.05f; - static const float g = 9.806f; - - if (msg->msgid == MAVLINK_MSG_ID_RAW_IMU) { - - mavlink_raw_imu_t imu; - mavlink_msg_raw_imu_decode(msg, &imu); - - /* packet counter */ - static uint16_t hil_counter = 0; - static uint16_t hil_frames = 0; - static uint64_t old_timestamp = 0; - - /* sensors general */ - hil_sensors.timestamp = imu.time_usec; - - /* hil gyro */ - static const float mrad2rad = 1.0e-3f; - hil_sensors.gyro_counter = hil_counter; - hil_sensors.gyro_raw[0] = imu.xgyro; - hil_sensors.gyro_raw[1] = imu.ygyro; - hil_sensors.gyro_raw[2] = imu.zgyro; - hil_sensors.gyro_rad_s[0] = imu.xgyro * mrad2rad; - hil_sensors.gyro_rad_s[1] = imu.ygyro * mrad2rad; - hil_sensors.gyro_rad_s[2] = imu.zgyro * mrad2rad; - - /* accelerometer */ - hil_sensors.accelerometer_counter = hil_counter; - static const float mg2ms2 = 9.8f / 1000.0f; - hil_sensors.accelerometer_raw[0] = imu.xacc; - hil_sensors.accelerometer_raw[1] = imu.yacc; - hil_sensors.accelerometer_raw[2] = imu.zacc; - hil_sensors.accelerometer_m_s2[0] = mg2ms2 * imu.xacc; - hil_sensors.accelerometer_m_s2[1] = mg2ms2 * imu.yacc; - hil_sensors.accelerometer_m_s2[2] = mg2ms2 * imu.zacc; - hil_sensors.accelerometer_mode = 0; // TODO what is this? - hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16 - - /* adc */ - hil_sensors.adc_voltage_v[0] = 0; - hil_sensors.adc_voltage_v[1] = 0; - hil_sensors.adc_voltage_v[2] = 0; - - /* magnetometer */ - float mga2ga = 1.0e-3f; - hil_sensors.magnetometer_counter = hil_counter; - hil_sensors.magnetometer_raw[0] = imu.xmag; - hil_sensors.magnetometer_raw[1] = imu.ymag; - hil_sensors.magnetometer_raw[2] = imu.zmag; - hil_sensors.magnetometer_ga[0] = imu.xmag * mga2ga; - hil_sensors.magnetometer_ga[1] = imu.ymag * mga2ga; - hil_sensors.magnetometer_ga[2] = imu.zmag * mga2ga; - hil_sensors.magnetometer_range_ga = 32.7f; // int16 - hil_sensors.magnetometer_mode = 0; // TODO what is this - hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; - - /* publish */ - orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); - - // increment counters - hil_counter += 1 ; - hil_frames += 1 ; - - // output - if ((timestamp - old_timestamp) > 10000000) { - printf("receiving hil imu at %d hz\n", hil_frames/10); - old_timestamp = timestamp; - hil_frames = 0; - } - } - if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) { mavlink_highres_imu_t imu; @@ -437,13 +361,9 @@ handle_message(mavlink_message_t *msg) hil_sensors.magnetometer_mode = 0; // TODO what is this hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f; + /* baro */ hil_sensors.baro_pres_mbar = imu.abs_pressure; - - float tempC = imu.temperature; - float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f; - float h = ground_alt + (R / g) * tempAvgK * logf(ground_press / imu.abs_pressure); - - hil_sensors.baro_alt_meter = h; + hil_sensors.baro_alt_meter = imu.pressure_alt; hil_sensors.baro_temp_celcius = imu.temperature; hil_sensors.gyro_counter = hil_counter; @@ -516,44 +436,6 @@ handle_message(mavlink_message_t *msg) } } - if (msg->msgid == MAVLINK_MSG_ID_RAW_PRESSURE) { - - mavlink_raw_pressure_t press; - mavlink_msg_raw_pressure_decode(msg, &press); - - /* packet counter */ - static uint16_t hil_counter = 0; - static uint16_t hil_frames = 0; - static uint64_t old_timestamp = 0; - - /* sensors general */ - hil_sensors.timestamp = press.time_usec; - - /* baro */ - - float tempC = press.temperature / 100.0f; - float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f; - float h = ground_alt + (R / g) * tempAvgK * logf(ground_press / press.press_abs); - hil_sensors.baro_counter = hil_counter; - hil_sensors.baro_pres_mbar = press.press_abs; - hil_sensors.baro_alt_meter = h; - hil_sensors.baro_temp_celcius = tempC; - - /* publish */ - orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors); - - // increment counters - hil_counter += 1 ; - hil_frames += 1 ; - - // output - if ((timestamp - old_timestamp) > 10000000) { - printf("receiving hil pressure at %d hz\n", hil_frames/10); - old_timestamp = timestamp; - hil_frames = 0; - } - } - if (msg->msgid == MAVLINK_MSG_ID_HIL_STATE) { mavlink_hil_state_t hil_state; From 06e390b5e98b5e83646a8cd5f75b6b546000fc85 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Tue, 30 Apr 2013 16:55:12 -0400 Subject: [PATCH 060/102] Added MD25 I2C motor controller driver. --- apps/drivers/device/i2c.h | 9 + apps/drivers/md25/MD25.cpp | 553 +++++++++++++++++++++++++++++ apps/drivers/md25/MD25.hpp | 293 +++++++++++++++ apps/drivers/md25/Makefile | 43 +++ apps/drivers/md25/md25_main.cpp | 264 ++++++++++++++ nuttx/configs/px4fmu/nsh/appconfig | 1 + nuttx/configs/px4fmu/nsh/defconfig | 4 + 7 files changed, 1167 insertions(+) create mode 100644 apps/drivers/md25/MD25.cpp create mode 100644 apps/drivers/md25/MD25.hpp create mode 100644 apps/drivers/md25/Makefile create mode 100644 apps/drivers/md25/md25_main.cpp diff --git a/apps/drivers/device/i2c.h b/apps/drivers/device/i2c.h index 66c34dd7c4..cc1f4e4d91 100644 --- a/apps/drivers/device/i2c.h +++ b/apps/drivers/device/i2c.h @@ -53,6 +53,15 @@ namespace device __EXPORT class __EXPORT I2C : public CDev { +public: + + /** + * Get the address + */ + uint16_t get_address() { + return _address; + } + protected: /** * The number of times a read or write operation will be retried on diff --git a/apps/drivers/md25/MD25.cpp b/apps/drivers/md25/MD25.cpp new file mode 100644 index 0000000000..92778b109d --- /dev/null +++ b/apps/drivers/md25/MD25.cpp @@ -0,0 +1,553 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file md25.cpp + * + * Driver for MD25 I2C Motor Driver + * + * references: + * http://www.robot-electronics.co.uk/htm/md25tech.htm + * http://www.robot-electronics.co.uk/files/rpi_md25.c + * + */ + +#include "MD25.hpp" +#include +#include + +#include +#include + +// registers +enum { + // RW: read/write + // R: read + REG_SPEED1_RW = 0, + REG_SPEED2_RW, + REG_ENC1A_R, + REG_ENC1B_R, + REG_ENC1C_R, + REG_ENC1D_R, + REG_ENC2A_R, + REG_ENC2B_R, + REG_ENC2C_R, + REG_ENC2D_R, + REG_BATTERY_VOLTS_R, + REG_MOTOR1_CURRENT_R, + REG_MOTOR2_CURRENT_R, + REG_SW_VERSION_R, + REG_ACCEL_RATE_RW, + REG_MODE_RW, + REG_COMMAND_RW, +}; + +MD25::MD25(const char *deviceName, int bus, + uint16_t address, uint32_t speed) : + I2C("MD25", deviceName, bus, address, speed), + _controlPoll(), + _actuators(NULL, ORB_ID(actuator_controls_0), 20), + _version(0), + _motor1Speed(0), + _motor2Speed(0), + _revolutions1(0), + _revolutions2(0), + _batteryVoltage(0), + _motor1Current(0), + _motor2Current(0), + _motorAccel(0), + _mode(MODE_UNSIGNED_SPEED), + _command(CMD_RESET_ENCODERS) +{ + // setup control polling + _controlPoll.fd = _actuators.getHandle(); + _controlPoll.events = POLLIN; + + // if initialization fails raise an error, unless + // probing + int ret = I2C::init(); + + if (ret != OK) { + warnc(ret, "I2C::init failed for bus: %d address: %d\n", bus, address); + } + + // setup default settings, reset encoders + setMotor1Speed(0); + setMotor2Speed(0); + resetEncoders(); + _setMode(MD25::MODE_UNSIGNED_SPEED); + setSpeedRegulation(true); + setTimeout(true); +} + +MD25::~MD25() +{ +} + +int MD25::readData() +{ + uint8_t sendBuf[1]; + sendBuf[0] = REG_SPEED1_RW; + uint8_t recvBuf[17]; + int ret = transfer(sendBuf, sizeof(sendBuf), + recvBuf, sizeof(recvBuf)); + + if (ret == OK) { + _version = recvBuf[REG_SW_VERSION_R]; + _motor1Speed = _uint8ToNorm(recvBuf[REG_SPEED1_RW]); + _motor2Speed = _uint8ToNorm(recvBuf[REG_SPEED2_RW]); + _revolutions1 = -int32_t((recvBuf[REG_ENC1A_R] << 24) + + (recvBuf[REG_ENC1B_R] << 16) + + (recvBuf[REG_ENC1C_R] << 8) + + recvBuf[REG_ENC1D_R]) / 360.0; + _revolutions2 = -int32_t((recvBuf[REG_ENC2A_R] << 24) + + (recvBuf[REG_ENC2B_R] << 16) + + (recvBuf[REG_ENC2C_R] << 8) + + recvBuf[REG_ENC2D_R]) / 360.0; + _batteryVoltage = recvBuf[REG_BATTERY_VOLTS_R] / 10.0; + _motor1Current = recvBuf[REG_MOTOR1_CURRENT_R] / 10.0; + _motor2Current = recvBuf[REG_MOTOR2_CURRENT_R] / 10.0; + _motorAccel = recvBuf[REG_ACCEL_RATE_RW]; + _mode = e_mode(recvBuf[REG_MODE_RW]); + _command = e_cmd(recvBuf[REG_COMMAND_RW]); + } + + return ret; +} + +void MD25::status(char *string, size_t n) +{ + snprintf(string, n, + "version:\t%10d\n" \ + "motor 1 speed:\t%10.2f\n" \ + "motor 2 speed:\t%10.2f\n" \ + "revolutions 1:\t%10.2f\n" \ + "revolutions 2:\t%10.2f\n" \ + "battery volts :\t%10.2f\n" \ + "motor 1 current :\t%10.2f\n" \ + "motor 2 current :\t%10.2f\n" \ + "motor accel :\t%10d\n" \ + "mode :\t%10d\n" \ + "command :\t%10d\n", + getVersion(), + double(getMotor1Speed()), + double(getMotor2Speed()), + double(getRevolutions1()), + double(getRevolutions2()), + double(getBatteryVolts()), + double(getMotor1Current()), + double(getMotor2Current()), + getMotorAccel(), + getMode(), + getCommand()); +} + +uint8_t MD25::getVersion() +{ + return _version; +} + +float MD25::getMotor1Speed() +{ + return _motor1Speed; +} + +float MD25::getMotor2Speed() +{ + return _motor2Speed; +} + +float MD25::getRevolutions1() +{ + return _revolutions1; +} + +float MD25::getRevolutions2() +{ + return _revolutions2; +} + +float MD25::getBatteryVolts() +{ + return _batteryVoltage; +} + +float MD25::getMotor1Current() +{ + return _motor1Current; +} +float MD25::getMotor2Current() +{ + return _motor2Current; +} + +uint8_t MD25::getMotorAccel() +{ + return _motorAccel; +} + +MD25::e_mode MD25::getMode() +{ + return _mode; +} + +MD25::e_cmd MD25::getCommand() +{ + return _command; +} + +int MD25::resetEncoders() +{ + return _writeUint8(REG_COMMAND_RW, + CMD_RESET_ENCODERS); +} + +int MD25::_setMode(e_mode mode) +{ + return _writeUint8(REG_MODE_RW, + mode); +} + +int MD25::setSpeedRegulation(bool enable) +{ + if (enable) { + return _writeUint8(REG_COMMAND_RW, + CMD_ENABLE_SPEED_REGULATION); + + } else { + return _writeUint8(REG_COMMAND_RW, + CMD_DISABLE_SPEED_REGULATION); + } +} + +int MD25::setTimeout(bool enable) +{ + if (enable) { + return _writeUint8(REG_COMMAND_RW, + CMD_ENABLE_TIMEOUT); + + } else { + return _writeUint8(REG_COMMAND_RW, + CMD_DISABLE_TIMEOUT); + } +} + +int MD25::setDeviceAddress(uint8_t address) +{ + uint8_t sendBuf[1]; + sendBuf[0] = CMD_CHANGE_I2C_SEQ_0; + int ret = OK; + ret = transfer(sendBuf, sizeof(sendBuf), + nullptr, 0); + + if (ret != OK) { + warnc(ret, "MD25::setDeviceAddress"); + return ret; + } + + usleep(5000); + sendBuf[0] = CMD_CHANGE_I2C_SEQ_1; + ret = transfer(sendBuf, sizeof(sendBuf), + nullptr, 0); + + if (ret != OK) { + warnc(ret, "MD25::setDeviceAddress"); + return ret; + } + + usleep(5000); + sendBuf[0] = CMD_CHANGE_I2C_SEQ_2; + ret = transfer(sendBuf, sizeof(sendBuf), + nullptr, 0); + + if (ret != OK) { + warnc(ret, "MD25::setDeviceAddress"); + return ret; + } + + return OK; +} + +int MD25::setMotor1Speed(float value) +{ + return _writeUint8(REG_SPEED1_RW, + _normToUint8(value)); +} + +int MD25::setMotor2Speed(float value) +{ + return _writeUint8(REG_SPEED2_RW, + _normToUint8(value)); +} + +void MD25::update() +{ + // wait for an actuator publication, + // check for exit condition every second + // note "::poll" is required to distinguish global + // poll from member function for driver + if (::poll(&_controlPoll, 1, 1000) < 0) return; // poll error + + // if new data, send to motors + if (_actuators.updated()) { + _actuators.update(); + setMotor1Speed(_actuators.control[CH_SPEED_LEFT]); + setMotor2Speed(_actuators.control[CH_SPEED_RIGHT]); + } +} + +int MD25::probe() +{ + uint8_t goodAddress = 0; + bool found = false; + int ret = OK; + + // try initial address first, if good, then done + if (readData() == OK) return ret; + + // try all other addresses + uint8_t testAddress = 0; + + //printf("searching for MD25 address\n"); + while (true) { + set_address(testAddress); + ret = readData(); + + if (ret == OK && !found) { + //printf("device found at address: 0x%X\n", testAddress); + if (!found) { + found = true; + goodAddress = testAddress; + } + } + + if (testAddress > 254) { + break; + } + + testAddress++; + } + + if (found) { + set_address(goodAddress); + return OK; + + } else { + set_address(0); + return ret; + } +} + +int MD25::search() +{ + uint8_t goodAddress = 0; + bool found = false; + int ret = OK; + // try all other addresses + uint8_t testAddress = 0; + + //printf("searching for MD25 address\n"); + while (true) { + set_address(testAddress); + ret = readData(); + + if (ret == OK && !found) { + printf("device found at address: 0x%X\n", testAddress); + + if (!found) { + found = true; + goodAddress = testAddress; + } + } + + if (testAddress > 254) { + break; + } + + testAddress++; + } + + if (found) { + set_address(goodAddress); + return OK; + + } else { + set_address(0); + return ret; + } +} + +int MD25::_writeUint8(uint8_t reg, uint8_t value) +{ + uint8_t sendBuf[2]; + sendBuf[0] = reg; + sendBuf[1] = value; + return transfer(sendBuf, sizeof(sendBuf), + nullptr, 0); +} + +int MD25::_writeInt8(uint8_t reg, int8_t value) +{ + uint8_t sendBuf[2]; + sendBuf[0] = reg; + sendBuf[1] = value; + return transfer(sendBuf, sizeof(sendBuf), + nullptr, 0); +} + +float MD25::_uint8ToNorm(uint8_t value) +{ + // TODO, should go from 0 to 255 + // possibly should handle this differently + return (value - 128) / 127.0; +} + +uint8_t MD25::_normToUint8(float value) +{ + if (value > 1) value = 1; + + if (value < -1) value = -1; + + // TODO, should go from 0 to 255 + // possibly should handle this differently + return 127 * value + 128; +} + +int md25Test(const char *deviceName, uint8_t bus, uint8_t address) +{ + printf("md25 test: starting\n"); + + // setup + MD25 md25("/dev/md25", bus, address); + + // print status + char buf[200]; + md25.status(buf, sizeof(buf)); + printf("%s\n", buf); + + // setup for test + md25.setSpeedRegulation(true); + md25.setTimeout(true); + float dt = 0.1; + float speed = 0.2; + float t = 0; + + // motor 1 test + printf("md25 test: spinning motor 1 forward for 1 rev at 0.1 speed\n"); + t = 0; + + while (true) { + t += dt; + md25.setMotor1Speed(speed); + md25.readData(); + usleep(1000000 * dt); + + if (md25.getRevolutions1() > 1) { + printf("finished 1 revolution fwd\n"); + break; + } + + if (t > 2.0f) break; + } + + md25.setMotor1Speed(0); + printf("revolution of wheel 1: %8.4f\n", double(md25.getRevolutions1())); + md25.resetEncoders(); + + t = 0; + + while (true) { + t += dt; + md25.setMotor1Speed(-speed); + md25.readData(); + usleep(1000000 * dt); + + if (md25.getRevolutions1() < -1) { + printf("finished 1 revolution rev\n"); + break; + } + + if (t > 2.0f) break; + } + + md25.setMotor1Speed(0); + printf("revolution of wheel 1: %8.4f\n", double(md25.getRevolutions1())); + md25.resetEncoders(); + + // motor 2 test + printf("md25 test: spinning motor 2 forward for 1 rev at 0.1 speed\n"); + t = 0; + + while (true) { + t += dt; + md25.setMotor2Speed(speed); + md25.readData(); + usleep(1000000 * dt); + + if (md25.getRevolutions2() > 1) { + printf("finished 1 revolution fwd\n"); + break; + } + + if (t > 2.0f) break; + } + + md25.setMotor2Speed(0); + printf("revolution of wheel 2: %8.4f\n", double(md25.getRevolutions2())); + md25.resetEncoders(); + + t = 0; + + while (true) { + t += dt; + md25.setMotor2Speed(-speed); + md25.readData(); + usleep(1000000 * dt); + + if (md25.getRevolutions2() < -1) { + printf("finished 1 revolution rev\n"); + break; + } + + if (t > 2.0f) break; + } + + md25.setMotor2Speed(0); + printf("revolution of wheel 2: %8.4f\n", double(md25.getRevolutions2())); + md25.resetEncoders(); + + printf("Test complete\n"); + return 0; +} + +// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/apps/drivers/md25/MD25.hpp b/apps/drivers/md25/MD25.hpp new file mode 100644 index 0000000000..e77511b163 --- /dev/null +++ b/apps/drivers/md25/MD25.hpp @@ -0,0 +1,293 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file md25.cpp + * + * Driver for MD25 I2C Motor Driver + * + * references: + * http://www.robot-electronics.co.uk/htm/md25tech.htm + * http://www.robot-electronics.co.uk/files/rpi_md25.c + * + */ + +#pragma once + +#include +#include +#include +#include +#include + +/** + * This is a driver for the MD25 motor controller utilizing the I2C interface. + */ +class MD25 : public device::I2C +{ +public: + + /** + * modes + * + * NOTE: this driver assumes we are always + * in mode 0! + * + * seprate speed mode: + * motor speed1 = speed1 + * motor speed2 = speed2 + * turn speed mode: + * motor speed1 = speed1 + speed2 + * motor speed2 = speed2 - speed2 + * unsigned: + * full rev (0), stop(128), full fwd (255) + * signed: + * full rev (-127), stop(0), full fwd (128) + * + * modes numbers: + * 0 : unsigned separate (default) + * 1 : signed separate + * 2 : unsigned turn + * 3 : signed turn + */ + enum e_mode { + MODE_UNSIGNED_SPEED = 0, + MODE_SIGNED_SPEED, + MODE_UNSIGNED_SPEED_TURN, + MODE_SIGNED_SPEED_TURN, + }; + + /** commands */ + enum e_cmd { + CMD_RESET_ENCODERS = 32, + CMD_DISABLE_SPEED_REGULATION = 48, + CMD_ENABLE_SPEED_REGULATION = 49, + CMD_DISABLE_TIMEOUT = 50, + CMD_ENABLE_TIMEOUT = 51, + CMD_CHANGE_I2C_SEQ_0 = 160, + CMD_CHANGE_I2C_SEQ_1 = 170, + CMD_CHANGE_I2C_SEQ_2 = 165, + }; + + /** control channels */ + enum e_channels { + CH_SPEED_LEFT = 0, + CH_SPEED_RIGHT + }; + + /** + * constructor + * @param deviceName the name of the device e.g. "/dev/md25" + * @param bus the I2C bus + * @param address the adddress on the I2C bus + * @param speed the speed of the I2C communication + */ + MD25(const char *deviceName, + int bus, + uint16_t address, + uint32_t speed = 100000); + + /** + * deconstructor + */ + virtual ~MD25(); + + /** + * @return software version + */ + uint8_t getVersion(); + + /** + * @return speed of motor, normalized (-1, 1) + */ + float getMotor1Speed(); + + /** + * @return speed of motor 2, normalized (-1, 1) + */ + float getMotor2Speed(); + + /** + * @return number of rotations since reset + */ + float getRevolutions1(); + + /** + * @return number of rotations since reset + */ + float getRevolutions2(); + + /** + * @return battery voltage, volts + */ + float getBatteryVolts(); + + /** + * @return motor 1 current, amps + */ + float getMotor1Current(); + + /** + * @return motor 2 current, amps + */ + float getMotor2Current(); + + /** + * @return the motor acceleration + * controls motor speed change (1-10) + * accel rate | time for full fwd. to full rev. + * 1 | 6.375 s + * 2 | 1.6 s + * 3 | 0.675 s + * 5(default) | 1.275 s + * 10 | 0.65 s + */ + uint8_t getMotorAccel(); + + /** + * @return motor output mode + * */ + e_mode getMode(); + + /** + * @return current command register value + */ + e_cmd getCommand(); + + /** + * resets the encoders + * @return non-zero -> error + * */ + int resetEncoders(); + + /** + * enable/disable speed regulation + * @return non-zero -> error + */ + int setSpeedRegulation(bool enable); + + /** + * set the timeout for the motors + * enable/disable timeout (motor stop) + * after 2 sec of no i2c messages + * @return non-zero -> error + */ + int setTimeout(bool enable); + + /** + * sets the device address + * can only be done with one MD25 + * on the bus + * @return non-zero -> error + */ + int setDeviceAddress(uint8_t address); + + /** + * set motor 1 speed + * @param normSpeed normalize speed between -1 and 1 + * @return non-zero -> error + */ + int setMotor1Speed(float normSpeed); + + /** + * set motor 2 speed + * @param normSpeed normalize speed between -1 and 1 + * @return non-zero -> error + */ + int setMotor2Speed(float normSpeed); + + /** + * main update loop that updates MD25 motor + * speeds based on actuator publication + */ + void update(); + + /** + * probe for device + */ + virtual int probe(); + + /** + * search for device + */ + int search(); + + /** + * read data from i2c + */ + int readData(); + + /** + * print status + */ + void status(char *string, size_t n); + +private: + /** poll structure for control packets */ + struct pollfd _controlPoll; + + /** actuator controls subscription */ + control::UOrbSubscription _actuators; + + // local copy of data from i2c device + uint8_t _version; + float _motor1Speed; + float _motor2Speed; + float _revolutions1; + float _revolutions2; + float _batteryVoltage; + float _motor1Current; + float _motor2Current; + uint8_t _motorAccel; + e_mode _mode; + e_cmd _command; + + // private methods + int _writeUint8(uint8_t reg, uint8_t value); + int _writeInt8(uint8_t reg, int8_t value); + float _uint8ToNorm(uint8_t value); + uint8_t _normToUint8(float value); + + /** + * set motor control mode, + * this driver assumed we are always in mode 0 + * so we don't let the user change the mode + * @return non-zero -> error + */ + int _setMode(e_mode); +}; + +// unit testing +int md25Test(const char *deviceName, uint8_t bus, uint8_t address); + +// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/apps/drivers/md25/Makefile b/apps/drivers/md25/Makefile new file mode 100644 index 0000000000..cce2fd0953 --- /dev/null +++ b/apps/drivers/md25/Makefile @@ -0,0 +1,43 @@ +############################################################################ +# +# Copyright (C) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# MD25 I2C Based Motor Controller +# http://www.robot-electronics.co.uk/htm/md25tech.htm +# + +APPNAME = md25 +PRIORITY = SCHED_PRIORITY_DEFAULT +STACKSIZE = 2048 + +include $(APPDIR)/mk/app.mk diff --git a/apps/drivers/md25/md25_main.cpp b/apps/drivers/md25/md25_main.cpp new file mode 100644 index 0000000000..85aaab7f6d --- /dev/null +++ b/apps/drivers/md25/md25_main.cpp @@ -0,0 +1,264 @@ +/**************************************************************************** + * + * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + + + +/** + * @ file md25.cpp + * + * Driver for MD25 I2C Motor Driver + * + * references: + * http://www.robot-electronics.co.uk/htm/md25tech.htm + * http://www.robot-electronics.co.uk/files/rpi_md25.c + * + */ + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include "MD25.hpp" + +static bool thread_should_exit = false; /**< Deamon exit flag */ +static bool thread_running = false; /**< Deamon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ + +/** + * Deamon management function. + */ +extern "C" __EXPORT int md25_main(int argc, char *argv[]); + +/** + * Mainloop of deamon. + */ +int md25_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: md25 {start|stop|status|search|test|change_address}\n\n"); + exit(1); +} + +/** + * The deamon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int md25_main(int argc, char *argv[]) +{ + + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("md25 already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn("md25", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 10, + 2048, + md25_thread_main, + (const char **)argv); + exit(0); + } + + if (!strcmp(argv[1], "test")) { + + if (argc < 4) { + printf("usage: md25 test bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + md25Test(deviceName, bus, address); + + exit(0); + } + + if (!strcmp(argv[1], "probe")) { + if (argc < 4) { + printf("usage: md25 probe bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + MD25 md25(deviceName, bus, address); + + int ret = md25.probe(); + + if (ret == OK) { + printf("MD25 found on bus %d at address 0x%X\n", bus, md25.get_address()); + + } else { + printf("MD25 not found on bus %d\n", bus); + } + + exit(0); + } + + if (!strcmp(argv[1], "search")) { + if (argc < 3) { + printf("usage: md25 search bus\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t address = strtoul(argv[3], nullptr, 0); + + MD25 md25(deviceName, bus, address); + + md25.search(); + + exit(0); + } + + if (!strcmp(argv[1], "change_address")) { + if (argc < 5) { + printf("usage: md25 change_address bus old_address new_address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[2], nullptr, 0); + + uint8_t old_address = strtoul(argv[3], nullptr, 0); + + uint8_t new_address = strtoul(argv[4], nullptr, 0); + + MD25 md25(deviceName, bus, old_address); + + int ret = md25.setDeviceAddress(new_address); + + if (ret == OK) { + printf("MD25 new address set to 0x%X\n", new_address); + + } else { + printf("MD25 failed to set address to 0x%X\n", new_address); + } + + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + printf("\tmd25 app is running\n"); + + } else { + printf("\tmd25 app not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int md25_thread_main(int argc, char *argv[]) +{ + printf("[MD25] starting\n"); + + if (argc < 5) { + // extra md25 in arg list since this is a thread + printf("usage: md25 start bus address\n"); + exit(0); + } + + const char *deviceName = "/dev/md25"; + + uint8_t bus = strtoul(argv[3], nullptr, 0); + + uint8_t address = strtoul(argv[4], nullptr, 0); + + // start + MD25 md25("/dev/md25", bus, address); + + thread_running = true; + + // loop + while (!thread_should_exit) { + md25.update(); + } + + // exit + printf("[MD25] exiting.\n"); + thread_running = false; + return 0; +} + +// vi:noet:smarttab:autoindent:ts=4:sw=4:tw=78 diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig index 82ab94be78..300ed3f31a 100644 --- a/nuttx/configs/px4fmu/nsh/appconfig +++ b/nuttx/configs/px4fmu/nsh/appconfig @@ -128,6 +128,7 @@ CONFIGURED_APPS += drivers/mkblctrl CONFIGURED_APPS += drivers/hil CONFIGURED_APPS += drivers/gps CONFIGURED_APPS += drivers/mb12xx +CONFIGURED_APPS += drivers/md25 # Testing stuff CONFIGURED_APPS += px4/sensors_bringup diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 130886aac2..b89a08708d 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -647,10 +647,14 @@ CONFIG_DISABLE_POLL=n # CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing: # 5.1234567 # CONFIG_HAVE_LONG_LONG - Enabled printf("%llu) +# CONFIG_LIBC_STRERR - allow printing of error text +# CONFIG_LIBC_STRERR_SHORT - allow printing of short error text # CONFIG_NOPRINTF_FIELDWIDTH=n CONFIG_LIBC_FLOATINGPOINT=y CONFIG_HAVE_LONG_LONG=y +CONFIG_LIBC_STRERROR=n +CONFIG_LIBC_STRERROR_SHORT=n # # Allow for architecture optimized implementations From 1caffca3584fe323c83206379cc337e19768d854 Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 8 May 2013 22:50:18 -0700 Subject: [PATCH 061/102] whitespace --- makefiles/firmware.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index fff0e1c65c..b63aa28d73 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -193,7 +193,7 @@ EXTRA_CLEANS = # for GMSL). # where to look for modules -MODULE_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC) +MODULE_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC) # sort and unique the modules list MODULES := $(sort $(MODULES)) From 296a19072d26dfb814f7ca164e508b9203d51ac1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 15:39:54 +0200 Subject: [PATCH 062/102] Enabled leds on FMU again --- makefiles/config_px4fmu_default.mk | 1 + src/drivers/boards/px4fmu/module.mk | 3 ++- src/drivers/boards/px4fmu/px4fmu_init.c | 27 +++++++++++++++++------- src/drivers/boards/px4fmu/px4fmu_led.c | 28 ++++++++++++++++--------- src/drivers/led/led.cpp | 21 ++++++++++++------- 5 files changed, 54 insertions(+), 26 deletions(-) diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 07f9bdbc32..7f12ca7315 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -14,6 +14,7 @@ MODULES += drivers/device MODULES += drivers/stm32 MODULES += drivers/stm32/adc MODULES += drivers/stm32/tone_alarm +MODULES += drivers/led MODULES += drivers/px4io MODULES += drivers/px4fmu MODULES += drivers/boards/px4fmu diff --git a/src/drivers/boards/px4fmu/module.mk b/src/drivers/boards/px4fmu/module.mk index 2cb261d305..66b7769173 100644 --- a/src/drivers/boards/px4fmu/module.mk +++ b/src/drivers/boards/px4fmu/module.mk @@ -6,4 +6,5 @@ SRCS = px4fmu_can.c \ px4fmu_init.c \ px4fmu_pwm_servo.c \ px4fmu_spi.c \ - px4fmu_usb.c + px4fmu_usb.c \ + px4fmu_led.c diff --git a/src/drivers/boards/px4fmu/px4fmu_init.c b/src/drivers/boards/px4fmu/px4fmu_init.c index 5dd70c3f95..69edc23ab2 100644 --- a/src/drivers/boards/px4fmu/px4fmu_init.c +++ b/src/drivers/boards/px4fmu/px4fmu_init.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -91,6 +91,19 @@ # endif #endif +/* + * Ideally we'd be able to get these from up_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + /**************************************************************************** * Protected Functions ****************************************************************************/ @@ -114,7 +127,7 @@ __EXPORT void stm32_boardinitialize(void) /* configure SPI interfaces */ stm32_spiinitialize(); - /* configure LEDs */ + /* configure LEDs (empty call to NuttX' ledinit) */ up_ledinit(); } @@ -178,11 +191,11 @@ __EXPORT int nsh_archinitialize(void) (hrt_callout)stm32_serial_dma_poll, NULL); - // initial LED state -// drv_led_start(); - up_ledoff(LED_BLUE); - up_ledoff(LED_AMBER); - up_ledon(LED_BLUE); + /* initial LED state */ + drv_led_start(); + led_off(LED_AMBER); + led_on(LED_BLUE); + /* Configure SPI-based devices */ diff --git a/src/drivers/boards/px4fmu/px4fmu_led.c b/src/drivers/boards/px4fmu/px4fmu_led.c index fd1e159aa7..34fd194c33 100644 --- a/src/drivers/boards/px4fmu/px4fmu_led.c +++ b/src/drivers/boards/px4fmu/px4fmu_led.c @@ -39,19 +39,27 @@ #include -#include #include -#include -#include - -#include "chip.h" -#include "up_arch.h" -#include "up_internal.h" #include "stm32_internal.h" #include "px4fmu_internal.h" -__EXPORT void up_ledinit() +#include + +/* + * Ideally we'd be able to get these from up_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ +__BEGIN_DECLS +extern void led_init(); +extern void led_on(int led); +extern void led_off(int led); +__END_DECLS + +__EXPORT void led_init() { /* Configure LED1-2 GPIOs for output */ @@ -59,7 +67,7 @@ __EXPORT void up_ledinit() stm32_configgpio(GPIO_LED2); } -__EXPORT void up_ledon(int led) +__EXPORT void led_on(int led) { if (led == 0) { @@ -73,7 +81,7 @@ __EXPORT void up_ledon(int led) } } -__EXPORT void up_ledoff(int led) +__EXPORT void led_off(int led) { if (led == 0) { diff --git a/src/drivers/led/led.cpp b/src/drivers/led/led.cpp index c7c45525e1..04b565358c 100644 --- a/src/drivers/led/led.cpp +++ b/src/drivers/led/led.cpp @@ -41,12 +41,17 @@ #include #include -/* Ideally we'd be able to get these from up_internal.h */ -//#include +/* + * Ideally we'd be able to get these from up_internal.h, + * but since we want to be able to disable the NuttX use + * of leds for system indication at will and there is no + * separate switch, we need to build independent of the + * CONFIG_ARCH_LEDS configuration switch. + */ __BEGIN_DECLS -extern void up_ledinit(); -extern void up_ledon(int led); -extern void up_ledoff(int led); +extern void led_init(); +extern void led_on(int led); +extern void led_off(int led); __END_DECLS class LED : device::CDev @@ -74,7 +79,7 @@ int LED::init() { CDev::init(); - up_ledinit(); + led_init(); return 0; } @@ -86,11 +91,11 @@ LED::ioctl(struct file *filp, int cmd, unsigned long arg) switch (cmd) { case LED_ON: - up_ledon(arg); + led_on(arg); break; case LED_OFF: - up_ledoff(arg); + led_off(arg); break; default: From 3ec536a876a66f4e56549957e81ed4547c92a0c3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 17:13:38 +0200 Subject: [PATCH 063/102] Improved GPS update rate calculation --- src/drivers/gps/gps.cpp | 4 ++-- src/drivers/gps/gps_helper.cpp | 11 +++++++++-- src/drivers/gps/gps_helper.h | 4 ++++ 3 files changed, 15 insertions(+), 4 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 7db2578160..38835418b0 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -288,7 +288,6 @@ GPS::task_main() // GPS is obviously detected successfully, reset statistics _Helper->reset_update_rates(); - warnx("module configuration successful"); while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) { // lock(); @@ -306,6 +305,8 @@ GPS::task_main() _rate = last_rate_count / ((float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f); last_rate_measurement = hrt_absolute_time(); last_rate_count = 0; + _Helper->store_update_rates(); + _Helper->reset_update_rates(); } if (!_healthy) { @@ -381,7 +382,6 @@ GPS::print_info() warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate()); warnx("rate publication:\t%6.2f Hz", (double)_rate); - _Helper->reset_update_rates(); } usleep(100000); diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp index 54ac90dabd..ba86d370a8 100644 --- a/src/drivers/gps/gps_helper.cpp +++ b/src/drivers/gps/gps_helper.cpp @@ -46,13 +46,13 @@ float GPS_Helper::get_position_update_rate() { - return _rate_count_lat_lon / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); + return _rate_lat_lon; } float GPS_Helper::get_velocity_update_rate() { - return _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); + return _rate_vel; } float @@ -63,6 +63,13 @@ GPS_Helper::reset_update_rates() _interval_rate_start = hrt_absolute_time(); } +float +GPS_Helper::store_update_rates() +{ + _rate_vel = _rate_count_vel / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); + _rate_lat_lon = _rate_count_lat_lon / (((float)(hrt_absolute_time() - _interval_rate_start)) / 1000000.0f); +} + int GPS_Helper::set_baudrate(const int &fd, unsigned baud) { diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h index 7e456a6aae..defc1a074a 100644 --- a/src/drivers/gps/gps_helper.h +++ b/src/drivers/gps/gps_helper.h @@ -52,11 +52,15 @@ public: float get_position_update_rate(); float get_velocity_update_rate(); float reset_update_rates(); + float store_update_rates(); protected: uint8_t _rate_count_lat_lon; uint8_t _rate_count_vel; + float _rate_lat_lon; + float _rate_vel; + uint64_t _interval_rate_start; }; From fa1b7388f3485d8c7af42607b154f529d43153ea Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 17:34:00 +0200 Subject: [PATCH 064/102] Implemented new led status proposal --- src/modules/commander/commander.c | 30 ++++++++++++++++++++++++------ 1 file changed, 24 insertions(+), 6 deletions(-) diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index 01ab9e3d9c..cd2ef8137e 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -1503,22 +1503,40 @@ int commander_thread_main(int argc, char *argv[]) if ((current_status.state_machine == SYSTEM_STATE_GROUND_READY || current_status.state_machine == SYSTEM_STATE_AUTO || current_status.state_machine == SYSTEM_STATE_MANUAL)) { - /* armed */ - led_toggle(LED_BLUE); + /* armed, solid */ + led_on(LED_AMBER); } else if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { /* not armed */ - led_toggle(LED_BLUE); + led_toggle(LED_AMBER); } - /* toggle error led at 5 Hz in HIL mode */ + if (hrt_absolute_time() - gps_position.timestamp_position < 2000000) { + + /* toggle GPS (blue) led at 1 Hz if GPS present but no lock, make is solid once locked */ + if ((hrt_absolute_time() - gps_position.timestamp_position < 2000000) + && (gps_position.fix_type == GPS_FIX_TYPE_3D)) { + /* GPS lock */ + led_on(LED_BLUE); + + } else if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { + /* no GPS lock, but GPS module is aquiring lock */ + led_toggle(LED_BLUE); + } + + } else { + /* no GPS info, don't light the blue led */ + led_off(LED_BLUE); + } + + /* toggle GPS led at 5 Hz in HIL mode */ if (current_status.flag_hil_enabled) { /* hil enabled */ - led_toggle(LED_AMBER); + led_toggle(LED_BLUE); } else if (bat_remain < 0.3f && (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT)) { /* toggle error (red) at 5 Hz on low battery or error */ - led_toggle(LED_AMBER); + led_toggle(LED_BLUE); } else { // /* Constant error indication in standby mode without GPS */ From 26efba2ff365b1463ca9f6aaaf936557a92c4eb1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 17:38:12 +0200 Subject: [PATCH 065/102] New blink patterns for safety switch, removed GPS lock indicator --- src/drivers/px4io/px4io.cpp | 11 ++--------- src/modules/px4iofirmware/protocol.h | 1 - src/modules/px4iofirmware/safety.c | 9 +++------ 3 files changed, 5 insertions(+), 16 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index b4703839bf..e69fbebf74 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -502,8 +502,7 @@ PX4IO::init() io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_ARM_OK | PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | - PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | - PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK, 0); + PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0); /* publish RC config to IO */ ret = io_set_rc_config(); @@ -707,11 +706,6 @@ PX4IO::io_set_arming_state() } else { clear |= PX4IO_P_SETUP_ARMING_ARM_OK; } - if (vstatus.flag_vector_flight_mode_ok) { - set |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK; - } else { - clear |= PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK; - } if (vstatus.flag_external_manual_override_ok) { set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK; } else { @@ -1309,11 +1303,10 @@ PX4IO::print_status() /* setup and state */ printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES)); uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING); - printf("arming 0x%04x%s%s%s%s\n", + printf("arming 0x%04x%s%s%s\n", arming, ((arming & PX4IO_P_SETUP_ARMING_ARM_OK) ? " ARM_OK" : ""), ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""), - ((arming & PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK) ? " VECTOR_FLIGHT_OK" : ""), ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : "")); printf("rates 0x%04x default %u alt %u relays 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES), diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index b80551a077..d015fb629a 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -147,7 +147,6 @@ #define PX4IO_P_SETUP_ARMING 1 /* arming controls */ #define PX4IO_P_SETUP_ARMING_ARM_OK (1 << 0) /* OK to arm */ #define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */ -#define PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK (1 << 3) /* OK to perform position / vector control (= position lock) */ #define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */ #define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */ diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c index 5495d5ae12..a2880d2efb 100644 --- a/src/modules/px4iofirmware/safety.c +++ b/src/modules/px4iofirmware/safety.c @@ -56,11 +56,10 @@ static unsigned counter = 0; /* * Define the various LED flash sequences for each system state. */ -#define LED_PATTERN_SAFE 0xffff /**< always on */ -#define LED_PATTERN_VECTOR_FLIGHT_MODE_OK 0xFFFE /**< always on with short break */ -#define LED_PATTERN_FMU_ARMED 0x4444 /**< slow blinking */ +#define LED_PATTERN_SAFE 0x000f /**< always on */ +#define LED_PATTERN_FMU_ARMED 0x5555 /**< slow blinking */ #define LED_PATTERN_IO_ARMED 0x5555 /**< fast blinking */ -#define LED_PATTERN_IO_FMU_ARMED 0x5050 /**< long off then double blink */ +#define LED_PATTERN_IO_FMU_ARMED 0xffff /**< long off then double blink */ static unsigned blink_counter = 0; @@ -151,8 +150,6 @@ safety_check_button(void *arg) } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) { pattern = LED_PATTERN_FMU_ARMED; - } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_VECTOR_FLIGHT_OK) { - pattern = LED_PATTERN_VECTOR_FLIGHT_MODE_OK; } /* Turn the LED on if we have a 1 at the current bit position */ From d6cb588c3c078d3858d8c7bcb78ca72373aa73d8 Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 9 May 2013 10:02:56 -0700 Subject: [PATCH 066/102] fix capitalisation of include file name Marko Pagott --- src/drivers/md25/md25_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 85aaab7f6d..740dd0b287 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -55,7 +55,7 @@ #include #include -#include "MD25.hpp" +#include "md25.hpp" static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ From b7a9e0778359b9da7eb27e1292557e7a0f9a7278 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 19:03:24 +0200 Subject: [PATCH 067/102] Hotfix: Wrong capitalization on header file name --- src/drivers/md25/md25_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 85aaab7f6d..80850e7088 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -55,7 +55,7 @@ #include #include -#include "MD25.hpp" +#include "md25.hpp" static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ From 304ce63f00e72cf8a8162abad295a52a5773265d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 May 2013 19:03:24 +0200 Subject: [PATCH 068/102] Hotfix: Wrong capitalization on header file name --- src/drivers/md25/md25_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/md25/md25_main.cpp b/src/drivers/md25/md25_main.cpp index 85aaab7f6d..80850e7088 100644 --- a/src/drivers/md25/md25_main.cpp +++ b/src/drivers/md25/md25_main.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -55,7 +55,7 @@ #include #include -#include "MD25.hpp" +#include "md25.hpp" static bool thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ From 196ee8b16fcd42fca04d1fb7e11ec46dd45c8421 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 11 May 2013 11:32:05 -0700 Subject: [PATCH 069/102] Change the way modules are built so that object paths are relative and use vpath for locating sources (so source paths are also shorter). Add some basic documentation for the build system files while we're at it. --- makefiles/README.txt | 71 +++++++++++++++++++++++++++++ makefiles/firmware.mk | 7 ++- makefiles/module.mk | 51 +++++++++++++-------- src/modules/mathlib/CMSIS/module.mk | 5 +- 4 files changed, 110 insertions(+), 24 deletions(-) create mode 100644 makefiles/README.txt diff --git a/makefiles/README.txt b/makefiles/README.txt new file mode 100644 index 0000000000..8b84e4c40d --- /dev/null +++ b/makefiles/README.txt @@ -0,0 +1,71 @@ +PX4 Build System +================ + +The files in this directory implement the PX4 runtime firmware build system +and configuration for the standard PX4 boards and software, in conjunction +with Makefile in the parent directory. + +../Makefile + + Top-level makefile for the PX4 build system. This makefile supports + building NuttX archives, as well as supervising the building of all + of the defined PX4 firmware configurations. + + Try 'make help' in the parent directory for documentation. + +firmware.mk + + Manages the build for one specific firmware configuration. + See the comments at the top of this file for detailed documentation. + + Builds modules, builtin command lists and the ROMFS (if configured). + + This is the makefile directly used by external build systems; it can + be configured to compile modules both inside and outside the PX4 + source tree. When used in this mode, at least BOARD, MODULES and + CONFIG_FILE must be set. + +module.mk + + Called by firmware.mk to build individual modules. + See the comments at the top of this file for detailed documentation. + + Not normally used other than by firmware.mk. + +nuttx.mk + + Called by ../Makefile to build or download the NuttX archives. + +upload.mk + + Called by ../Makefile to upload files to a target board. Can be used + by external build systems as well. + +setup.mk + + Provides common path and tool definitions. Implements host system-specific + compatibility hacks. + +board_.mk + + Board-specific configuration for . Typically sets CONFIG_ARCH + and then includes the toolchain definition for the board. + +config__.mk + + Parameters for a specific configuration on a specific board. + The board name is derived from the filename. Sets MODULES to select + source modules to be included in the configuration, may also set + ROMFS_ROOT to build a ROMFS and BUILTIN_COMMANDS to include non-module + commands (e.g. from NuttX) + +toolchain_.mk + + Provides macros used to compile and link source files. + Accepts EXTRADEFINES to add additional pre-processor symbol definitions, + EXTRACFLAGS, EXTRACXXFLAGS, EXTRAAFLAGS and EXTRALDFLAGS to pass + additional flags to the C compiler, C++ compiler, assembler and linker + respectively. + + Defines the COMPILE, COMPILEXX, ASSEMBLE, PRELINK, ARCHIVE and LINK + macros that are used elsewhere in the build system. diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index b63aa28d73..e6a45a4e8a 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -223,12 +223,15 @@ MODULE_OBJS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)module .PHONY: $(MODULE_OBJS) $(MODULE_OBJS): relpath = $(patsubst $(WORK_DIR)%,%,$@) $(MODULE_OBJS): mkfile = $(patsubst %module.pre.o,%module.mk,$(relpath)) +$(MODULE_OBJS): workdir = $(@D) $(MODULE_OBJS): $(GLOBAL_DEPS) $(NUTTX_CONFIG_HEADER) + $(Q) $(MKDIR) -p $(workdir) $(Q) $(MAKE) -r -f $(PX4_MK_DIR)module.mk \ - MODULE_WORK_DIR=$(dir $@) \ + -C $(workdir) \ + MODULE_WORK_DIR=$(workdir) \ MODULE_OBJ=$@ \ MODULE_MK=$(mkfile) \ - MODULE_NAME=$(lastword $(subst /, ,$(@D))) \ + MODULE_NAME=$(lastword $(subst /, ,$(workdir))) \ module # make a list of phony clean targets for modules diff --git a/makefiles/module.mk b/makefiles/module.mk index 0fe6f0ffec..db6f4e15ec 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -39,6 +39,10 @@ # symbols, as the global namespace is shared between all modules. Normally an # module will just export one or more _main functions. # +# IMPORTANT NOTE: +# +# This makefile assumes it is being invoked in the module's output directory. +# # # Variables that can be set by the module's module.mk: @@ -179,26 +183,30 @@ CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibi # module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES) +## +## Locate sources (allows relative source paths in module.mk) +## +#define SRC_SEARCH +# $(abspath $(firstword $(wildcard $1) $(wildcard $(MODULE_SRC)/$1) MISSING_$1)) +#endef # -# Locate sources (allows relative source paths in module.mk) +#ABS_SRCS ?= $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src))) +#MISSING_SRCS := $(subst MISSING_,,$(filter MISSING_%,$(ABS_SRCS))) +#ifneq ($(MISSING_SRCS),) +#$(error $(MODULE_MK): missing in SRCS: $(MISSING_SRCS)) +#endif +#ifeq ($(ABS_SRCS),) +#$(error $(MODULE_MK): nothing to compile in SRCS) +#endif # -define SRC_SEARCH - $(abspath $(firstword $(wildcard $1) $(wildcard $(MODULE_SRC)/$1) MISSING_$1)) -endef +## +## Object files we will generate from sources +## +#OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o) -ABS_SRCS ?= $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src))) -MISSING_SRCS := $(subst MISSING_,,$(filter MISSING_%,$(ABS_SRCS))) -ifneq ($(MISSING_SRCS),) -$(error $(MODULE_MK): missing in SRCS: $(MISSING_SRCS)) -endif -ifeq ($(ABS_SRCS),) -$(error $(MODULE_MK): nothing to compile in SRCS) -endif - -# -# Object files we will generate from sources -# -OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o) +OBJS = $(addsuffix .o,$(SRCS)) +$(info SRCS $(SRCS)) +$(info OBJS $(OBJS)) # # SRCS -> OBJS rules @@ -206,13 +214,16 @@ OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o) $(OBJS): $(GLOBAL_DEPS) -$(filter %.c.o,$(OBJS)): $(MODULE_WORK_DIR)%.c.o: %.c $(GLOBAL_DEPS) +vpath %.c $(MODULE_SRC) +$(filter %.c.o,$(OBJS)): %.c.o: %.c $(GLOBAL_DEPS) $(call COMPILE,$<,$@) -$(filter %.cpp.o,$(OBJS)): $(MODULE_WORK_DIR)%.cpp.o: %.cpp $(GLOBAL_DEPS) +vpath %.cpp $(MODULE_SRC) +$(filter %.cpp.o,$(OBJS)): %.cpp.o: %.cpp $(GLOBAL_DEPS) $(call COMPILEXX,$<,$@) -$(filter %.S.o,$(OBJS)): $(MODULE_WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS) +vpath %.S $(MODULE_SRC) +$(filter %.S.o,$(OBJS)): %.S.o: %.S $(GLOBAL_DEPS) $(call ASSEMBLE,$<,$@) # diff --git a/src/modules/mathlib/CMSIS/module.mk b/src/modules/mathlib/CMSIS/module.mk index c676f32618..ba45b159ea 100644 --- a/src/modules/mathlib/CMSIS/module.mk +++ b/src/modules/mathlib/CMSIS/module.mk @@ -38,8 +38,9 @@ # # Find sources # -DSPLIB_SRCDIR := $(PX4_MODULE_SRC)/modules/mathlib/CMSIS -ABS_SRCS := $(wildcard $(DSPLIB_SRCDIR)/DSP_Lib/Source/*/*.c) +DSPLIB_SRCDIR := $(dir $(lastword $(MAKEFILE_LIST))) +SRCLIST := $(wildcard $(DSPLIB_SRCDIR)DSP_Lib/Source/*/*.c) +SRCS := $(patsubst $(DSPLIB_SRCDIR)%,%,$(SRCLIST)) zork.c INCLUDE_DIRS += $(DSPLIB_SRCDIR)/Include \ $(DSPLIB_SRCDIR)/Device/ARM/ARMCM4/Include \ From 555d42e0cd2724225391bede58629d3bcea175db Mon Sep 17 00:00:00 2001 From: px4dev Date: Sat, 11 May 2013 16:46:52 -0700 Subject: [PATCH 070/102] Oops, left in some test code. --- src/modules/mathlib/CMSIS/module.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mathlib/CMSIS/module.mk b/src/modules/mathlib/CMSIS/module.mk index ba45b159ea..5e1abe642f 100644 --- a/src/modules/mathlib/CMSIS/module.mk +++ b/src/modules/mathlib/CMSIS/module.mk @@ -40,7 +40,7 @@ # DSPLIB_SRCDIR := $(dir $(lastword $(MAKEFILE_LIST))) SRCLIST := $(wildcard $(DSPLIB_SRCDIR)DSP_Lib/Source/*/*.c) -SRCS := $(patsubst $(DSPLIB_SRCDIR)%,%,$(SRCLIST)) zork.c +SRCS := $(patsubst $(DSPLIB_SRCDIR)%,%,$(SRCLIST)) INCLUDE_DIRS += $(DSPLIB_SRCDIR)/Include \ $(DSPLIB_SRCDIR)/Device/ARM/ARMCM4/Include \ From 0c43da3b6424dbc877c464b6898f18fe650c703f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 May 2013 13:11:12 +0200 Subject: [PATCH 071/102] Tested with PX4FMU and PX4IO with GPS and arming --- src/modules/commander/commander.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/commander.c b/src/modules/commander/commander.c index cd2ef8137e..aab8f3e04d 100644 --- a/src/modules/commander/commander.c +++ b/src/modules/commander/commander.c @@ -1519,7 +1519,7 @@ int commander_thread_main(int argc, char *argv[]) /* GPS lock */ led_on(LED_BLUE); - } else if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { + } else if ((counter + 4) % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { /* no GPS lock, but GPS module is aquiring lock */ led_toggle(LED_BLUE); } @@ -1535,8 +1535,8 @@ int commander_thread_main(int argc, char *argv[]) led_toggle(LED_BLUE); } else if (bat_remain < 0.3f && (low_voltage_counter > LOW_VOLTAGE_BATTERY_COUNTER_LIMIT)) { - /* toggle error (red) at 5 Hz on low battery or error */ - led_toggle(LED_BLUE); + /* toggle arming (red) at 5 Hz on low battery or error */ + led_toggle(LED_AMBER); } else { // /* Constant error indication in standby mode without GPS */ From 0ee738e9c91c49739798ac5ff8dd4a12c06bb82f Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 12 May 2013 10:51:25 -0700 Subject: [PATCH 072/102] Fix ROMFS dependency scan, add a warning if ROMFS_ROOT appears to be empty. --- makefiles/firmware.mk | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index e6a45a4e8a..6fa0ae3eb0 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -269,13 +269,17 @@ endif # # Add dependencies on anything in the ROMFS root -ROMFS_DEPS += $(wildcard \ - (ROMFS_ROOT)/* \ - (ROMFS_ROOT)/*/* \ - (ROMFS_ROOT)/*/*/* \ - (ROMFS_ROOT)/*/*/*/* \ - (ROMFS_ROOT)/*/*/*/*/* \ - (ROMFS_ROOT)/*/*/*/*/*/*) +ROMFS_FILES += $(wildcard \ + $(ROMFS_ROOT)/* \ + $(ROMFS_ROOT)/*/* \ + $(ROMFS_ROOT)/*/*/* \ + $(ROMFS_ROOT)/*/*/*/* \ + $(ROMFS_ROOT)/*/*/*/*/* \ + $(ROMFS_ROOT)/*/*/*/*/*/*) +ifeq ($(ROMFS_FILES),) +$(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files) +endif +ROMFS_DEPS += $(ROMFS_FILES) ROMFS_IMG = $(WORK_DIR)romfs.img ROMFS_CSRC = $(ROMFS_IMG:.img=.c) ROMFS_OBJ = $(ROMFS_CSRC:.c=.o) From 79f9b61aff0570d1ab98dc5a4c7e6a71eec5009b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 May 2013 20:05:20 +0200 Subject: [PATCH 073/102] Fixed led patterns to be up to the latest specs --- src/drivers/px4io/px4io.cpp | 32 ++++++++++++-------- src/modules/commander/state_machine_helper.c | 5 +++ src/modules/px4iofirmware/protocol.h | 3 +- src/modules/px4iofirmware/safety.c | 26 ++++++++-------- src/modules/uORB/topics/actuator_controls.h | 1 + 5 files changed, 41 insertions(+), 26 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index e69fbebf74..3006cf885b 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -416,7 +416,7 @@ PX4IO::init() * already armed, and has been configured for in-air restart */ if ((reg & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) && - (reg & PX4IO_P_SETUP_ARMING_ARM_OK)) { + (reg & PX4IO_P_SETUP_ARMING_FMU_ARMED)) { mavlink_log_emergency(_mavlink_fd, "[IO] RECOVERING FROM FMU IN-AIR RESTART"); @@ -500,7 +500,7 @@ PX4IO::init() /* dis-arm IO before touching anything */ io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, - PX4IO_P_SETUP_ARMING_ARM_OK | + PX4IO_P_SETUP_ARMING_FMU_ARMED | PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0); @@ -701,11 +701,18 @@ PX4IO::io_set_arming_state() uint16_t set = 0; uint16_t clear = 0; - if (armed.armed) { - set |= PX4IO_P_SETUP_ARMING_ARM_OK; + if (armed.armed && !armed.lockdown) { + set |= PX4IO_P_SETUP_ARMING_FMU_ARMED; } else { - clear |= PX4IO_P_SETUP_ARMING_ARM_OK; + clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED; } + + if (armed.ready_to_arm) { + set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK; + } else { + clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK; + } + if (vstatus.flag_external_manual_override_ok) { set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK; } else { @@ -1271,9 +1278,9 @@ PX4IO::print_status() io_reg_get(PX4IO_PAGE_STATUS, PX4IO_P_STATUS_IBATT), io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_VBATT_SCALE)); printf("amp_per_volt %.3f amp_offset %.3f mAhDischarged %.3f\n", - _battery_amp_per_volt, - _battery_amp_bias, - _battery_mamphour_total); + (double)_battery_amp_per_volt, + (double)_battery_amp_bias, + (double)_battery_mamphour_total); printf("actuators"); for (unsigned i = 0; i < _max_actuators; i++) printf(" %u", io_reg_get(PX4IO_PAGE_ACTUATORS, i)); @@ -1303,9 +1310,10 @@ PX4IO::print_status() /* setup and state */ printf("features 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FEATURES)); uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING); - printf("arming 0x%04x%s%s%s\n", + printf("arming 0x%04x%s%s%s%s\n", arming, - ((arming & PX4IO_P_SETUP_ARMING_ARM_OK) ? " ARM_OK" : ""), + ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : ""), + ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : ""), ((arming & PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK) ? " MANUAL_OVERRIDE_OK" : ""), ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : "")); printf("rates 0x%04x default %u alt %u relays 0x%04x\n", @@ -1347,12 +1355,12 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) switch (cmd) { case PWM_SERVO_ARM: /* set the 'armed' bit */ - ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_ARM_OK); + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_FMU_ARMED); break; case PWM_SERVO_DISARM: /* clear the 'armed' bit */ - ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_ARM_OK, 0); + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FMU_ARMED, 0); break; case PWM_SERVO_SET_UPDATE_RATE: diff --git a/src/modules/commander/state_machine_helper.c b/src/modules/commander/state_machine_helper.c index bea388a101..ab728c7bbb 100644 --- a/src/modules/commander/state_machine_helper.c +++ b/src/modules/commander/state_machine_helper.c @@ -249,6 +249,11 @@ void publish_armed_status(const struct vehicle_status_s *current_status) { struct actuator_armed_s armed; armed.armed = current_status->flag_system_armed; + + /* XXX allow arming by external components on multicopters only if not yet armed by RC */ + /* XXX allow arming only if core sensors are ok */ + armed.ready_to_arm = true; + /* lock down actuators if required, only in HIL */ armed.lockdown = (current_status->flag_hil_enabled) ? true : false; orb_advert_t armed_pub = orb_advertise(ORB_ID(actuator_armed), &armed); diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index d015fb629a..e575bd8412 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -145,7 +145,8 @@ #define PX4IO_P_SETUP_FEATURES 0 #define PX4IO_P_SETUP_ARMING 1 /* arming controls */ -#define PX4IO_P_SETUP_ARMING_ARM_OK (1 << 0) /* OK to arm */ +#define PX4IO_P_SETUP_ARMING_IO_ARM_OK (1 << 0) /* OK to arm the IO side */ +#define PX4IO_P_SETUP_ARMING_FMU_ARMED (1 << 1) /* FMU is already armed */ #define PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK (1 << 2) /* OK to switch to manual override via override RC channel */ #define PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK (1 << 4) /* OK to try in-air restart */ diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c index a2880d2efb..f6cd5fb450 100644 --- a/src/modules/px4iofirmware/safety.c +++ b/src/modules/px4iofirmware/safety.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -32,7 +32,8 @@ ****************************************************************************/ /** - * @file Safety button logic. + * @file safety.c + * Safety button logic. */ #include @@ -56,10 +57,10 @@ static unsigned counter = 0; /* * Define the various LED flash sequences for each system state. */ -#define LED_PATTERN_SAFE 0x000f /**< always on */ -#define LED_PATTERN_FMU_ARMED 0x5555 /**< slow blinking */ -#define LED_PATTERN_IO_ARMED 0x5555 /**< fast blinking */ -#define LED_PATTERN_IO_FMU_ARMED 0xffff /**< long off then double blink */ +#define LED_PATTERN_FMU_OK_TO_ARM 0x0003 /**< slow blinking */ +#define LED_PATTERN_FMU_REFUSE_TO_ARM 0x5555 /**< fast blinking */ +#define LED_PATTERN_IO_ARMED 0x5050 /**< long off, then double blink */ +#define LED_PATTERN_IO_FMU_ARMED 0xffff /**< constantly on */ static unsigned blink_counter = 0; @@ -108,7 +109,8 @@ safety_check_button(void *arg) * state machine, keep ARM_COUNTER_THRESHOLD the same * length in all cases of the if/else struct below. */ - if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) { + if (safety_button_pressed && !(r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) && + (r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK)) { if (counter < ARM_COUNTER_THRESHOLD) { counter++; @@ -119,8 +121,6 @@ safety_check_button(void *arg) counter++; } - /* Disarm quickly */ - } else if (safety_button_pressed && (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) { if (counter < ARM_COUNTER_THRESHOLD) { @@ -137,18 +137,18 @@ safety_check_button(void *arg) } /* Select the appropriate LED flash pattern depending on the current IO/FMU arm state */ - uint16_t pattern = LED_PATTERN_SAFE; + uint16_t pattern = LED_PATTERN_FMU_REFUSE_TO_ARM; if (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) { - if (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) { + if (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) { pattern = LED_PATTERN_IO_FMU_ARMED; } else { pattern = LED_PATTERN_IO_ARMED; } - } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) { - pattern = LED_PATTERN_FMU_ARMED; + } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) { + pattern = LED_PATTERN_FMU_OK_TO_ARM; } diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h index 0b50a29ac8..b7c4196c0a 100644 --- a/src/modules/uORB/topics/actuator_controls.h +++ b/src/modules/uORB/topics/actuator_controls.h @@ -69,6 +69,7 @@ ORB_DECLARE(actuator_controls_3); /** global 'actuator output is live' control. */ struct actuator_armed_s { bool armed; /**< Set to true if system is armed */ + bool ready_to_arm; /**< Set to true if system is ready to be armed */ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */ }; From 6ea204c8136a3e4c81e2e542e56a865c57f381e7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 May 2013 20:08:09 +0200 Subject: [PATCH 074/102] Added fixed wing controller example --- makefiles/config_px4fmu_default.mk | 4 + src/examples/fixedwing_control/main.c | 474 +++++++++++++++++++++++ src/examples/fixedwing_control/module.mk | 41 ++ src/examples/fixedwing_control/params.c | 77 ++++ src/examples/fixedwing_control/params.h | 65 ++++ 5 files changed, 661 insertions(+) create mode 100644 src/examples/fixedwing_control/main.c create mode 100644 src/examples/fixedwing_control/module.mk create mode 100644 src/examples/fixedwing_control/params.c create mode 100644 src/examples/fixedwing_control/params.h diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 00d402c4a9..27bf0f973b 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -105,6 +105,10 @@ MODULES += modules/uORB # https://pixhawk.ethz.ch/px4/dev/debug_values #MODULES += examples/px4_mavlink_debug +# Tutorial code from +# https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control +MODULES += examples/fixedwing_control + # # Transitional support - add commands from the NuttX export archive. # diff --git a/src/examples/fixedwing_control/main.c b/src/examples/fixedwing_control/main.c new file mode 100644 index 0000000000..1753070e2f --- /dev/null +++ b/src/examples/fixedwing_control/main.c @@ -0,0 +1,474 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +/** + * @file main.c + * Implementation of a fixed wing attitude controller. This file is a complete + * fixed wing controller flying manual attitude control or auto waypoint control. + * There is no need to touch any other system components to extend / modify the + * complete control architecture. + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* process-specific header files */ +#include "params.h" + +/* Prototypes */ +/** + * Daemon management function. + */ +__EXPORT int ex_fixedwing_control_main(int argc, char *argv[]); + +/** + * Mainloop of daemon. + */ +int fixedwing_control_thread_main(int argc, char *argv[]); + +/** + * Print the correct usage. + */ +static void usage(const char *reason); + +void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, + float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + struct actuator_controls_s *actuators); + +void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp, + const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp); + +/* Variables */ +static bool thread_should_exit = false; /**< Daemon exit flag */ +static bool thread_running = false; /**< Daemon status flag */ +static int deamon_task; /**< Handle of deamon task / thread */ +static struct params p; +static struct param_handles ph; + +void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, + float speed_body[], float gyro[], struct vehicle_rates_setpoint_s *rates_sp, + struct actuator_controls_s *actuators) +{ + + /* + * The PX4 architecture provides a mixer outside of the controller. + * The mixer is fed with a default vector of actuator controls, representing + * moments applied to the vehicle frame. This vector + * is structured as: + * + * Control Group 0 (attitude): + * + * 0 - roll (-1..+1) + * 1 - pitch (-1..+1) + * 2 - yaw (-1..+1) + * 3 - thrust ( 0..+1) + * 4 - flaps (-1..+1) + * ... + * + * Control Group 1 (payloads / special): + * + * ... + */ + + /* + * Calculate roll error and apply P gain + */ + float roll_err = att->roll - att_sp->roll_body; + actuators->control[0] = roll_err * p.roll_p; + + /* + * Calculate pitch error and apply P gain + */ + float pitch_err = att->pitch - att_sp->pitch_body; + actuators->control[1] = pitch_err * p.pitch_p; +} + +void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp, + const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp) +{ + + /* + * Calculate heading error of current position to desired position + */ + + /* PX4 uses 1e7 scaled integers to represent global coordinates for max resolution */ + float bearing = get_bearing_to_next_waypoint(pos->lat/1e7d, pos->lon/1e7d, sp->lat/1e7d, sp->lon/1e7d); + + /* calculate heading error */ + float yaw_err = att->yaw - bearing; + /* apply control gain */ + att_sp->roll_body = yaw_err * p.hdng_p; +} + +/* Main Thread */ +int fixedwing_control_thread_main(int argc, char *argv[]) +{ + /* read arguments */ + bool verbose = false; + + for (int i = 1; i < argc; i++) { + if (strcmp(argv[i], "-v") == 0 || strcmp(argv[i], "--verbose") == 0) { + verbose = true; + } + } + + /* welcome user (warnx prints a line, including an appended\n, with variable arguments */ + warnx("[example fixedwing control] started"); + + /* initialize parameters, first the handles, then the values */ + parameters_init(&ph); + parameters_update(&ph, &p); + + /* declare and safely initialize all structs to zero */ + struct vehicle_attitude_s att; + memset(&att, 0, sizeof(att)); + struct vehicle_attitude_setpoint_s att_sp; + memset(&att_sp, 0, sizeof(att_sp)); + struct vehicle_rates_setpoint_s rates_sp; + memset(&rates_sp, 0, sizeof(rates_sp)); + struct vehicle_global_position_s global_pos; + memset(&global_pos, 0, sizeof(global_pos)); + struct manual_control_setpoint_s manual_sp; + memset(&manual_sp, 0, sizeof(manual_sp)); + struct vehicle_status_s vstatus; + memset(&vstatus, 0, sizeof(vstatus)); + struct vehicle_global_position_setpoint_s global_sp; + memset(&global_sp, 0, sizeof(global_sp)); + + /* output structs */ + struct actuator_controls_s actuators; + memset(&actuators, 0, sizeof(actuators)); + + + /* publish actuator controls */ + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) { + actuators.control[i] = 0.0f; + } + + orb_advert_t actuator_pub = orb_advertise(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, &actuators); + orb_advert_t rates_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); + + /* subscribe */ + int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); + int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); + int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); + int global_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint)); + int param_sub = orb_subscribe(ORB_ID(parameter_update)); + + /* Setup of loop */ + float gyro[3] = {0.0f, 0.0f, 0.0f}; + float speed_body[3] = {0.0f, 0.0f, 0.0f}; + struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN }, + { .fd = att_sub, .events = POLLIN }}; + + while (!thread_should_exit) { + + /* + * Wait for a sensor or param update, check for exit condition every 500 ms. + * This means that the execution will block here without consuming any resources, + * but will continue to execute the very moment a new attitude measurement or + * a param update is published. So no latency in contrast to the polling + * design pattern (do not confuse the poll() system call with polling). + * + * This design pattern makes the controller also agnostic of the attitude + * update speed - it runs as fast as the attitude updates with minimal latency. + */ + int ret = poll(fds, 2, 500); + + if (ret < 0) { + /* poll error, this will not really happen in practice */ + warnx("poll error"); + + } else if (ret == 0) { + /* no return value = nothing changed for 500 ms, ignore */ + } else { + + /* only update parameters if they changed */ + if (fds[0].revents & POLLIN) { + /* read from param to clear updated flag (uORB API requirement) */ + struct parameter_update_s update; + orb_copy(ORB_ID(parameter_update), param_sub, &update); + + /* if a param update occured, re-read our parameters */ + parameters_update(&ph, &p); + } + + /* only run controller if attitude changed */ + if (fds[1].revents & POLLIN) { + + + /* Check if there is a new position measurement or position setpoint */ + bool pos_updated; + orb_check(global_pos_sub, &pos_updated); + bool global_sp_updated; + orb_check(global_sp_sub, &global_sp_updated); + + /* get a local copy of attitude */ + orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); + + if (global_sp_updated) + orb_copy(ORB_ID(vehicle_global_position_setpoint), global_sp_sub, &global_sp); + + if (pos_updated) { + orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos); + + if (att.R_valid) { + speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz; + speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz; + speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz; + + } else { + speed_body[0] = 0; + speed_body[1] = 0; + speed_body[2] = 0; + + warnx("Did not get a valid R\n"); + } + } + + orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp); + orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus); + + gyro[0] = att.rollspeed; + gyro[1] = att.pitchspeed; + gyro[2] = att.yawspeed; + + /* control */ + + if (vstatus.state_machine == SYSTEM_STATE_AUTO || + vstatus.state_machine == SYSTEM_STATE_STABILIZED) { + + /* simple heading control */ + control_heading(&global_pos, &global_sp, &att, &att_sp); + + /* nail pitch and yaw (rudder) to zero. This example only controls roll (index 0) */ + actuators.control[1] = 0.0f; + actuators.control[2] = 0.0f; + + /* simple attitude control */ + control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + /* set flaps to zero */ + actuators.control[4] = 0.0f; + + } else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) { + if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) { + + /* if the RC signal is lost, try to stay level and go slowly back down to ground */ + if (vstatus.rc_signal_lost) { + + /* put plane into loiter */ + att_sp.roll_body = 0.3f; + att_sp.pitch_body = 0.0f; + + /* limit throttle to 60 % of last value if sane */ + if (isfinite(manual_sp.throttle) && + (manual_sp.throttle >= 0.0f) && + (manual_sp.throttle <= 1.0f)) { + att_sp.thrust = 0.6f * manual_sp.throttle; + + } else { + att_sp.thrust = 0.0f; + } + + att_sp.yaw_body = 0; + + // XXX disable yaw control, loiter + + } else { + + att_sp.roll_body = manual_sp.roll; + att_sp.pitch_body = manual_sp.pitch; + att_sp.yaw_body = 0; + att_sp.thrust = manual_sp.throttle; + } + + att_sp.timestamp = hrt_absolute_time(); + + /* attitude control */ + control_attitude(&att_sp, &att, speed_body, gyro, &rates_sp, &actuators); + + /* pass through throttle */ + actuators.control[3] = att_sp.thrust; + + /* pass through flaps */ + if (isfinite(manual_sp.flaps)) { + actuators.control[4] = manual_sp.flaps; + + } else { + actuators.control[4] = 0.0f; + } + + } else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) { + /* directly pass through values */ + actuators.control[0] = manual_sp.roll; + /* positive pitch means negative actuator -> pull up */ + actuators.control[1] = manual_sp.pitch; + actuators.control[2] = manual_sp.yaw; + actuators.control[3] = manual_sp.throttle; + + if (isfinite(manual_sp.flaps)) { + actuators.control[4] = manual_sp.flaps; + + } else { + actuators.control[4] = 0.0f; + } + } + } + + /* publish rates */ + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp); + + /* sanity check and publish actuator outputs */ + if (isfinite(actuators.control[0]) && + isfinite(actuators.control[1]) && + isfinite(actuators.control[2]) && + isfinite(actuators.control[3])) { + orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + } + } + } + } + + printf("[ex_fixedwing_control] exiting, stopping all motors.\n"); + thread_running = false; + + /* kill all outputs */ + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROLS; i++) + actuators.control[i] = 0.0f; + + orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators); + + fflush(stdout); + + return 0; +} + +/* Startup Functions */ + +static void +usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + + fprintf(stderr, "usage: ex_fixedwing_control {start|stop|status}\n\n"); + exit(1); +} + +/** + * The daemon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_create(). + */ +int ex_fixedwing_control_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) { + + if (thread_running) { + printf("ex_fixedwing_control already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + deamon_task = task_spawn("ex_fixedwing_control", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 20, + 2048, + fixedwing_control_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + thread_running = true; + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (thread_running) { + printf("\tex_fixedwing_control is running\n"); + + } else { + printf("\tex_fixedwing_control not started\n"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + + + diff --git a/src/examples/fixedwing_control/module.mk b/src/examples/fixedwing_control/module.mk new file mode 100644 index 0000000000..d2c48934fc --- /dev/null +++ b/src/examples/fixedwing_control/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Fixedwing Attitude Control Demo / Example Application +# + +MODULE_COMMAND = ex_fixedwing_control + +SRCS = main.c \ + params.c diff --git a/src/examples/fixedwing_control/params.c b/src/examples/fixedwing_control/params.c new file mode 100644 index 0000000000..8042c74f5e --- /dev/null +++ b/src/examples/fixedwing_control/params.c @@ -0,0 +1,77 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file params.c + * + * Parameters for fixedwing demo + */ + +#include "params.h" + +/* controller parameters, use max. 15 characters for param name! */ + +/** + * + */ +PARAM_DEFINE_FLOAT(EXFW_HDNG_P, 0.2f); + +/** + * + */ +PARAM_DEFINE_FLOAT(EXFW_ROLL_P, 0.2f); + +/** + * + */ +PARAM_DEFINE_FLOAT(EXFW_PITCH_P, 0.2f); + +int parameters_init(struct param_handles *h) +{ + /* PID parameters */ + h->hdng_p = param_find("EXFW_HDNG_P"); + h->roll_p = param_find("EXFW_ROLL_P"); + h->pitch_p = param_find("EXFW_PITCH_P"); + + return OK; +} + +int parameters_update(const struct param_handles *h, struct params *p) +{ + param_get(h->hdng_p, &(p->hdng_p)); + param_get(h->roll_p, &(p->roll_p)); + param_get(h->pitch_p, &(p->pitch_p)); + + return OK; +} diff --git a/src/examples/fixedwing_control/params.h b/src/examples/fixedwing_control/params.h new file mode 100644 index 0000000000..4ae8e90ec4 --- /dev/null +++ b/src/examples/fixedwing_control/params.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * Author: Lorenz Meier + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/* + * @file params.h + * + * Definition of parameters for fixedwing example + */ + +#include + +struct params { + float hdng_p; + float roll_p; + float pitch_p; +}; + +struct param_handles { + param_t hdng_p; + param_t roll_p; + param_t pitch_p; +}; + +/** + * Initialize all parameter handles and values + * + */ +int parameters_init(struct param_handles *h); + +/** + * Update all parameters + * + */ +int parameters_update(const struct param_handles *h, struct params *p); From edb0e01dfd9c38b826ec038ff7b8387e8ce0bd21 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 12 May 2013 14:04:57 -0700 Subject: [PATCH 075/102] HOTFIX: simplify symbol names going into the ROMFS object, hopefully this avoids inconsistent symbol naming on Windows. --- Makefile | 9 +++++++-- makefiles/firmware.mk | 2 +- makefiles/toolchain_gnu-arm-eabi.mk | 15 +++++++++++++++ 3 files changed, 23 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index 224910e0fc..1d1287b7f7 100644 --- a/Makefile +++ b/Makefile @@ -159,11 +159,11 @@ $(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS) .PHONY: clean clean: $(Q) $(RMDIR) $(BUILD_DIR)*.build - $(Q) $(REMOVE) -f $(IMAGE_DIR)*.px4 + $(Q) $(REMOVE) $(IMAGE_DIR)*.px4 .PHONY: distclean distclean: clean - $(Q) $(REMOVE) -f $(ARCHIVE_DIR)*.export + $(Q) $(REMOVE) $(ARCHIVE_DIR)*.export $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean # @@ -196,6 +196,11 @@ help: @echo " distclean" @echo " Remove all compilation products, including NuttX RTOS archives." @echo "" + @echo " upload" + @echo " When exactly one config is being built, add this target to upload the" + @echo " firmware to the board when the build is complete. Not supported for" + @echo " all configurations." + @echo "" @echo " Common options:" @echo " ---------------" @echo "" diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 6fa0ae3eb0..7afa3e787d 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -280,7 +280,7 @@ ifeq ($(ROMFS_FILES),) $(error ROMFS_ROOT $(ROMFS_ROOT) specifies a directory containing no files) endif ROMFS_DEPS += $(ROMFS_FILES) -ROMFS_IMG = $(WORK_DIR)romfs.img +ROMFS_IMG = romfs.img ROMFS_CSRC = $(ROMFS_IMG:.img=.c) ROMFS_OBJ = $(ROMFS_CSRC:.c=.o) LIBS += $(ROMFS_OBJ) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 0e651e53c8..874e7154c7 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -254,6 +254,20 @@ endef # - relink the object and insert the binary file # - edit symbol names to suit # +# NOTE: exercise caution using this with absolute pathnames; it looks +# like the MinGW tools insert an extra _ in the binary symbol name; e.g. +# the path: +# +# /d/px4/firmware/Build/px4fmu_default.build/romfs.img +# +# is assigned symbols like: +# +# _binary_d__px4_firmware_Build_px4fmu_default_build_romfs_img_size +# +# when we would expect +# +# _binary__d_px4_firmware_Build_px4fmu_default_build_romfs_img_size +# define BIN_SYM_PREFIX _binary_$(subst /,_,$(subst .,_,$1)) endef @@ -267,4 +281,5 @@ define BIN_TO_OBJ --redefine-sym $(call BIN_SYM_PREFIX,$1)_start=$3 \ --redefine-sym $(call BIN_SYM_PREFIX,$1)_size=$3_len \ --strip-symbol $(call BIN_SYM_PREFIX,$1)_end + $(Q) $(REMOVE) $2.c $2.c.o endef From 1ff6c80866775b48bf38de5cdf5dea5f99691fc0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 08:28:36 +0200 Subject: [PATCH 076/102] More example fixes --- makefiles/config_px4fmu_default.mk | 2 +- src/examples/px4_daemon_app/module.mk | 2 +- src/examples/px4_mavlink_debug/module.mk | 2 +- src/examples/px4_simple_app/module.mk | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index 27bf0f973b..ae62b70347 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -107,7 +107,7 @@ MODULES += modules/uORB # Tutorial code from # https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control -MODULES += examples/fixedwing_control +MODULES += examples/fixedwing_control # # Transitional support - add commands from the NuttX export archive. diff --git a/src/examples/px4_daemon_app/module.mk b/src/examples/px4_daemon_app/module.mk index d23c19b75d..5f8aa73d57 100644 --- a/src/examples/px4_daemon_app/module.mk +++ b/src/examples/px4_daemon_app/module.mk @@ -37,4 +37,4 @@ MODULE_COMMAND = px4_daemon_app -SRCS = px4_daemon_app.c +SRCS = px4_daemon_app.c diff --git a/src/examples/px4_mavlink_debug/module.mk b/src/examples/px4_mavlink_debug/module.mk index 3d400fdbfc..fefd614961 100644 --- a/src/examples/px4_mavlink_debug/module.mk +++ b/src/examples/px4_mavlink_debug/module.mk @@ -37,4 +37,4 @@ MODULE_COMMAND = px4_mavlink_debug -SRCS = px4_mavlink_debug.c \ No newline at end of file +SRCS = px4_mavlink_debug.c \ No newline at end of file diff --git a/src/examples/px4_simple_app/module.mk b/src/examples/px4_simple_app/module.mk index 2c102fa500..32b06c3a58 100644 --- a/src/examples/px4_simple_app/module.mk +++ b/src/examples/px4_simple_app/module.mk @@ -37,4 +37,4 @@ MODULE_COMMAND = px4_simple_app -SRCS = px4_simple_app.c +SRCS = px4_simple_app.c From ff518e72d4f8628a44ff5d4106cf56ace6ec97f7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 08:34:48 +0200 Subject: [PATCH 077/102] Make it harder to run into a non-existent uORB error --- ROMFS/px4fmu_common/init.d/rc.sensors | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 42c2f52e94..62c7184b85 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -7,6 +7,14 @@ # Start sensor drivers here. # +# +# Check for UORB +# +if uorb start +then + echo "uORB started" +fi + ms5611 start adc start From 69571c48c4fa742cfbfe9ce2333fc3d9c1f06034 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 10:02:15 +0200 Subject: [PATCH 078/102] Fixed compile and logic errors, behaving now --- src/modules/px4iofirmware/mixer.cpp | 4 ++-- src/modules/px4iofirmware/registers.c | 9 +++++---- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index f38593d2aa..5ada1b220e 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -174,7 +174,7 @@ mixer_tick(void) * here. */ bool should_arm = ( - /* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) && + /* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED) && /* there is valid input */ (r_status_flags & (PX4IO_P_STATUS_FLAGS_RAW_PWM | PX4IO_P_STATUS_FLAGS_MIXER_OK)) && /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) && @@ -246,7 +246,7 @@ void mixer_handle_text(const void *buffer, size_t length) { /* do not allow a mixer change while fully armed */ - if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) && + if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) { return; } diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 4f3addfea8..61049c8b6a 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -142,9 +142,10 @@ volatile uint16_t r_page_setup[] = }; #define PX4IO_P_SETUP_FEATURES_VALID (0) -#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_ARM_OK | \ +#define PX4IO_P_SETUP_ARMING_VALID (PX4IO_P_SETUP_ARMING_FMU_ARMED | \ PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK | \ - PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) + PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK | \ + PX4IO_P_SETUP_ARMING_IO_ARM_OK) #define PX4IO_P_SETUP_RATES_VALID ((1 << IO_SERVO_COUNT) - 1) #define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1) @@ -311,7 +312,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) * so that an in-air reset of FMU can not lead to a * lockup of the IO arming state. */ - if ((r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) && !(value & PX4IO_P_SETUP_ARMING_ARM_OK)) { + if ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && !(value & PX4IO_P_SETUP_ARMING_FMU_ARMED)) { r_status_flags &= ~PX4IO_P_STATUS_FLAGS_ARMED; } @@ -362,7 +363,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) case PX4IO_PAGE_RC_CONFIG: { /* do not allow a RC config change while fully armed */ - if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_ARM_OK) && + if (/* FMU is armed */ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) && /* IO is armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_ARMED)) { break; } From 3ac76c4476038b170c319cfccd4a934363e1aca4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 10:15:36 +0200 Subject: [PATCH 079/102] Blink pattern fixes --- src/modules/px4iofirmware/safety.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/px4iofirmware/safety.c b/src/modules/px4iofirmware/safety.c index f6cd5fb450..4dbecc2744 100644 --- a/src/modules/px4iofirmware/safety.c +++ b/src/modules/px4iofirmware/safety.c @@ -60,6 +60,7 @@ static unsigned counter = 0; #define LED_PATTERN_FMU_OK_TO_ARM 0x0003 /**< slow blinking */ #define LED_PATTERN_FMU_REFUSE_TO_ARM 0x5555 /**< fast blinking */ #define LED_PATTERN_IO_ARMED 0x5050 /**< long off, then double blink */ +#define LED_PATTERN_FMU_ARMED 0x5500 /**< long off, then quad blink */ #define LED_PATTERN_IO_FMU_ARMED 0xffff /**< constantly on */ static unsigned blink_counter = 0; @@ -147,6 +148,8 @@ safety_check_button(void *arg) pattern = LED_PATTERN_IO_ARMED; } + } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) { + pattern = LED_PATTERN_FMU_ARMED; } else if (r_setup_arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) { pattern = LED_PATTERN_FMU_OK_TO_ARM; From 7ae053c16b6bfb8bcd01cfc5418771854363f659 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 10:26:42 +0200 Subject: [PATCH 080/102] Hotfix: Make the param file name less then 8 characters --- ROMFS/px4fmu_common/init.d/rc.FMU_quad_x | 6 +++--- ROMFS/px4fmu_common/init.d/rc.IO_QUAD | 6 +++--- ROMFS/px4fmu_common/init.d/rc.PX4IO | 6 +++--- ROMFS/px4fmu_common/init.d/rc.PX4IOAR | 8 ++++---- ROMFS/px4fmu_common/init.d/rc.hil | 6 +++--- 5 files changed, 16 insertions(+), 16 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x b/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x index 8787443ea2..980197d68e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x +++ b/ROMFS/px4fmu_common/init.d/rc.FMU_quad_x @@ -20,10 +20,10 @@ uorb start # Load microSD params # echo "[init] loading microSD params" -param select /fs/microsd/parameters -if [ -f /fs/microsd/parameters ] +param select /fs/microsd/params +if [ -f /fs/microsd/params ] then - param load /fs/microsd/parameters + param load /fs/microsd/params fi # diff --git a/ROMFS/px4fmu_common/init.d/rc.IO_QUAD b/ROMFS/px4fmu_common/init.d/rc.IO_QUAD index 287cb0483b..5f2de0d7e0 100644 --- a/ROMFS/px4fmu_common/init.d/rc.IO_QUAD +++ b/ROMFS/px4fmu_common/init.d/rc.IO_QUAD @@ -13,10 +13,10 @@ uorb start # Load microSD params # echo "[init] loading microSD params" -param select /fs/microsd/parameters -if [ -f /fs/microsd/parameters ] +param select /fs/microsd/params +if [ -f /fs/microsd/params ] then - param load /fs/microsd/parameters + param load /fs/microsd/params fi # diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IO b/ROMFS/px4fmu_common/init.d/rc.PX4IO index 7ae4a55860..925a5703e7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.PX4IO +++ b/ROMFS/px4fmu_common/init.d/rc.PX4IO @@ -13,10 +13,10 @@ uorb start # Load microSD params # echo "[init] loading microSD params" -param select /fs/microsd/parameters -if [ -f /fs/microsd/parameters ] +param select /fs/microsd/params +if [ -f /fs/microsd/params ] then - param load /fs/microsd/parameters + param load /fs/microsd/params fi # diff --git a/ROMFS/px4fmu_common/init.d/rc.PX4IOAR b/ROMFS/px4fmu_common/init.d/rc.PX4IOAR index ab29e21c7e..f55ac2ae34 100644 --- a/ROMFS/px4fmu_common/init.d/rc.PX4IOAR +++ b/ROMFS/px4fmu_common/init.d/rc.PX4IOAR @@ -17,13 +17,13 @@ echo "[init] doing PX4IOAR startup..." uorb start # -# Init the parameter storage +# Load microSD params # echo "[init] loading microSD params" -param select /fs/microsd/parameters -if [ -f /fs/microsd/parameters ] +param select /fs/microsd/params +if [ -f /fs/microsd/params ] then - param load /fs/microsd/parameters + param load /fs/microsd/params fi # diff --git a/ROMFS/px4fmu_common/init.d/rc.hil b/ROMFS/px4fmu_common/init.d/rc.hil index 980b78edda..7614ac0feb 100644 --- a/ROMFS/px4fmu_common/init.d/rc.hil +++ b/ROMFS/px4fmu_common/init.d/rc.hil @@ -17,10 +17,10 @@ hil mode_pwm # Load microSD params # echo "[init] loading microSD params" -param select /fs/microsd/parameters -if [ -f /fs/microsd/parameters ] +param select /fs/microsd/params +if [ -f /fs/microsd/params ] then - param load /fs/microsd/parameters + param load /fs/microsd/params fi # From 9a07788d58dd6f1ca6657e18048bf88eae5f6e10 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 13 May 2013 23:25:18 +0200 Subject: [PATCH 081/102] Hotfix: Off-by-one fix in overflow check --- src/drivers/ardrone_interface/ardrone_motor_control.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c index f15c74a22d..ecd31a073d 100644 --- a/src/drivers/ardrone_interface/ardrone_motor_control.c +++ b/src/drivers/ardrone_interface/ardrone_motor_control.c @@ -482,10 +482,10 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls motor_pwm[3] = (motor_pwm[3] > 0) ? motor_pwm[3] : 10; /* Failsafe logic - should never be necessary */ - motor_pwm[0] = (motor_pwm[0] <= 512) ? motor_pwm[0] : 512; - motor_pwm[1] = (motor_pwm[1] <= 512) ? motor_pwm[1] : 512; - motor_pwm[2] = (motor_pwm[2] <= 512) ? motor_pwm[2] : 512; - motor_pwm[3] = (motor_pwm[3] <= 512) ? motor_pwm[3] : 512; + motor_pwm[0] = (motor_pwm[0] <= 511) ? motor_pwm[0] : 511; + motor_pwm[1] = (motor_pwm[1] <= 511) ? motor_pwm[1] : 511; + motor_pwm[2] = (motor_pwm[2] <= 511) ? motor_pwm[2] : 511; + motor_pwm[3] = (motor_pwm[3] <= 511) ? motor_pwm[3] : 511; /* send motors via UART */ ardrone_write_motor_commands(ardrone_write, motor_pwm[0], motor_pwm[1], motor_pwm[2], motor_pwm[3]); From 0c43315c1ed8538daee9ad47c14731c295c2dda2 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 13 May 2013 22:20:08 -0700 Subject: [PATCH 082/102] Hotfix: better error messages for missing modules --- makefiles/firmware.mk | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 7afa3e787d..497e792376 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -201,9 +201,9 @@ MODULES := $(sort $(MODULES)) # locate the first instance of a module by full path or by looking on the # module search path define MODULE_SEARCH - $(abspath $(firstword $(wildcard $(1)/module.mk) \ - $(foreach search_dir,$(MODULE_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/module.mk)) \ - MISSING_$1)) + $(firstword $(abspath $(wildcard $(1)/module.mk)) \ + $(abspath $(foreach search_dir,$(MODULE_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/module.mk))) \ + MISSING_$1) endef # make a list of module makefiles and check that we found them all From fa816d0fd65da461fd5bf8803cf00caebaf23c5c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 May 2013 16:21:33 +1000 Subject: [PATCH 083/102] arming: added PWM_SERVO_SET_ARM_OK and PWM_SERVO_CLEAR_ARM_OK these new ioctls allow for the flight code to tell the IO board that arming can proceed --- src/drivers/drv_pwm_output.h | 6 ++++++ src/drivers/px4fmu/fmu.cpp | 5 +++++ src/drivers/px4io/px4io.cpp | 10 ++++++++++ 3 files changed, 21 insertions(+) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 07831f20cf..56af710592 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -109,6 +109,12 @@ ORB_DECLARE(output_pwm); /** selects servo update rates, one bit per servo. 0 = default (50Hz), 1 = alternate */ #define PWM_SERVO_SELECT_UPDATE_RATE _IOC(_PWM_SERVO_BASE, 4) +/** set the 'ARM ok' bit, which activates the safety switch */ +#define PWM_SERVO_SET_ARM_OK _IOC(_PWM_SERVO_BASE, 5) + +/** clear the 'ARM ok' bit, which deactivates the safety switch */ +#define PWM_SERVO_CLEAR_ARM_OK _IOC(_PWM_SERVO_BASE, 6) + /** set a single servo to a specific value */ #define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 761a23c426..bf72892ebe 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -606,6 +606,11 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) up_pwm_servo_arm(true); break; + case PWM_SERVO_SET_ARM_OK: + case PWM_SERVO_CLEAR_ARM_OK: + // these are no-ops, as no safety switch + break; + case PWM_SERVO_DISARM: up_pwm_servo_arm(false); break; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 3006cf885b..a40142792a 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1358,6 +1358,16 @@ PX4IO::ioctl(file *filep, int cmd, unsigned long arg) ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_FMU_ARMED); break; + case PWM_SERVO_SET_ARM_OK: + /* set the 'OK to arm' bit */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_IO_ARM_OK); + break; + + case PWM_SERVO_CLEAR_ARM_OK: + /* clear the 'OK to arm' bit */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_IO_ARM_OK, 0); + break; + case PWM_SERVO_DISARM: /* clear the 'armed' bit */ ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FMU_ARMED, 0); From 504b6d12561d68874ded4c1f747c21926a065045 Mon Sep 17 00:00:00 2001 From: px4dev Date: Fri, 17 May 2013 01:55:02 -0700 Subject: [PATCH 084/102] Hotfix: install the firmware .bin files as well as the .px4 bundles until we have a chance to fix the px4io uploader. --- Makefile | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Makefile b/Makefile index 1d1287b7f7..dea3443901 100644 --- a/Makefile +++ b/Makefile @@ -95,9 +95,14 @@ all: $(STAGED_FIRMWARES) # # Copy FIRMWARES into the image directory. # +# XXX copying the .bin files is a hack to work around the PX4IO uploader +# not supporting .px4 files, and it should be deprecated onced that +# is taken care of. +# $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4 @echo %% Copying $@ $(Q) $(COPY) $< $@ + $(Q) $(COPY) $(patsubst %.px4,%.bin,$<) $(patsubst %.px4,%.bin,$@) # # Generate FIRMWARES. From 40b732b3366db18efb7a8365746c869feca8c843 Mon Sep 17 00:00:00 2001 From: Duncan Greer Date: Sat, 18 May 2013 20:07:01 +1000 Subject: [PATCH 085/102] Added CCPM mixer --- ROMFS/px4fmu_common/mixers/FMU_CCPM.mix | 53 +++++++++++++++++++++++++ 1 file changed, 53 insertions(+) create mode 100644 ROMFS/px4fmu_common/mixers/FMU_CCPM.mix diff --git a/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix b/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix new file mode 100644 index 0000000000..8ac1626c7b --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix @@ -0,0 +1,53 @@ +Helicopter 120 degree Cyclic-Collective-Pitch Mixing (CCPM) for PX4FMU +================================================== + + +Output 0 - Rear Servo Mixer +---------------- + +Rear Servo = Collective (Thrust - 3) + Elevator (Pitch - 1) + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 3 10000 10000 0 -10000 10000 +S: 0 1 10000 10000 0 -10000 10000 + + +Output 1 - Left Servo Mixer +----------------- +Left Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) + 0.866 * Aileron (Roll - 0) + +M: 3 +O: 10000 10000 0 -10000 10000 +S: 0 3 -10000 -10000 0 -10000 10000 +S: 0 1 -5000 -5000 0 -10000 10000 +S: 0 0 8660 8660 0 -10000 10000 + + +Output 2 - Right Servo Mixer +---------------- +Right Servo = Collective (Thurst - 3) - 0.5 * Elevator (Pitch - 1) - 0.866 * Aileron (Roll - 0) + + +M: 3 +O: 10000 10000 0 -10000 10000 +S: 0 3 -10000 -10000 0 -10000 10000 +S: 0 1 -5000 -5000 0 -10000 10000 +S: 0 0 -8660 -8660 0 -10000 10000 + +Output 3 - Tail Servo Mixer +---------------- +Tail Servo = Yaw (control index = 2) + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 2 10000 10000 0 -10000 10000 + + +Output 4 - Motor speed mixer +----------------- +This would be the governor output - not sure what group id to use here? + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 5 0 20000 -10000 -10000 10000 From eab8f9b28608f7f91641442e833b2324710147d9 Mon Sep 17 00:00:00 2001 From: Duncan Greer Date: Sat, 18 May 2013 20:12:08 +1000 Subject: [PATCH 086/102] changed control index for speed controller output from 5 to 4 --- ROMFS/px4fmu_common/mixers/FMU_CCPM.mix | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix b/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix index 8ac1626c7b..1c45b3e59f 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_CCPM.mix @@ -46,8 +46,8 @@ S: 0 2 10000 10000 0 -10000 10000 Output 4 - Motor speed mixer ----------------- -This would be the governor output - not sure what group id to use here? +This would be the motor speed control output from governor power demand- not sure what index to use here? M: 1 O: 10000 10000 0 -10000 10000 -S: 0 5 0 20000 -10000 -10000 10000 +S: 0 4 0 20000 -10000 -10000 10000 From 3a1c9f14f68054537657851eacb60d930c3d4221 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 20 May 2013 00:26:41 +0200 Subject: [PATCH 087/102] Teach the PX4 build system how to handle pre-built libraries. --- makefiles/firmware.mk | 76 +++++++++++++++---- makefiles/library.mk | 169 ++++++++++++++++++++++++++++++++++++++++++ makefiles/module.mk | 24 +----- 3 files changed, 233 insertions(+), 36 deletions(-) create mode 100644 makefiles/library.mk diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk index 497e792376..6b09e6ec32 100644 --- a/makefiles/firmware.mk +++ b/makefiles/firmware.mk @@ -180,18 +180,6 @@ EXTRA_CLEANS = # Modules ################################################################################ -# -# We don't actually know what a module is called; all we have is a path fragment -# that we can search for, and where we expect to find a module.mk file. -# -# As such, we replicate the successfully-found path inside WORK_DIR for the -# module's build products in order to keep modules separated from each other. -# -# XXX If this becomes unwieldy or breaks for other reasons, we will need to -# move to allocating directory names and keeping tabs on makefiles via -# the directory name. That will involve arithmetic (it'd probably be time -# for GMSL). - # where to look for modules MODULE_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC) @@ -248,6 +236,66 @@ $(MODULE_CLEANS): MODULE_MK=$(mkfile) \ clean +################################################################################ +# Libraries +################################################################################ + +# where to look for libraries +LIBRARY_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC) + +# sort and unique the library list +LIBRARIES := $(sort $(LIBRARIES)) + +# locate the first instance of a library by full path or by looking on the +# library search path +define LIBRARY_SEARCH + $(firstword $(abspath $(wildcard $(1)/library.mk)) \ + $(abspath $(foreach search_dir,$(LIBRARY_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/library.mk))) \ + MISSING_$1) +endef + +# make a list of library makefiles and check that we found them all +LIBRARY_MKFILES := $(foreach library,$(LIBRARIES),$(call LIBRARY_SEARCH,$(library))) +MISSING_LIBRARIES := $(subst MISSING_,,$(filter MISSING_%,$(LIBRARY_MKFILES))) +ifneq ($(MISSING_LIBRARIES),) +$(error Can't find library(s): $(MISSING_LIBRARIES)) +endif + +# Make a list of the archive files we expect to build from libraries +# Note that this path will typically contain a double-slash at the WORK_DIR boundary; this must be +# preserved as it is used below to get the absolute path for the library.mk file correct. +# +LIBRARY_LIBS := $(foreach path,$(dir $(LIBRARY_MKFILES)),$(WORK_DIR)$(path)library.a) + +# rules to build module objects +.PHONY: $(LIBRARY_LIBS) +$(LIBRARY_LIBS): relpath = $(patsubst $(WORK_DIR)%,%,$@) +$(LIBRARY_LIBS): mkfile = $(patsubst %library.a,%library.mk,$(relpath)) +$(LIBRARY_LIBS): workdir = $(@D) +$(LIBRARY_LIBS): $(GLOBAL_DEPS) $(NUTTX_CONFIG_HEADER) + $(Q) $(MKDIR) -p $(workdir) + $(Q) $(MAKE) -r -f $(PX4_MK_DIR)library.mk \ + -C $(workdir) \ + LIBRARY_WORK_DIR=$(workdir) \ + LIBRARY_LIB=$@ \ + LIBRARY_MK=$(mkfile) \ + LIBRARY_NAME=$(lastword $(subst /, ,$(workdir))) \ + library + +# make a list of phony clean targets for modules +LIBRARY_CLEANS := $(foreach path,$(dir $(LIBRARY_MKFILES)),$(WORK_DIR)$(path)/clean) + +# rules to clean modules +.PHONY: $(LIBRARY_CLEANS) +$(LIBRARY_CLEANS): relpath = $(patsubst $(WORK_DIR)%,%,$@) +$(LIBRARY_CLEANS): mkfile = $(patsubst %clean,%library.mk,$(relpath)) +$(LIBRARY_CLEANS): + @$(ECHO) %% cleaning using $(mkfile) + $(Q) $(MAKE) -r -f $(PX4_MK_DIR)library.mk \ + LIBRARY_WORK_DIR=$(dir $@) \ + LIBRARY_MK=$(mkfile) \ + clean + ################################################################################ # NuttX libraries and paths ################################################################################ @@ -420,8 +468,8 @@ $(PRODUCT_BUNDLE): $(PRODUCT_BIN) $(PRODUCT_BIN): $(PRODUCT_ELF) $(call SYM_TO_BIN,$<,$@) -$(PRODUCT_ELF): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES) - $(call LINK,$@,$(OBJS) $(MODULE_OBJS)) +$(PRODUCT_ELF): $(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES) + $(call LINK,$@,$(OBJS) $(MODULE_OBJS) $(LIBRARY_LIBS)) # # Utility rules diff --git a/makefiles/library.mk b/makefiles/library.mk new file mode 100644 index 0000000000..28a421fe0e --- /dev/null +++ b/makefiles/library.mk @@ -0,0 +1,169 @@ +# +# Copyright (c) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# + +# +# Framework makefile for PX4 libraries +# +# This makefile is invoked by firmware.mk to build each of the linraries +# that will subsequently be linked into the firmware image. +# +# Applications are built as standard ar archives. Unlike modules, +# all public symbols in library objects are visible across the entire +# firmware stack. +# +# In general, modules should be preferred to libraries when possible. +# Libraries may also be pre-built. +# +# IMPORTANT NOTE: +# +# This makefile assumes it is being invoked in the library's output directory. +# + +# +# Variables that can be set by the library's library.mk: +# +# +# SRCS (optional) +# +# Lists the .c, cpp and .S files that should be compiled/assembled to +# produce the library. +# +# PREBUILT_LIB (optional) +# +# Names the prebuilt library in the source directory that should be +# linked into the firmware. +# +# INCLUDE_DIRS (optional, must be appended, ignored if SRCS not set) +# +# The list of directories searched for include files. If non-standard +# includes (e.g. those from another module) are required, paths to search +# can be added here. +# +# + +# +# Variables visible to the library's library.mk: +# +# CONFIG +# BOARD +# LIBRARY_WORK_DIR +# LIBRARY_LIB +# LIBRARY_MK +# Anything set in setup.mk, board_$(BOARD).mk and the toolchain file. +# Anything exported from config_$(CONFIG).mk +# + +################################################################################ +# No user-serviceable parts below. +################################################################################ + +ifeq ($(LIBRARY_MK),) +$(error No library makefile specified) +endif +$(info %% LIBRARY_MK = $(LIBRARY_MK)) + +# +# Get the board/toolchain config +# +include $(PX4_MK_DIR)/board_$(BOARD).mk + +# +# Get the library's config +# +include $(LIBRARY_MK) +LIBRARY_SRC := $(dir $(LIBRARY_MK)) +$(info % LIBRARY_NAME = $(LIBRARY_NAME)) +$(info % LIBRARY_SRC = $(LIBRARY_SRC)) +$(info % LIBRARY_LIB = $(LIBRARY_LIB)) +$(info % LIBRARY_WORK_DIR = $(LIBRARY_WORK_DIR)) + +# +# Things that, if they change, might affect everything +# +GLOBAL_DEPS += $(MAKEFILE_LIST) + +################################################################################ +# Build rules +################################################################################ + +# +# What we're going to build +# +library: $(LIBRARY_LIB) + +ifneq ($(PREBUILT_LIB),) + +VPATH = $(LIBRARY_SRC) +$(LIBRARY_LIB): $(PREBUILT_LIB) $(GLOBAL_DEPS) + @$(ECHO) "PREBUILT: $(PREBUILT_LIB)" + $(Q) $(COPY) $< $@ + +else + +## +## Object files we will generate from sources +## + +OBJS = $(addsuffix .o,$(SRCS)) + +# +# SRCS -> OBJS rules +# + +$(OBJS): $(GLOBAL_DEPS) + +vpath %.c $(LIBRARY_SRC) +$(filter %.c.o,$(OBJS)): %.c.o: %.c $(GLOBAL_DEPS) + $(call COMPILE,$<,$@) + +vpath %.cpp $(LIBRARY_SRC) +$(filter %.cpp.o,$(OBJS)): %.cpp.o: %.cpp $(GLOBAL_DEPS) + $(call COMPILEXX,$<,$@) + +vpath %.S $(LIBRARY_SRC) +$(filter %.S.o,$(OBJS)): %.S.o: %.S $(GLOBAL_DEPS) + $(call ASSEMBLE,$<,$@) + +# +# Built product rules +# + +$(LIBRARY_LIB): $(OBJS) $(GLOBAL_DEPS) + $(call ARCHIVE,$@,$(OBJS)) + +endif + +# +# Utility rules +# + +clean: + $(Q) $(REMOVE) $(LIBRARY_LIB) $(OBJS) diff --git a/makefiles/module.mk b/makefiles/module.mk index db6f4e15ec..074cd159ae 100644 --- a/makefiles/module.mk +++ b/makefiles/module.mk @@ -35,7 +35,7 @@ # This makefile is invoked by firmware.mk to build each of the modules # that will subsequently be linked into the firmware image. # -# Applications are built as prelinked objects with a limited set of exported +# Modules are built as prelinked objects with a limited set of exported # symbols, as the global namespace is shared between all modules. Normally an # module will just export one or more _main functions. # @@ -183,30 +183,10 @@ CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibi # module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES) -## -## Locate sources (allows relative source paths in module.mk) -## -#define SRC_SEARCH -# $(abspath $(firstword $(wildcard $1) $(wildcard $(MODULE_SRC)/$1) MISSING_$1)) -#endef -# -#ABS_SRCS ?= $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src))) -#MISSING_SRCS := $(subst MISSING_,,$(filter MISSING_%,$(ABS_SRCS))) -#ifneq ($(MISSING_SRCS),) -#$(error $(MODULE_MK): missing in SRCS: $(MISSING_SRCS)) -#endif -#ifeq ($(ABS_SRCS),) -#$(error $(MODULE_MK): nothing to compile in SRCS) -#endif -# ## ## Object files we will generate from sources ## -#OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o) - -OBJS = $(addsuffix .o,$(SRCS)) -$(info SRCS $(SRCS)) -$(info OBJS $(OBJS)) +OBJS = $(addsuffix .o,$(SRCS)) # # SRCS -> OBJS rules From 5576e321fa8cd027b15deeb15b7ca05541fde4fe Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 20 May 2013 00:30:43 +0200 Subject: [PATCH 088/102] Use the new prebuilt-library support to wrap the ARM CMSIS DSP library, and update to the version shipped with CMSIS 3.0 r3p2 --- makefiles/config_px4fmu_default.mk | 8 +- .../Source/BasicMathFunctions/arm_abs_f32.c | 159 - .../Source/BasicMathFunctions/arm_abs_q15.c | 173 - .../Source/BasicMathFunctions/arm_abs_q31.c | 125 - .../Source/BasicMathFunctions/arm_abs_q7.c | 152 - .../Source/BasicMathFunctions/arm_add_f32.c | 145 - .../Source/BasicMathFunctions/arm_add_q15.c | 135 - .../Source/BasicMathFunctions/arm_add_q31.c | 143 - .../Source/BasicMathFunctions/arm_add_q7.c | 129 - .../BasicMathFunctions/arm_dot_prod_f32.c | 125 - .../BasicMathFunctions/arm_dot_prod_q15.c | 135 - .../BasicMathFunctions/arm_dot_prod_q31.c | 138 - .../BasicMathFunctions/arm_dot_prod_q7.c | 154 - .../Source/BasicMathFunctions/arm_mult_f32.c | 172 - .../Source/BasicMathFunctions/arm_mult_q15.c | 152 - .../Source/BasicMathFunctions/arm_mult_q31.c | 143 - .../Source/BasicMathFunctions/arm_mult_q7.c | 128 - .../BasicMathFunctions/arm_negate_f32.c | 137 - .../BasicMathFunctions/arm_negate_q15.c | 137 - .../BasicMathFunctions/arm_negate_q31.c | 124 - .../Source/BasicMathFunctions/arm_negate_q7.c | 120 - .../BasicMathFunctions/arm_offset_f32.c | 158 - .../BasicMathFunctions/arm_offset_q15.c | 131 - .../BasicMathFunctions/arm_offset_q31.c | 135 - .../Source/BasicMathFunctions/arm_offset_q7.c | 130 - .../Source/BasicMathFunctions/arm_scale_f32.c | 161 - .../Source/BasicMathFunctions/arm_scale_q15.c | 157 - .../Source/BasicMathFunctions/arm_scale_q31.c | 221 - .../Source/BasicMathFunctions/arm_scale_q7.c | 144 - .../Source/BasicMathFunctions/arm_shift_q15.c | 243 - .../Source/BasicMathFunctions/arm_shift_q31.c | 195 - .../Source/BasicMathFunctions/arm_shift_q7.c | 215 - .../Source/BasicMathFunctions/arm_sub_f32.c | 145 - .../Source/BasicMathFunctions/arm_sub_q15.c | 135 - .../Source/BasicMathFunctions/arm_sub_q31.c | 141 - .../Source/BasicMathFunctions/arm_sub_q7.c | 126 - .../Source/CommonTables/arm_common_tables.c | 4689 ----- .../ComplexMathFunctions/arm_cmplx_conj_f32.c | 174 - .../ComplexMathFunctions/arm_cmplx_conj_q15.c | 153 - .../ComplexMathFunctions/arm_cmplx_conj_q31.c | 172 - .../arm_cmplx_dot_prod_f32.c | 160 - .../arm_cmplx_dot_prod_q15.c | 144 - .../arm_cmplx_dot_prod_q31.c | 145 - .../ComplexMathFunctions/arm_cmplx_mag_f32.c | 157 - .../ComplexMathFunctions/arm_cmplx_mag_q15.c | 145 - .../ComplexMathFunctions/arm_cmplx_mag_q31.c | 177 - .../arm_cmplx_mag_squared_f32.c | 207 - .../arm_cmplx_mag_squared_q15.c | 140 - .../arm_cmplx_mag_squared_q31.c | 153 - .../arm_cmplx_mult_cmplx_f32.c | 199 - .../arm_cmplx_mult_cmplx_q15.c | 185 - .../arm_cmplx_mult_cmplx_q31.c | 318 - .../arm_cmplx_mult_real_f32.c | 217 - .../arm_cmplx_mult_real_q15.c | 195 - .../arm_cmplx_mult_real_q31.c | 215 - .../ControllerFunctions/arm_pid_init_f32.c | 79 - .../ControllerFunctions/arm_pid_init_q15.c | 114 - .../ControllerFunctions/arm_pid_init_q31.c | 99 - .../ControllerFunctions/arm_pid_reset_f32.c | 57 - .../ControllerFunctions/arm_pid_reset_q15.c | 56 - .../ControllerFunctions/arm_pid_reset_q31.c | 57 - .../ControllerFunctions/arm_sin_cos_f32.c | 428 - .../ControllerFunctions/arm_sin_cos_q31.c | 324 - .../Source/FastMathFunctions/arm_cos_f32.c | 280 - .../Source/FastMathFunctions/arm_cos_q15.c | 205 - .../Source/FastMathFunctions/arm_cos_q31.c | 239 - .../Source/FastMathFunctions/arm_sin_f32.c | 281 - .../Source/FastMathFunctions/arm_sin_q15.c | 208 - .../Source/FastMathFunctions/arm_sin_q31.c | 240 - .../Source/FastMathFunctions/arm_sqrt_q15.c | 131 - .../Source/FastMathFunctions/arm_sqrt_q31.c | 129 - .../arm_biquad_cascade_df1_32x64_init_q31.c | 105 - .../arm_biquad_cascade_df1_32x64_q31.c | 553 - .../arm_biquad_cascade_df1_f32.c | 421 - .../arm_biquad_cascade_df1_fast_q15.c | 283 - .../arm_biquad_cascade_df1_fast_q31.c | 275 - .../arm_biquad_cascade_df1_init_f32.c | 107 - .../arm_biquad_cascade_df1_init_q15.c | 109 - .../arm_biquad_cascade_df1_init_q31.c | 109 - .../arm_biquad_cascade_df1_q15.c | 408 - .../arm_biquad_cascade_df1_q31.c | 400 - .../arm_biquad_cascade_df2T_f32.c | 377 - .../arm_biquad_cascade_df2T_init_f32.c | 97 - .../Source/FilteringFunctions/arm_conv_f32.c | 646 - .../arm_conv_fast_opt_q15.c | 538 - .../FilteringFunctions/arm_conv_fast_q15.c | 1405 -- .../FilteringFunctions/arm_conv_fast_q31.c | 572 - .../FilteringFunctions/arm_conv_opt_q15.c | 544 - .../FilteringFunctions/arm_conv_opt_q7.c | 434 - .../FilteringFunctions/arm_conv_partial_f32.c | 661 - .../arm_conv_partial_fast_opt_q15.c | 763 - .../arm_conv_partial_fast_q15.c | 1473 -- .../arm_conv_partial_fast_q31.c | 599 - .../arm_conv_partial_opt_q15.c | 764 - .../arm_conv_partial_opt_q7.c | 806 - .../FilteringFunctions/arm_conv_partial_q15.c | 778 - .../FilteringFunctions/arm_conv_partial_q31.c | 599 - .../FilteringFunctions/arm_conv_partial_q7.c | 733 - .../Source/FilteringFunctions/arm_conv_q15.c | 733 - .../Source/FilteringFunctions/arm_conv_q31.c | 564 - .../Source/FilteringFunctions/arm_conv_q7.c | 689 - .../FilteringFunctions/arm_correlate_f32.c | 738 - .../arm_correlate_fast_opt_q15.c | 507 - .../arm_correlate_fast_q15.c | 1314 -- .../arm_correlate_fast_q31.c | 607 - .../arm_correlate_opt_q15.c | 512 - .../FilteringFunctions/arm_correlate_opt_q7.c | 463 - .../FilteringFunctions/arm_correlate_q15.c | 718 - .../FilteringFunctions/arm_correlate_q31.c | 664 - .../FilteringFunctions/arm_correlate_q7.c | 789 - .../FilteringFunctions/arm_fir_decimate_f32.c | 518 - .../arm_fir_decimate_fast_q15.c | 590 - .../arm_fir_decimate_fast_q31.c | 343 - .../arm_fir_decimate_init_f32.c | 112 - .../arm_fir_decimate_init_q15.c | 114 - .../arm_fir_decimate_init_q31.c | 112 - .../FilteringFunctions/arm_fir_decimate_q15.c | 691 - .../FilteringFunctions/arm_fir_decimate_q31.c | 306 - .../Source/FilteringFunctions/arm_fir_f32.c | 554 - .../FilteringFunctions/arm_fir_fast_q15.c | 341 - .../FilteringFunctions/arm_fir_fast_q31.c | 309 - .../FilteringFunctions/arm_fir_init_f32.c | 94 - .../FilteringFunctions/arm_fir_init_q15.c | 152 - .../FilteringFunctions/arm_fir_init_q31.c | 94 - .../FilteringFunctions/arm_fir_init_q7.c | 92 - .../arm_fir_interpolate_f32.c | 574 - .../arm_fir_interpolate_init_f32.c | 116 - .../arm_fir_interpolate_init_q15.c | 115 - .../arm_fir_interpolate_init_q31.c | 116 - .../arm_fir_interpolate_q15.c | 503 - .../arm_fir_interpolate_q31.c | 499 - .../FilteringFunctions/arm_fir_lattice_f32.c | 499 - .../arm_fir_lattice_init_f32.c | 78 - .../arm_fir_lattice_init_q15.c | 78 - .../arm_fir_lattice_init_q31.c | 78 - .../FilteringFunctions/arm_fir_lattice_q15.c | 531 - .../FilteringFunctions/arm_fir_lattice_q31.c | 348 - .../Source/FilteringFunctions/arm_fir_q15.c | 689 - .../Source/FilteringFunctions/arm_fir_q31.c | 363 - .../Source/FilteringFunctions/arm_fir_q7.c | 388 - .../FilteringFunctions/arm_fir_sparse_f32.c | 365 - .../arm_fir_sparse_init_f32.c | 102 - .../arm_fir_sparse_init_q15.c | 102 - .../arm_fir_sparse_init_q31.c | 101 - .../arm_fir_sparse_init_q7.c | 102 - .../FilteringFunctions/arm_fir_sparse_q15.c | 406 - .../FilteringFunctions/arm_fir_sparse_q31.c | 370 - .../FilteringFunctions/arm_fir_sparse_q7.c | 398 - .../FilteringFunctions/arm_iir_lattice_f32.c | 440 - .../arm_iir_lattice_init_f32.c | 86 - .../arm_iir_lattice_init_q15.c | 86 - .../arm_iir_lattice_init_q31.c | 86 - .../FilteringFunctions/arm_iir_lattice_q15.c | 457 - .../FilteringFunctions/arm_iir_lattice_q31.c | 345 - .../Source/FilteringFunctions/arm_lms_f32.c | 434 - .../FilteringFunctions/arm_lms_init_f32.c | 90 - .../FilteringFunctions/arm_lms_init_q15.c | 100 - .../FilteringFunctions/arm_lms_init_q31.c | 100 - .../FilteringFunctions/arm_lms_norm_f32.c | 456 - .../arm_lms_norm_init_f32.c | 100 - .../arm_lms_norm_init_q15.c | 107 - .../arm_lms_norm_init_q31.c | 106 - .../FilteringFunctions/arm_lms_norm_q15.c | 435 - .../FilteringFunctions/arm_lms_norm_q31.c | 426 - .../Source/FilteringFunctions/arm_lms_q15.c | 374 - .../Source/FilteringFunctions/arm_lms_q31.c | 364 - .../Source/MatrixFunctions/arm_mat_add_f32.c | 206 - .../Source/MatrixFunctions/arm_mat_add_q15.c | 161 - .../Source/MatrixFunctions/arm_mat_add_q31.c | 205 - .../Source/MatrixFunctions/arm_mat_init_f32.c | 86 - .../Source/MatrixFunctions/arm_mat_init_q15.c | 78 - .../Source/MatrixFunctions/arm_mat_init_q31.c | 82 - .../MatrixFunctions/arm_mat_inverse_f32.c | 668 - .../Source/MatrixFunctions/arm_mat_mult_f32.c | 284 - .../MatrixFunctions/arm_mat_mult_fast_q15.c | 361 - .../MatrixFunctions/arm_mat_mult_fast_q31.c | 218 - .../Source/MatrixFunctions/arm_mat_mult_q15.c | 467 - .../Source/MatrixFunctions/arm_mat_mult_q31.c | 292 - .../MatrixFunctions/arm_mat_scale_f32.c | 179 - .../MatrixFunctions/arm_mat_scale_q15.c | 181 - .../MatrixFunctions/arm_mat_scale_q31.c | 201 - .../Source/MatrixFunctions/arm_mat_sub_f32.c | 207 - .../Source/MatrixFunctions/arm_mat_sub_q15.c | 158 - .../Source/MatrixFunctions/arm_mat_sub_q31.c | 206 - .../MatrixFunctions/arm_mat_trans_f32.c | 216 - .../MatrixFunctions/arm_mat_trans_q15.c | 282 - .../MatrixFunctions/arm_mat_trans_q31.c | 208 - .../Source/StatisticsFunctions/arm_max_f32.c | 178 - .../Source/StatisticsFunctions/arm_max_q15.c | 168 - .../Source/StatisticsFunctions/arm_max_q31.c | 169 - .../Source/StatisticsFunctions/arm_max_q7.c | 169 - .../Source/StatisticsFunctions/arm_mean_f32.c | 131 - .../Source/StatisticsFunctions/arm_mean_q15.c | 125 - .../Source/StatisticsFunctions/arm_mean_q31.c | 128 - .../Source/StatisticsFunctions/arm_mean_q7.c | 125 - .../Source/StatisticsFunctions/arm_min_f32.c | 175 - .../Source/StatisticsFunctions/arm_min_q15.c | 169 - .../Source/StatisticsFunctions/arm_min_q31.c | 168 - .../Source/StatisticsFunctions/arm_min_q7.c | 170 - .../StatisticsFunctions/arm_power_f32.c | 138 - .../StatisticsFunctions/arm_power_q15.c | 144 - .../StatisticsFunctions/arm_power_q31.c | 135 - .../Source/StatisticsFunctions/arm_power_q7.c | 133 - .../Source/StatisticsFunctions/arm_rms_f32.c | 133 - .../Source/StatisticsFunctions/arm_rms_q15.c | 153 - .../Source/StatisticsFunctions/arm_rms_q31.c | 146 - .../Source/StatisticsFunctions/arm_std_f32.c | 188 - .../Source/StatisticsFunctions/arm_std_q15.c | 197 - .../Source/StatisticsFunctions/arm_std_q31.c | 184 - .../Source/StatisticsFunctions/arm_var_f32.c | 184 - .../Source/StatisticsFunctions/arm_var_q15.c | 180 - .../Source/StatisticsFunctions/arm_var_q31.c | 170 - .../Source/SupportFunctions/arm_copy_f32.c | 130 - .../Source/SupportFunctions/arm_copy_q15.c | 109 - .../Source/SupportFunctions/arm_copy_q31.c | 118 - .../Source/SupportFunctions/arm_copy_q7.c | 110 - .../Source/SupportFunctions/arm_fill_f32.c | 129 - .../Source/SupportFunctions/arm_fill_q15.c | 115 - .../Source/SupportFunctions/arm_fill_q31.c | 116 - .../Source/SupportFunctions/arm_fill_q7.c | 113 - .../SupportFunctions/arm_float_to_q15.c | 196 - .../SupportFunctions/arm_float_to_q31.c | 203 - .../Source/SupportFunctions/arm_float_to_q7.c | 195 - .../SupportFunctions/arm_q15_to_float.c | 126 - .../Source/SupportFunctions/arm_q15_to_q31.c | 148 - .../Source/SupportFunctions/arm_q15_to_q7.c | 146 - .../SupportFunctions/arm_q31_to_float.c | 123 - .../Source/SupportFunctions/arm_q31_to_q15.c | 137 - .../Source/SupportFunctions/arm_q31_to_q7.c | 128 - .../Source/SupportFunctions/arm_q7_to_float.c | 123 - .../Source/SupportFunctions/arm_q7_to_q15.c | 149 - .../Source/SupportFunctions/arm_q7_to_q31.c | 134 - .../TransformFunctions/arm_bitreversal.c | 222 - .../TransformFunctions/arm_cfft_radix2_f32.c | 511 - .../arm_cfft_radix2_init_f32.c | 198 - .../arm_cfft_radix2_init_q15.c | 186 - .../arm_cfft_radix2_init_q31.c | 164 - .../TransformFunctions/arm_cfft_radix2_q15.c | 712 - .../TransformFunctions/arm_cfft_radix2_q31.c | 310 - .../TransformFunctions/arm_cfft_radix4_f32.c | 1236 -- .../arm_cfft_radix4_init_f32.c | 161 - .../arm_cfft_radix4_init_q15.c | 149 - .../arm_cfft_radix4_init_q31.c | 145 - .../TransformFunctions/arm_cfft_radix4_q15.c | 1896 -- .../TransformFunctions/arm_cfft_radix4_q31.c | 891 - .../Source/TransformFunctions/arm_dct4_f32.c | 453 - .../TransformFunctions/arm_dct4_init_f32.c | 16511 ---------------- .../TransformFunctions/arm_dct4_init_q15.c | 4276 ---- .../TransformFunctions/arm_dct4_init_q31.c | 8356 -------- .../Source/TransformFunctions/arm_dct4_q15.c | 386 - .../Source/TransformFunctions/arm_dct4_q31.c | 387 - .../Source/TransformFunctions/arm_rfft_f32.c | 382 - .../TransformFunctions/arm_rfft_init_f32.c | 8369 -------- .../TransformFunctions/arm_rfft_init_q15.c | 2229 --- .../TransformFunctions/arm_rfft_init_q31.c | 4274 ---- .../Source/TransformFunctions/arm_rfft_q15.c | 460 - .../Source/TransformFunctions/arm_rfft_q31.c | 326 - .../mathlib/CMSIS/Include/arm_common_tables.h | 97 +- .../mathlib/CMSIS/Include/arm_const_structs.h | 85 + src/modules/mathlib/CMSIS/Include/arm_math.h | 1467 +- src/modules/mathlib/CMSIS/Include/core_cm3.h | 57 +- src/modules/mathlib/CMSIS/Include/core_cm4.h | 57 +- .../mathlib/CMSIS/Include/core_cm4_simd.h | 54 +- .../mathlib/CMSIS/Include/core_cmFunc.h | 72 +- .../mathlib/CMSIS/Include/core_cmInstr.h | 134 +- .../mathlib/CMSIS/{module.mk => library.mk} | 34 +- src/modules/mathlib/CMSIS/license.txt | 27 + 267 files changed, 1071 insertions(+), 120792 deletions(-) delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/CommonTables/arm_common_tables.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_bitreversal.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c delete mode 100644 src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c create mode 100644 src/modules/mathlib/CMSIS/Include/arm_const_structs.h rename src/modules/mathlib/CMSIS/{module.mk => library.mk} (69%) create mode 100644 src/modules/mathlib/CMSIS/license.txt diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk index ae62b70347..1e4d592665 100644 --- a/makefiles/config_px4fmu_default.mk +++ b/makefiles/config_px4fmu_default.mk @@ -80,15 +80,19 @@ MODULES += modules/multirotor_pos_control MODULES += modules/sdlog # -# Libraries +# Library modules # MODULES += modules/systemlib MODULES += modules/systemlib/mixer MODULES += modules/mathlib -MODULES += modules/mathlib/CMSIS MODULES += modules/controllib MODULES += modules/uORB +# +# Libraries +# +LIBRARIES += modules/mathlib/CMSIS + # # Demo apps # diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c deleted file mode 100644 index 7070274da2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_f32.c +++ /dev/null @@ -1,159 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_abs_f32.c -* -* Description: Vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" -#include - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicAbs Vector Absolute Value - * - * Computes the absolute value of a vector on an element-by-element basis. - * - *
        
- *     pDst[n] = abs(pSrcA[n]),   0 <= n < blockSize.        
- * 
- * - * The operation can be done in-place by setting the input and output pointers to the same buffer. - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Floating-point vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_abs_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; /* temporary variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute and then store the results in the destination buffer. */ - /* read sample from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - - /* find absolute value */ - in1 = fabsf(in1); - - /* read sample from source */ - in4 = *(pSrc + 3); - - /* find absolute value */ - in2 = fabsf(in2); - - /* read sample from source */ - *pDst = in1; - - /* find absolute value */ - in3 = fabsf(in3); - - /* find absolute value */ - in4 = fabsf(in4); - - /* store result to destination */ - *(pDst + 1) = in2; - - /* store result to destination */ - *(pDst + 2) = in3; - - /* store result to destination */ - *(pDst + 3) = in4; - - - /* Update source pointer to process next sampels */ - pSrc += 4u; - - /* Update destination pointer to process next sampels */ - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute and then store the results in the destination buffer. */ - *pDst++ = fabsf(*pSrc++); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicAbs group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c deleted file mode 100644 index 6d6a4b6d80..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q15.c +++ /dev/null @@ -1,173 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q15.c -* -* Description: Q15 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Q15 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. - */ - -void arm_abs_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1; /* Input value1 */ - q15_t in2; /* Input value2 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read two inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - - - /* Store the Absolute result in the destination buffer by packing the two values, in a single cycle */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(((in1 > 0) ? in1 : __QSUB16(0, in1)), - ((in2 > 0) ? in2 : __QSUB16(0, in2)), 16); - -#else - - - *__SIMD32(pDst)++ = - __PKHBT(((in2 > 0) ? in2 : __QSUB16(0, in2)), - ((in1 > 0) ? in1 : __QSUB16(0, in1)), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(((in1 > 0) ? in1 : __QSUB16(0, in1)), - ((in2 > 0) ? in2 : __QSUB16(0, in2)), 16); - -#else - - - *__SIMD32(pDst)++ = - __PKHBT(((in2 > 0) ? in2 : __QSUB16(0, in2)), - ((in1 > 0) ? in1 : __QSUB16(0, in1)), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in1 = *pSrc++; - - /* Calculate absolute value of input and then store the result in the destination buffer. */ - *pDst++ = (in1 > 0) ? in1 : __QSUB16(0, in1); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* Temporary input variable */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in = *pSrc++; - - /* Calculate absolute value of input and then store the result in the destination buffer. */ - *pDst++ = (in > 0) ? in : ((in == (q15_t) 0x8000) ? 0x7fff : -in); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicAbs group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c deleted file mode 100644 index d9e3e7aa3c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q31.c +++ /dev/null @@ -1,125 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q31.c -* -* Description: Q31 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - - -/** - * @brief Q31 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. - */ - -void arm_abs_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - q31_t in; /* Input value */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute of input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - *pDst++ = (in1 > 0) ? in1 : __QSUB(0, in1); - *pDst++ = (in2 > 0) ? in2 : __QSUB(0, in2); - *pDst++ = (in3 > 0) ? in3 : __QSUB(0, in3); - *pDst++ = (in4 > 0) ? in4 : __QSUB(0, in4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Calculate absolute value of the input (if -1 then saturated to 0x7fffffff) and then store the results in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in > 0) ? in : ((in == 0x80000000) ? 0x7fffffff : -in); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of BasicAbs group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c deleted file mode 100644 index 258ecef2c8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_abs_q7.c +++ /dev/null @@ -1,152 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_abs_q7.c -* -* Description: Q7 vector absolute value. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAbs - * @{ - */ - -/** - * @brief Q7 vector absolute value. - * @param[in] *pSrc points to the input buffer - * @param[out] *pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - * @return none. - * - * \par Conditions for optimum performance - * Input and output buffers should be aligned by 32-bit - * - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. - */ - -void arm_abs_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - q7_t in; /* Input value1 */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; /* temporary input variables */ - q31_t out1, out2, out3, out4; /* temporary output variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read inputs */ - in1 = (q31_t) * pSrc; - in2 = (q31_t) * (pSrc + 1); - in3 = (q31_t) * (pSrc + 2); - - /* find absolute value */ - out1 = (in1 > 0) ? in1 : __QSUB8(0, in1); - - /* read input */ - in4 = (q31_t) * (pSrc + 3); - - /* find absolute value */ - out2 = (in2 > 0) ? in2 : __QSUB8(0, in2); - - /* store result to destination */ - *pDst = (q7_t) out1; - - /* find absolute value */ - out3 = (in3 > 0) ? in3 : __QSUB8(0, in3); - - /* find absolute value */ - out4 = (in4 > 0) ? in4 : __QSUB8(0, in4); - - /* store result to destination */ - *(pDst + 1) = (q7_t) out2; - - /* store result to destination */ - *(pDst + 2) = (q7_t) out3; - - /* store result to destination */ - *(pDst + 3) = (q7_t) out4; - - /* update pointers to process next samples */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; -#else - - /* Run the below code for Cortex-M0 */ - blkCnt = blockSize; - -#endif // #define ARM_MATH_CM0 - - while(blkCnt > 0u) - { - /* C = |A| */ - /* Read the input */ - in = *pSrc++; - - /* Store the Absolute result in the destination buffer */ - *pDst++ = (in > 0) ? in : ((in == (q7_t) 0x80) ? 0x7f : -in); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicAbs group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c deleted file mode 100644 index 0961dd1db3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_f32.c +++ /dev/null @@ -1,145 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_add_f32.c -* -* Description: Floating-point vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicAdd Vector Addition - * - * Element-by-element addition of two vectors. - * - *
        
- *     pDst[n] = pSrcA[n] + pSrcB[n],   0 <= n < blockSize.        
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Floating-point vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_add_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t inA1, inA2, inA3, inA4; /* temporary input variabels */ - float32_t inB1, inB2, inB3, inB4; /* temporary input variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - - /* read four inputs from sourceA and four inputs from sourceB */ - inA1 = *pSrcA; - inB1 = *pSrcB; - inA2 = *(pSrcA + 1); - inB2 = *(pSrcB + 1); - inA3 = *(pSrcA + 2); - inB3 = *(pSrcB + 2); - inA4 = *(pSrcA + 3); - inB4 = *(pSrcB + 3); - - /* C = A + B */ - /* add and store result to destination */ - *pDst = inA1 + inB1; - *(pDst + 1) = inA2 + inB2; - *(pDst + 2) = inA3 + inB3; - *(pDst + 3) = inA4 + inB4; - - /* update pointers to process next samples */ - pSrcA += 4u; - pSrcB += 4u; - pDst += 4u; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) + (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c deleted file mode 100644 index 788b2ebb2c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q15.c +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_add_q15.c -* -* Description: Q15 vector addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Q15 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_add_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inB1, inB2; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - inA1 = *__SIMD32(pSrcA)++; - inA2 = *__SIMD32(pSrcA)++; - inB1 = *__SIMD32(pSrcB)++; - inB2 = *__SIMD32(pSrcB)++; - - *__SIMD32(pDst)++ = __QADD16(inA1, inB1); - *__SIMD32(pDst)++ = __QADD16(inA2, inB2); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __QADD16(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ + *pSrcB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c deleted file mode 100644 index c5b18711d4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q31.c +++ /dev/null @@ -1,143 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_add_q31.c -* -* Description: Q31 vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - - -/** - * @brief Q31 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_add_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inA3, inA4; - q31_t inB1, inB2, inB3, inB4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - inA1 = *pSrcA++; - inA2 = *pSrcA++; - inB1 = *pSrcB++; - inB2 = *pSrcB++; - - inA3 = *pSrcA++; - inA4 = *pSrcA++; - inB3 = *pSrcB++; - inB4 = *pSrcB++; - - *pDst++ = __QADD(inA1, inB1); - *pDst++ = __QADD(inA2, inB2); - *pDst++ = __QADD(inA3, inB3); - *pDst++ = __QADD(inA4, inB4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = __QADD(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ + *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c deleted file mode 100644 index 5407c006fb..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_add_q7.c +++ /dev/null @@ -1,129 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_add_q7.c -* -* Description: Q7 vector addition. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicAdd - * @{ - */ - -/** - * @brief Q7 vector addition. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_add_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(*pSrcA++ + *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + B */ - /* Add and then store the results in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ + *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c deleted file mode 100644 index 6f7fbcebf2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_f32.c +++ /dev/null @@ -1,125 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_f32.c -* -* Description: Floating-point dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup dot_prod Vector Dot Product - * - * Computes the dot product of two vectors. - * The vectors are multiplied element-by-element and then summed. - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of floating-point vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - */ - - -void arm_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t blockSize, - float32_t * result) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer */ - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - sum += (*pSrcA++) * (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum += (*pSrcA++) * (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - /* Store the result back in the destination buffer */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c deleted file mode 100644 index 24611a05f5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q15.c +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q15.c -* -* Description: Q15 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q15 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.15 x 1.15 = 2.30 format and these - * results are added to a 64-bit accumulator in 34.30 format. - * Nonsaturating additions are used and given that there are 33 guard bits in the accumulator - * there is no risk of overflow. - * The return result is in 34.30 format. - */ - -void arm_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t blockSize, - q63_t * result) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); - sum = __SMLALD(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the results in a temporary buffer. */ - sum = __SMLALD(*pSrcA++, *pSrcB++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the results in a temporary buffer. */ - sum += (q63_t) ((q31_t) * pSrcA++ * *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the result in the destination buffer in 34.30 format */ - *result = sum; - -} - -/** - * @} end of dot_prod group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c deleted file mode 100644 index 5e4031338c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q31.c +++ /dev/null @@ -1,138 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q31.c -* -* Description: Q31 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q31 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.31 x 1.31 = 2.62 format and these - * are truncated to 2.48 format by discarding the lower 14 bits. - * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. - * There are 15 guard bits in the accumulator and there is no risk of overflow as long as - * the length of the vectors is less than 2^16 elements. - * The return result is in 16.48 format. - */ - -void arm_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t blockSize, - q63_t * result) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inA3, inA4; - q31_t inB1, inB2, inB3, inB4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - inA1 = *pSrcA++; - inA2 = *pSrcA++; - inA3 = *pSrcA++; - inA4 = *pSrcA++; - inB1 = *pSrcB++; - inB2 = *pSrcB++; - inB3 = *pSrcB++; - inB4 = *pSrcB++; - - sum += ((q63_t) inA1 * inB1) >> 14u; - sum += ((q63_t) inA2 * inB2) >> 14u; - sum += ((q63_t) inA3 * inB3) >> 14u; - sum += ((q63_t) inA4 * inB4) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Calculate dot product and then store the result in a temporary buffer. */ - sum += ((q63_t) * pSrcA++ * *pSrcB++) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result in the destination buffer in 16.48 format */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c deleted file mode 100644 index ddf2d0c243..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_dot_prod_q7.c +++ /dev/null @@ -1,154 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dot_prod_q7.c -* -* Description: Q7 dot product. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup dot_prod - * @{ - */ - -/** - * @brief Dot product of Q7 vectors. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] *result output result returned here - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The intermediate multiplications are in 1.7 x 1.7 = 2.14 format and these - * results are added to an accumulator in 18.14 format. - * Nonsaturating additions are used and there is no danger of wrap around as long as - * the vectors are less than 2^18 elements long. - * The return result is in 18.14 format. - */ - -void arm_dot_prod_q7( - q7_t * pSrcA, - q7_t * pSrcB, - uint32_t blockSize, - q31_t * result) -{ - uint32_t blkCnt; /* loop counter */ - - q31_t sum = 0; /* Temporary variables to store output */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t input1, input2; /* Temporary variables to store input */ - q31_t inA1, inA2, inB1, inB2; /* Temporary variables to store input */ - - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* read 4 samples at a time from sourceA */ - input1 = *__SIMD32(pSrcA)++; - /* read 4 samples at a time from sourceB */ - input2 = *__SIMD32(pSrcB)++; - - /* extract two q7_t samples to q15_t samples */ - inA1 = __SXTB16(__ROR(input1, 8)); - /* extract reminaing two samples */ - inA2 = __SXTB16(input1); - /* extract two q7_t samples to q15_t samples */ - inB1 = __SXTB16(__ROR(input2, 8)); - /* extract reminaing two samples */ - inB2 = __SXTB16(input2); - - /* multiply and accumulate two samples at a time */ - sum = __SMLAD(inA1, inB1, sum); - sum = __SMLAD(inA2, inB2, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Dot product and then store the results in a temporary buffer. */ - sum = __SMLAD(*pSrcA++, *pSrcB++, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0]* B[0] + A[1]* B[1] + A[2]* B[2] + .....+ A[blockSize-1]* B[blockSize-1] */ - /* Dot product and then store the results in a temporary buffer. */ - sum += (q31_t) ((q15_t) * pSrcA++ * *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /* Store the result in the destination buffer in 18.14 format */ - *result = sum; -} - -/** - * @} end of dot_prod group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c deleted file mode 100644 index 88a458b40a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_f32.c +++ /dev/null @@ -1,172 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mult_f32.c -* -* Description: Floating-point vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicMult Vector Multiplication - * - * Element-by-element multiplication of two vectors. - * - *
        
- *     pDst[n] = pSrcA[n] * pSrcB[n],   0 <= n < blockSize.        
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Floating-point vector multiplication. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_mult_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t inA1, inA2, inA3, inA4; /* temporary input variables */ - float32_t inB1, inB2, inB3, inB4; /* temporary input variables */ - float32_t out1, out2, out3, out4; /* temporary output variables */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in output buffer */ - /* read sample from sourceA */ - inA1 = *pSrcA; - /* read sample from sourceB */ - inB1 = *pSrcB; - /* read sample from sourceA */ - inA2 = *(pSrcA + 1); - /* read sample from sourceB */ - inB2 = *(pSrcB + 1); - - /* out = sourceA * sourceB */ - out1 = inA1 * inB1; - - /* read sample from sourceA */ - inA3 = *(pSrcA + 2); - /* read sample from sourceB */ - inB3 = *(pSrcB + 2); - - /* out = sourceA * sourceB */ - out2 = inA2 * inB2; - - /* read sample from sourceA */ - inA4 = *(pSrcA + 3); - - /* store result to destination buffer */ - *pDst = out1; - - /* read sample from sourceB */ - inB4 = *(pSrcB + 3); - - /* out = sourceA * sourceB */ - out3 = inA3 * inB3; - - /* store result to destination buffer */ - *(pDst + 1) = out2; - - /* out = sourceA * sourceB */ - out4 = inA4 * inB4; - /* store result to destination buffer */ - *(pDst + 2) = out3; - /* store result to destination buffer */ - *(pDst + 3) = out4; - - - /* update pointers to process next samples */ - pSrcA += 4u; - pSrcB += 4u; - pDst += 4u; - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in output buffer */ - *pDst++ = (*pSrcA++) * (*pSrcB++); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c deleted file mode 100644 index 99d44a4ba3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q15.c +++ /dev/null @@ -1,152 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q15.c -* -* Description: Q15 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - - -/** - * @brief Q15 vector multiplication - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_mult_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inB1, inB2; /* temporary input variables */ - q15_t out1, out2, out3, out4; /* temporary output variables */ - q31_t mul1, mul2, mul3, mul4; /* temporary variables */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* read two samples at a time from sourceA */ - inA1 = *__SIMD32(pSrcA)++; - /* read two samples at a time from sourceB */ - inB1 = *__SIMD32(pSrcB)++; - /* read two samples at a time from sourceA */ - inA2 = *__SIMD32(pSrcA)++; - /* read two samples at a time from sourceB */ - inB2 = *__SIMD32(pSrcB)++; - - /* multiply mul = sourceA * sourceB */ - mul1 = (q31_t) ((q15_t) (inA1 >> 16) * (q15_t) (inB1 >> 16)); - mul2 = (q31_t) ((q15_t) inA1 * (q15_t) inB1); - mul3 = (q31_t) ((q15_t) (inA2 >> 16) * (q15_t) (inB2 >> 16)); - mul4 = (q31_t) ((q15_t) inA2 * (q15_t) inB2); - - /* saturate result to 16 bit */ - out1 = (q15_t) __SSAT(mul1 >> 15, 16); - out2 = (q15_t) __SSAT(mul2 >> 15, 16); - out3 = (q15_t) __SSAT(mul3 >> 15, 16); - out4 = (q15_t) __SSAT(mul4 >> 15, 16); - - /* store the result */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(out2, out1, 16); - *__SIMD32(pDst)++ = __PKHBT(out4, out3, 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(out2, out1, 16); - *__SIMD32(pDst)++ = __PKHBT(out4, out3, 16); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the result in the destination buffer */ - *pDst++ = (q15_t) __SSAT((((q31_t) (*pSrcA++) * (*pSrcB++)) >> 15), 16); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c deleted file mode 100644 index 37ec8e25e1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q31.c +++ /dev/null @@ -1,143 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q31.c -* -* Description: Q31 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Q31 vector multiplication. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_mult_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inA3, inA4; /* temporary input variables */ - q31_t inB1, inB2, inB3, inB4; /* temporary input variables */ - q31_t out1, out2, out3, out4; /* temporary output variables */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and then store the results in the destination buffer. */ - inA1 = *pSrcA++; - inA2 = *pSrcA++; - inA3 = *pSrcA++; - inA4 = *pSrcA++; - inB1 = *pSrcB++; - inB2 = *pSrcB++; - inB3 = *pSrcB++; - inB4 = *pSrcB++; - - out1 = ((q63_t) inA1 * inB1) >> 32; - out2 = ((q63_t) inA2 * inB2) >> 32; - out3 = ((q63_t) inA3 * inB3) >> 32; - out4 = ((q63_t) inA4 * inB4) >> 32; - - out1 = __SSAT(out1, 31); - out2 = __SSAT(out2, 31); - out3 = __SSAT(out3, 31); - out4 = __SSAT(out4, 31); - - *pDst++ = out1 << 1u; - *pDst++ = out2 << 1u; - *pDst++ = out3 << 1u; - *pDst++ = out4 << 1u; - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and then store the results in the destination buffer. */ - *pDst++ = - (q31_t) clip_q63_to_q31(((q63_t) (*pSrcA++) * (*pSrcB++)) >> 31); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c deleted file mode 100644 index 14ee23ea6a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_mult_q7.c +++ /dev/null @@ -1,128 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mult_q7.c -* -* Description: Q7 vector multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 DP -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicMult - * @{ - */ - -/** - * @brief Q7 vector multiplication - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_mult_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counters */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t out1, out2, out3, out4; /* Temporary variables to store the product */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the results in temporary variables */ - out1 = (q7_t) __SSAT((((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7), 8); - out2 = (q7_t) __SSAT((((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7), 8); - out3 = (q7_t) __SSAT((((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7), 8); - out4 = (q7_t) __SSAT((((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7), 8); - - /* Store the results of 4 inputs in the destination buffer in single cycle by packing */ - *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A * B */ - /* Multiply the inputs and store the result in the destination buffer */ - *pDst++ = (q7_t) __SSAT((((q15_t) (*pSrcA++) * (*pSrcB++)) >> 7), 8); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c deleted file mode 100644 index 4f4d423ac9..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_f32.c +++ /dev/null @@ -1,137 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_negate_f32.c -* -* Description: Negates floating-point vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup negate Vector Negate - * - * Negates the elements of a vector. - * - *
        
- *     pDst[n] = -pSrc[n],   0 <= n < blockSize.        
- * 
- */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - -void arm_negate_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; /* temporary variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* read inputs from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - /* negate the input */ - in1 = -in1; - in2 = -in2; - in3 = -in3; - in4 = -in4; - - /* store the result to destination */ - *pDst = in1; - *(pDst + 1) = in2; - *(pDst + 2) = in3; - *(pDst + 3) = in4; - - /* update pointers to process next samples */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - *pDst++ = -*pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c deleted file mode 100644 index 21d58d1a4a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q15.c +++ /dev/null @@ -1,137 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q15.c -* -* Description: Negates Q15 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * \par Conditions for optimum performance - * Input and output buffers should be aligned by 32-bit - * - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF. - */ - -void arm_negate_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - q15_t in; - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Read two inputs at a time */ - in1 = _SIMD32_OFFSET(pSrc); - in2 = _SIMD32_OFFSET(pSrc + 2); - - /* negate two samples at a time */ - in1 = __QSUB16(0, in1); - - /* negate two samples at a time */ - in2 = __QSUB16(0, in2); - - /* store the result to destination 2 samples at a time */ - _SIMD32_OFFSET(pDst) = in1; - /* store the result to destination 2 samples at a time */ - _SIMD32_OFFSET(pDst + 2) = in2; - - - /* update pointers to process next samples */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the result in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in == (q15_t) 0x8000) ? 0x7fff : -in; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c deleted file mode 100644 index fc28c36218..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q31.c +++ /dev/null @@ -1,124 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q31.c -* -* Description: Negates Q31 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF. - */ - -void arm_negate_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t in; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - *pDst++ = __QSUB(0, in1); - *pDst++ = __QSUB(0, in2); - *pDst++ = __QSUB(0, in3); - *pDst++ = __QSUB(0, in4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the result in the destination buffer. */ - in = *pSrc++; - *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c deleted file mode 100644 index 601fb73934..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_negate_q7.c +++ /dev/null @@ -1,120 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_negate_q7.c -* -* Description: Negates Q7 vectors. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup negate - * @{ - */ - -/** - * @brief Negates the elements of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * The Q7 value -1 (0x80) will be saturated to the maximum allowable positive value 0x7F. - */ - -void arm_negate_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - q7_t in; - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t input; /* Input values1-4 */ - q31_t zero = 0x00000000; - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = -A */ - /* Read four inputs */ - input = *__SIMD32(pSrc)++; - - /* Store the Negated results in the destination buffer in a single cycle by packing the results */ - *__SIMD32(pDst)++ = __QSUB8(zero, input); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = -A */ - /* Negate and then store the results in the destination buffer. */ \ - in = *pSrc++; - *pDst++ = (in == (q7_t) 0x80) ? 0x7f : -in; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of negate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c deleted file mode 100644 index 4bdf06ee8d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_f32.c +++ /dev/null @@ -1,158 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_offset_f32.c -* -* Description: Floating-point vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup offset Vector Offset - * - * Adds a constant offset to each element of a vector. - * - *
        
- *     pDst[n] = pSrc[n] + offset,   0 <= n < blockSize.        
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - - -void arm_offset_f32( - float32_t * pSrc, - float32_t offset, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - /* read samples from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - - /* add offset to input */ - in1 = in1 + offset; - - /* read samples from source */ - in3 = *(pSrc + 2); - - /* add offset to input */ - in2 = in2 + offset; - - /* read samples from source */ - in4 = *(pSrc + 3); - - /* add offset to input */ - in3 = in3 + offset; - - /* store result to destination */ - *pDst = in1; - - /* add offset to input */ - in4 = in4 + offset; - - /* store result to destination */ - *(pDst + 1) = in2; - - /* store result to destination */ - *(pDst + 2) = in3; - - /* store result to destination */ - *(pDst + 3) = in4; - - /* update pointers to process next samples */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++) + offset; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of offset group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c deleted file mode 100644 index f8158f066f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q15.c +++ /dev/null @@ -1,131 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q15.c -* -* Description: Q15 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] are saturated. - */ - -void arm_offset_q15( - q15_t * pSrc, - q15_t offset, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t offset_packed; /* Offset packed to 32 bit */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Offset is packed to 32 bit in order to use SIMD32 for addition */ - offset_packed = __PKHBT(offset, offset, 16); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer, 2 samples at a time. */ - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); - *__SIMD32(pDst)++ = __QADD16(*__SIMD32(pSrc)++, offset_packed); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __QADD16(*pSrc++, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrc++ + offset), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c deleted file mode 100644 index 8b03ee3727..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q31.c +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q31.c -* -* Description: Q31 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] are saturated. - */ - -void arm_offset_q31( - q31_t * pSrc, - q31_t offset, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination buffer. */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - *pDst++ = __QADD(in1, offset); - *pDst++ = __QADD(in2, offset); - *pDst++ = __QADD(in3, offset); - *pDst++ = __QADD(in4, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = __QADD(*pSrc++, offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrc++ + offset); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c deleted file mode 100644 index 56643816f3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_offset_q7.c +++ /dev/null @@ -1,130 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_offset_q7.c -* -* Description: Q7 vector offset. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup offset - * @{ - */ - -/** - * @brief Adds a constant offset to a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] are saturated. - */ - -void arm_offset_q7( - q7_t * pSrc, - q7_t offset, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t offset_packed; /* Offset packed to 32 bit */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Offset is packed to 32 bit in order to use SIMD32 for addition */ - offset_packed = __PACKq7(offset, offset, offset, offset); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the results in the destination bufferfor 4 samples at a time. */ - *__SIMD32(pDst)++ = __QADD8(*__SIMD32(pSrc)++, offset_packed); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(*pSrc++ + offset, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A + offset */ - /* Add offset and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrc++ + offset, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of offset group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c deleted file mode 100644 index b77144a3ef..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_f32.c +++ /dev/null @@ -1,161 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_scale_f32.c -* -* Description: Multiplies a floating-point vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup scale Vector Scale - * - * Multiply a vector by a scalar value. For floating-point data, the algorithm used is: - * - *
        
- *     pDst[n] = pSrc[n] * scale,   0 <= n < blockSize.        
- * 
- * - * In the fixed-point Q7, Q15, and Q31 functions, scale is represented by - * a fractional multiplication scaleFract and an arithmetic shift shift. - * The shift allows the gain of the scaling operation to exceed 1.0. - * The algorithm used with fixed-point data is: - * - *
        
- *     pDst[n] = (pSrc[n] * scaleFract) << shift,   0 <= n < blockSize.        
- * 
- * - * The overall scale factor applied to the fixed-point data is - *
        
- *     scale = scaleFract * 2^shift.        
- * 
- */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a floating-point vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scale scale factor to be applied - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - */ - - -void arm_scale_f32( - float32_t * pSrc, - float32_t scale, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; /* temporary variabels */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the results in the destination buffer. */ - /* read input samples from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - - /* multiply with scaling factor */ - in1 = in1 * scale; - - /* read input sample from source */ - in3 = *(pSrc + 2); - - /* multiply with scaling factor */ - in2 = in2 * scale; - - /* read input sample from source */ - in4 = *(pSrc + 3); - - /* multiply with scaling factor */ - in3 = in3 * scale; - in4 = in4 * scale; - /* store the result to destination */ - *pDst = in1; - *(pDst + 1) = in2; - *(pDst + 2) = in3; - *(pDst + 3) = in4; - - /* update pointers to process next samples */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++) * scale; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of scale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c deleted file mode 100644 index 9e79202fe3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q15.c +++ /dev/null @@ -1,157 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q15.c -* -* Description: Multiplies a Q15 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q15 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.15 format. - * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. - */ - - -void arm_scale_q15( - q15_t * pSrc, - q15_t scaleFract, - int8_t shift, - q15_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = 15 - shift; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q15_t in1, in2, in3, in4; - q31_t inA1, inA2; /* Temporary variables */ - q31_t out1, out2, out3, out4; - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading 2 inputs from memory */ - inA1 = *__SIMD32(pSrc)++; - inA2 = *__SIMD32(pSrc)++; - - /* C = A * scale */ - /* Scale the inputs and then store the 2 results in the destination buffer - * in single cycle by packing the outputs */ - out1 = (q31_t) ((q15_t) (inA1 >> 16) * scaleFract); - out2 = (q31_t) ((q15_t) inA1 * scaleFract); - out3 = (q31_t) ((q15_t) (inA2 >> 16) * scaleFract); - out4 = (q31_t) ((q15_t) inA2 * scaleFract); - - /* apply shifting */ - out1 = out1 >> kShift; - out2 = out2 >> kShift; - out3 = out3 >> kShift; - out4 = out4 >> kShift; - - /* saturate the output */ - in1 = (q15_t) (__SSAT(out1, 16)); - in2 = (q15_t) (__SSAT(out2, 16)); - in3 = (q15_t) (__SSAT(out3, 16)); - in4 = (q15_t) (__SSAT(out4, 16)); - - /* store the result to destination */ - *__SIMD32(pDst)++ = __PKHBT(in2, in1, 16); - *__SIMD32(pDst)++ = __PKHBT(in4, in3, 16); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT(((q31_t) * pSrc++ * scaleFract) >> kShift, 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of scale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c deleted file mode 100644 index 8e9b50e72f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q31.c +++ /dev/null @@ -1,221 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q31.c -* -* Description: Multiplies a Q31 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q31 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.31 format. - * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. - */ - -void arm_scale_q31( - q31_t * pSrc, - q31_t scaleFract, - int8_t shift, - q31_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = shift + 1; /* Shift to apply after scaling */ - int8_t sign = (kShift & 0x80); - uint32_t blkCnt; /* loop counter */ - q31_t in, out; - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in1, in2, in3, in4; /* temporary input variables */ - q31_t out1, out2, out3, out4; /* temporary output variabels */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* read four inputs from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - /* multiply input with scaler value */ - in1 = ((q63_t) in1 * scaleFract) >> 32; - in2 = ((q63_t) in2 * scaleFract) >> 32; - in3 = ((q63_t) in3 * scaleFract) >> 32; - in4 = ((q63_t) in4 * scaleFract) >> 32; - - /* apply shifting */ - out1 = in1 << kShift; - out2 = in2 << kShift; - - /* saturate the results. */ - if(in1 != (out1 >> kShift)) - out1 = 0x7FFFFFFF ^ (in1 >> 31); - - if(in2 != (out2 >> kShift)) - out2 = 0x7FFFFFFF ^ (in2 >> 31); - - out3 = in3 << kShift; - out4 = in4 << kShift; - - *pDst = out1; - *(pDst + 1) = out2; - - if(in3 != (out3 >> kShift)) - out3 = 0x7FFFFFFF ^ (in3 >> 31); - - if(in4 != (out4 >> kShift)) - out4 = 0x7FFFFFFF ^ (in4 >> 31); - - /* Store result destination */ - *(pDst + 2) = out3; - *(pDst + 3) = out4; - - /* Update pointers to process next sampels */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - } - else - { - kShift = -kShift; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* read four inputs from source */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - /* multiply input with scaler value */ - in1 = ((q63_t) in1 * scaleFract) >> 32; - in2 = ((q63_t) in2 * scaleFract) >> 32; - in3 = ((q63_t) in3 * scaleFract) >> 32; - in4 = ((q63_t) in4 * scaleFract) >> 32; - - /* apply shifting */ - out1 = in1 >> kShift; - out2 = in2 >> kShift; - - out3 = in3 >> kShift; - out4 = in4 >> kShift; - - /* Store result destination */ - *pDst = out1; - *(pDst + 1) = out2; - - *(pDst + 2) = out3; - *(pDst + 3) = out4; - - /* Update pointers to process next sampels */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - } - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - in = *pSrc++; - in = ((q63_t) in * scaleFract) >> 32; - - if(sign == 0) - { - out = in << kShift; - if(in != (out >> kShift)) - out = 0x7FFFFFFF ^ (in >> 31); - } - else - { - out = in >> kShift; - } - - *pDst++ = out; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of scale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c deleted file mode 100644 index 76c35e6561..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_scale_q7.c +++ /dev/null @@ -1,144 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_scale_q7.c -* -* Description: Multiplies a Q7 vector by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup scale - * @{ - */ - -/** - * @brief Multiplies a Q7 vector by a scalar. - * @param[in] *pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.7 format. - * These are multiplied to yield a 2.14 intermediate result and this is shifted with saturation to 1.7 format. - */ - -void arm_scale_q7( - q7_t * pSrc, - q7_t scaleFract, - int8_t shift, - q7_t * pDst, - uint32_t blockSize) -{ - int8_t kShift = 7 - shift; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1, in2, in3, in4, out1, out2, out3, out4; /* Temporary variables to store input & output */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading 4 inputs from memory */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - /* C = A * scale */ - /* Scale the inputs and then store the results in the temporary variables. */ - out1 = (q7_t) (__SSAT(((in1) * scaleFract) >> kShift, 8)); - out2 = (q7_t) (__SSAT(((in2) * scaleFract) >> kShift, 8)); - out3 = (q7_t) (__SSAT(((in3) * scaleFract) >> kShift, 8)); - out4 = (q7_t) (__SSAT(((in4) * scaleFract) >> kShift, 8)); - - /* Packing the individual outputs into 32bit and storing in - * destination buffer in single write */ - *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) (__SSAT(((*pSrc++) * scaleFract) >> kShift, 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A * scale */ - /* Scale the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) (__SSAT((((q15_t) * pSrc++ * scaleFract) >> kShift), 8)); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of scale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c deleted file mode 100644 index b8301e63d8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q15.c +++ /dev/null @@ -1,243 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q15.c -* -* Description: Shifts the elements of a Q15 vector by a specified number of bits. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup shift - * @{ - */ - -/** - * @brief Shifts the elements of a Q15 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_shift_q15( - q15_t * pSrc, - int8_t shiftBits, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign; /* Sign of shiftBits */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t in1, in2; /* Temporary variables */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read 2 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - /* C = A << shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), - __SSAT((in2 << shiftBits), 16), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), - __SSAT((in1 << shiftBits), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in1 << shiftBits), 16), - __SSAT((in2 << shiftBits), 16), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(__SSAT((in2 << shiftBits), 16), - __SSAT((in1 << shiftBits), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift and then store the results in the destination buffer. */ - *pDst++ = __SSAT((*pSrc++ << shiftBits), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read 2 inputs */ - in1 = *pSrc++; - in2 = *pSrc++; - - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), - (in2 >> -shiftBits), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), - (in1 >> -shiftBits), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pSrc++; - in2 = *pSrc++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT((in1 >> -shiftBits), - (in2 >> -shiftBits), 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT((in2 >> -shiftBits), - (in1 >> -shiftBits), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift and then store the results in the destination buffer. */ - *pDst++ = __SSAT(((q31_t) * pSrc++ << shiftBits), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the inputs and then store the results in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of shift group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c deleted file mode 100644 index 561225a899..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q31.c +++ /dev/null @@ -1,195 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q31.c -* -* Description: Shifts the elements of a Q31 vector by a specified number of bits. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ -/** - * @defgroup shift Vector Shift - * - * Shifts the elements of a fixed-point vector by a specified number of bits. - * There are separate functions for Q7, Q15, and Q31 data types. - * The underlying algorithm used is: - * - *
        
- *     pDst[n] = pSrc[n] << shift,   0 <= n < blockSize.        
- * 
- * - * If shift is positive then the elements of the vector are shifted to the left. - * If shift is negative then the elements of the vector are shifted to the right. - */ - -/** - * @addtogroup shift - * @{ - */ - -/** - * @brief Shifts the elements of a Q31 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_shift_q31( - q31_t * pSrc, - int8_t shiftBits, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign = (shiftBits & 0x80); /* Sign of shiftBits */ - -#ifndef ARM_MATH_CM0 - - q31_t in1, in2, in3, in4; /* Temporary input variables */ - q31_t out1, out2, out3, out4; /* Temporary output variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift the input and then store the results in the destination buffer. */ - in1 = *pSrc; - in2 = *(pSrc + 1); - out1 = in1 << shiftBits; - in3 = *(pSrc + 2); - out2 = in2 << shiftBits; - in4 = *(pSrc + 3); - if(in1 != (out1 >> shiftBits)) - out1 = 0x7FFFFFFF ^ (in1 >> 31); - - if(in2 != (out2 >> shiftBits)) - out2 = 0x7FFFFFFF ^ (in2 >> 31); - - *pDst = out1; - out3 = in3 << shiftBits; - *(pDst + 1) = out2; - out4 = in4 << shiftBits; - - if(in3 != (out3 >> shiftBits)) - out3 = 0x7FFFFFFF ^ (in3 >> 31); - - if(in4 != (out4 >> shiftBits)) - out4 = 0x7FFFFFFF ^ (in4 >> 31); - - *(pDst + 2) = out3; - *(pDst + 3) = out4; - - /* Update destination pointer to process next sampels */ - pSrc += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the input and then store the results in the destination buffer. */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - *pDst = (in1 >> -shiftBits); - *(pDst + 1) = (in2 >> -shiftBits); - *(pDst + 2) = (in3 >> -shiftBits); - *(pDst + 3) = (in4 >> -shiftBits); - - - pSrc += 4u; - pDst += 4u; - - blkCnt--; - } - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A (>> or <<) shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (sign == 0u) ? clip_q63_to_q31((q63_t) * pSrc++ << shiftBits) : - (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - - -} - -/** - * @} end of shift group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c deleted file mode 100644 index 6dfd25f650..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_shift_q7.c +++ /dev/null @@ -1,215 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_shift_q7.c -* -* Description: Processing function for the Q7 Shifting -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup shift - * @{ - */ - - -/** - * @brief Shifts the elements of a Q7 vector a specified number of bits. - * @param[in] *pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in the vector - * @return none. - * - * \par Conditions for optimum performance - * Input and output buffers should be aligned by 32-bit - * - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x8 0x7F] will be saturated. - */ - -void arm_shift_q7( - q7_t * pSrc, - int8_t shiftBits, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - uint8_t sign; /* Sign of shiftBits */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q7_t in1; /* Input value1 */ - q7_t in2; /* Input value2 */ - q7_t in3; /* Input value3 */ - q7_t in4; /* Input value4 */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Read 4 inputs */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ - *__SIMD32(pDst)++ = __PACKq7(__SSAT((in1 << shiftBits), 8), - __SSAT((in2 << shiftBits), 8), - __SSAT((in3 << shiftBits), 8), - __SSAT((in4 << shiftBits), 8)); - /* Update source pointer to process next sampels */ - pSrc += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((*pSrc++ << shiftBits), 8); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - shiftBits = -shiftBits; - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Read 4 inputs */ - in1 = *pSrc; - in2 = *(pSrc + 1); - in3 = *(pSrc + 2); - in4 = *(pSrc + 3); - - /* Store the Shifted result in the destination buffer in single cycle by packing the outputs */ - *__SIMD32(pDst)++ = __PACKq7((in1 >> shiftBits), (in2 >> shiftBits), - (in3 >> shiftBits), (in4 >> shiftBits)); - - - pSrc += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - in1 = *pSrc++; - *pDst++ = (in1 >> shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Getting the sign of shiftBits */ - sign = (shiftBits & 0x80); - - /* If the shift value is positive then do right shift else left shift */ - if(sign == 0u) - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A << shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT(((q15_t) * pSrc++ << shiftBits), 8); - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A >> shiftBits */ - /* Shift the input and then store the result in the destination buffer. */ - *pDst++ = (*pSrc++ >> -shiftBits); - - /* Decrement the loop counter */ - blkCnt--; - } - } - -#endif /* #ifndef ARM_MATH_CM0 */ -} - -/** - * @} end of shift group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c deleted file mode 100644 index 4a660db49b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_f32.c +++ /dev/null @@ -1,145 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sub_f32.c -* -* Description: Floating-point vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @defgroup BasicSub Vector Subtraction - * - * Element-by-element subtraction of two vectors. - * - *
        
- *     pDst[n] = pSrcA[n] - pSrcB[n],   0 <= n < blockSize.        
- * 
- * - * There are separate functions for floating-point, Q7, Q15, and Q31 data types. - */ - -/** - * @addtogroup BasicSub - * @{ - */ - - -/** - * @brief Floating-point vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - */ - -void arm_sub_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t inA1, inA2, inA3, inA4; /* temporary variables */ - float32_t inB1, inB2, inB3, inB4; /* temporary variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - /* Read 4 input samples from sourceA and sourceB */ - inA1 = *pSrcA; - inB1 = *pSrcB; - inA2 = *(pSrcA + 1); - inB2 = *(pSrcB + 1); - inA3 = *(pSrcA + 2); - inB3 = *(pSrcB + 2); - inA4 = *(pSrcA + 3); - inB4 = *(pSrcB + 3); - - /* dst = srcA - srcB */ - /* subtract and store the result */ - *pDst = inA1 - inB1; - *(pDst + 1) = inA2 - inB2; - *(pDst + 2) = inA3 - inB3; - *(pDst + 3) = inA4 - inB4; - - - /* Update pointers to process next sampels */ - pSrcA += 4u; - pSrcB += 4u; - pDst += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - *pDst++ = (*pSrcA++) - (*pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c deleted file mode 100644 index d8cc12220a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q15.c +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q15.c -* -* Description: Q15 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q15 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -void arm_sub_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2; - q31_t inB1, inB2; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer two samples at a time. */ - inA1 = *__SIMD32(pSrcA)++; - inA2 = *__SIMD32(pSrcA)++; - inB1 = *__SIMD32(pSrcB)++; - inB2 = *__SIMD32(pSrcB)++; - - *__SIMD32(pDst)++ = __QSUB16(inA1, inB1); - *__SIMD32(pDst)++ = __QSUB16(inA2, inB2); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q15_t) __QSUB16(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q15_t) __SSAT(((q31_t) * pSrcA++ - *pSrcB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c deleted file mode 100644 index 34642f32e7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q31.c +++ /dev/null @@ -1,141 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q31.c -* -* Description: Q31 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q31 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -void arm_sub_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t inA1, inA2, inA3, inA4; - q31_t inB1, inB2, inB3, inB4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer. */ - inA1 = *pSrcA++; - inA2 = *pSrcA++; - inB1 = *pSrcB++; - inB2 = *pSrcB++; - - inA3 = *pSrcA++; - inA4 = *pSrcA++; - inB3 = *pSrcB++; - inB4 = *pSrcB++; - - *pDst++ = __QSUB(inA1, inB1); - *pDst++ = __QSUB(inA2, inB2); - *pDst++ = __QSUB(inA3, inB3); - *pDst++ = __QSUB(inA4, inB4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = __QSUB(*pSrcA++, *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q31_t) clip_q63_to_q31((q63_t) * pSrcA++ - *pSrcB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of BasicSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c deleted file mode 100644 index adbc7d0c08..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/BasicMathFunctions/arm_sub_q7.c +++ /dev/null @@ -1,126 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sub_q7.c -* -* Description: Q7 vector subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMath - */ - -/** - * @addtogroup BasicSub - * @{ - */ - -/** - * @brief Q7 vector subtraction. - * @param[in] *pSrcA points to the first input vector - * @param[in] *pSrcB points to the second input vector - * @param[out] *pDst points to the output vector - * @param[in] blockSize number of samples in each vector - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - */ - -void arm_sub_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the results in the destination buffer 4 samples at a time. */ - *__SIMD32(pDst)++ = __QSUB8(*__SIMD32(pSrcA)++, *__SIMD32(pSrcB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = __SSAT(*pSrcA++ - *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A - B */ - /* Subtract and then store the result in the destination buffer. */ - *pDst++ = (q7_t) __SSAT((q15_t) * pSrcA++ - *pSrcB++, 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of BasicSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/CommonTables/arm_common_tables.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/CommonTables/arm_common_tables.c deleted file mode 100644 index bf7ab3bed7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/CommonTables/arm_common_tables.c +++ /dev/null @@ -1,4689 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_common_tables.c -* -* Description: This file has common tables like fft twiddle factors, Bitreverse, reciprocal etc which are used across different functions -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup CFFT_CIFFT Complex FFT Tables - * @{ - */ - -/** -* \par -* Pseudo code for Generation of Bit reversal Table is -* \par -*
for(l=1;l <= N/4;l++)    
-* {    
-*   for(i=0;i> 1;    
-*  } 
-* \par -* where N = 4096 logN2 = 12 -* \par -* N is the maximum FFT Size supported -*/ - -/* -* @brief Table for bit reversal process -*/ -const uint16_t armBitRevTable[1024] = { - 0x400, 0x200, 0x600, 0x100, 0x500, 0x300, 0x700, - 0x80, 0x480, 0x280, 0x680, 0x180, 0x580, 0x380, - 0x780, 0x40, 0x440, 0x240, 0x640, 0x140, 0x540, - 0x340, 0x740, 0xc0, 0x4c0, 0x2c0, 0x6c0, 0x1c0, - 0x5c0, 0x3c0, 0x7c0, 0x20, 0x420, 0x220, 0x620, - 0x120, 0x520, 0x320, 0x720, 0xa0, 0x4a0, 0x2a0, - 0x6a0, 0x1a0, 0x5a0, 0x3a0, 0x7a0, 0x60, 0x460, - 0x260, 0x660, 0x160, 0x560, 0x360, 0x760, 0xe0, - 0x4e0, 0x2e0, 0x6e0, 0x1e0, 0x5e0, 0x3e0, 0x7e0, - 0x10, 0x410, 0x210, 0x610, 0x110, 0x510, 0x310, - 0x710, 0x90, 0x490, 0x290, 0x690, 0x190, 0x590, - 0x390, 0x790, 0x50, 0x450, 0x250, 0x650, 0x150, - 0x550, 0x350, 0x750, 0xd0, 0x4d0, 0x2d0, 0x6d0, - 0x1d0, 0x5d0, 0x3d0, 0x7d0, 0x30, 0x430, 0x230, - 0x630, 0x130, 0x530, 0x330, 0x730, 0xb0, 0x4b0, - 0x2b0, 0x6b0, 0x1b0, 0x5b0, 0x3b0, 0x7b0, 0x70, - 0x470, 0x270, 0x670, 0x170, 0x570, 0x370, 0x770, - 0xf0, 0x4f0, 0x2f0, 0x6f0, 0x1f0, 0x5f0, 0x3f0, - 0x7f0, 0x8, 0x408, 0x208, 0x608, 0x108, 0x508, - 0x308, 0x708, 0x88, 0x488, 0x288, 0x688, 0x188, - 0x588, 0x388, 0x788, 0x48, 0x448, 0x248, 0x648, - 0x148, 0x548, 0x348, 0x748, 0xc8, 0x4c8, 0x2c8, - 0x6c8, 0x1c8, 0x5c8, 0x3c8, 0x7c8, 0x28, 0x428, - 0x228, 0x628, 0x128, 0x528, 0x328, 0x728, 0xa8, - 0x4a8, 0x2a8, 0x6a8, 0x1a8, 0x5a8, 0x3a8, 0x7a8, - 0x68, 0x468, 0x268, 0x668, 0x168, 0x568, 0x368, - 0x768, 0xe8, 0x4e8, 0x2e8, 0x6e8, 0x1e8, 0x5e8, - 0x3e8, 0x7e8, 0x18, 0x418, 0x218, 0x618, 0x118, - 0x518, 0x318, 0x718, 0x98, 0x498, 0x298, 0x698, - 0x198, 0x598, 0x398, 0x798, 0x58, 0x458, 0x258, - 0x658, 0x158, 0x558, 0x358, 0x758, 0xd8, 0x4d8, - 0x2d8, 0x6d8, 0x1d8, 0x5d8, 0x3d8, 0x7d8, 0x38, - 0x438, 0x238, 0x638, 0x138, 0x538, 0x338, 0x738, - 0xb8, 0x4b8, 0x2b8, 0x6b8, 0x1b8, 0x5b8, 0x3b8, - 0x7b8, 0x78, 0x478, 0x278, 0x678, 0x178, 0x578, - 0x378, 0x778, 0xf8, 0x4f8, 0x2f8, 0x6f8, 0x1f8, - 0x5f8, 0x3f8, 0x7f8, 0x4, 0x404, 0x204, 0x604, - 0x104, 0x504, 0x304, 0x704, 0x84, 0x484, 0x284, - 0x684, 0x184, 0x584, 0x384, 0x784, 0x44, 0x444, - 0x244, 0x644, 0x144, 0x544, 0x344, 0x744, 0xc4, - 0x4c4, 0x2c4, 0x6c4, 0x1c4, 0x5c4, 0x3c4, 0x7c4, - 0x24, 0x424, 0x224, 0x624, 0x124, 0x524, 0x324, - 0x724, 0xa4, 0x4a4, 0x2a4, 0x6a4, 0x1a4, 0x5a4, - 0x3a4, 0x7a4, 0x64, 0x464, 0x264, 0x664, 0x164, - 0x564, 0x364, 0x764, 0xe4, 0x4e4, 0x2e4, 0x6e4, - 0x1e4, 0x5e4, 0x3e4, 0x7e4, 0x14, 0x414, 0x214, - 0x614, 0x114, 0x514, 0x314, 0x714, 0x94, 0x494, - 0x294, 0x694, 0x194, 0x594, 0x394, 0x794, 0x54, - 0x454, 0x254, 0x654, 0x154, 0x554, 0x354, 0x754, - 0xd4, 0x4d4, 0x2d4, 0x6d4, 0x1d4, 0x5d4, 0x3d4, - 0x7d4, 0x34, 0x434, 0x234, 0x634, 0x134, 0x534, - 0x334, 0x734, 0xb4, 0x4b4, 0x2b4, 0x6b4, 0x1b4, - 0x5b4, 0x3b4, 0x7b4, 0x74, 0x474, 0x274, 0x674, - 0x174, 0x574, 0x374, 0x774, 0xf4, 0x4f4, 0x2f4, - 0x6f4, 0x1f4, 0x5f4, 0x3f4, 0x7f4, 0xc, 0x40c, - 0x20c, 0x60c, 0x10c, 0x50c, 0x30c, 0x70c, 0x8c, - 0x48c, 0x28c, 0x68c, 0x18c, 0x58c, 0x38c, 0x78c, - 0x4c, 0x44c, 0x24c, 0x64c, 0x14c, 0x54c, 0x34c, - 0x74c, 0xcc, 0x4cc, 0x2cc, 0x6cc, 0x1cc, 0x5cc, - 0x3cc, 0x7cc, 0x2c, 0x42c, 0x22c, 0x62c, 0x12c, - 0x52c, 0x32c, 0x72c, 0xac, 0x4ac, 0x2ac, 0x6ac, - 0x1ac, 0x5ac, 0x3ac, 0x7ac, 0x6c, 0x46c, 0x26c, - 0x66c, 0x16c, 0x56c, 0x36c, 0x76c, 0xec, 0x4ec, - 0x2ec, 0x6ec, 0x1ec, 0x5ec, 0x3ec, 0x7ec, 0x1c, - 0x41c, 0x21c, 0x61c, 0x11c, 0x51c, 0x31c, 0x71c, - 0x9c, 0x49c, 0x29c, 0x69c, 0x19c, 0x59c, 0x39c, - 0x79c, 0x5c, 0x45c, 0x25c, 0x65c, 0x15c, 0x55c, - 0x35c, 0x75c, 0xdc, 0x4dc, 0x2dc, 0x6dc, 0x1dc, - 0x5dc, 0x3dc, 0x7dc, 0x3c, 0x43c, 0x23c, 0x63c, - 0x13c, 0x53c, 0x33c, 0x73c, 0xbc, 0x4bc, 0x2bc, - 0x6bc, 0x1bc, 0x5bc, 0x3bc, 0x7bc, 0x7c, 0x47c, - 0x27c, 0x67c, 0x17c, 0x57c, 0x37c, 0x77c, 0xfc, - 0x4fc, 0x2fc, 0x6fc, 0x1fc, 0x5fc, 0x3fc, 0x7fc, - 0x2, 0x402, 0x202, 0x602, 0x102, 0x502, 0x302, - 0x702, 0x82, 0x482, 0x282, 0x682, 0x182, 0x582, - 0x382, 0x782, 0x42, 0x442, 0x242, 0x642, 0x142, - 0x542, 0x342, 0x742, 0xc2, 0x4c2, 0x2c2, 0x6c2, - 0x1c2, 0x5c2, 0x3c2, 0x7c2, 0x22, 0x422, 0x222, - 0x622, 0x122, 0x522, 0x322, 0x722, 0xa2, 0x4a2, - 0x2a2, 0x6a2, 0x1a2, 0x5a2, 0x3a2, 0x7a2, 0x62, - 0x462, 0x262, 0x662, 0x162, 0x562, 0x362, 0x762, - 0xe2, 0x4e2, 0x2e2, 0x6e2, 0x1e2, 0x5e2, 0x3e2, - 0x7e2, 0x12, 0x412, 0x212, 0x612, 0x112, 0x512, - 0x312, 0x712, 0x92, 0x492, 0x292, 0x692, 0x192, - 0x592, 0x392, 0x792, 0x52, 0x452, 0x252, 0x652, - 0x152, 0x552, 0x352, 0x752, 0xd2, 0x4d2, 0x2d2, - 0x6d2, 0x1d2, 0x5d2, 0x3d2, 0x7d2, 0x32, 0x432, - 0x232, 0x632, 0x132, 0x532, 0x332, 0x732, 0xb2, - 0x4b2, 0x2b2, 0x6b2, 0x1b2, 0x5b2, 0x3b2, 0x7b2, - 0x72, 0x472, 0x272, 0x672, 0x172, 0x572, 0x372, - 0x772, 0xf2, 0x4f2, 0x2f2, 0x6f2, 0x1f2, 0x5f2, - 0x3f2, 0x7f2, 0xa, 0x40a, 0x20a, 0x60a, 0x10a, - 0x50a, 0x30a, 0x70a, 0x8a, 0x48a, 0x28a, 0x68a, - 0x18a, 0x58a, 0x38a, 0x78a, 0x4a, 0x44a, 0x24a, - 0x64a, 0x14a, 0x54a, 0x34a, 0x74a, 0xca, 0x4ca, - 0x2ca, 0x6ca, 0x1ca, 0x5ca, 0x3ca, 0x7ca, 0x2a, - 0x42a, 0x22a, 0x62a, 0x12a, 0x52a, 0x32a, 0x72a, - 0xaa, 0x4aa, 0x2aa, 0x6aa, 0x1aa, 0x5aa, 0x3aa, - 0x7aa, 0x6a, 0x46a, 0x26a, 0x66a, 0x16a, 0x56a, - 0x36a, 0x76a, 0xea, 0x4ea, 0x2ea, 0x6ea, 0x1ea, - 0x5ea, 0x3ea, 0x7ea, 0x1a, 0x41a, 0x21a, 0x61a, - 0x11a, 0x51a, 0x31a, 0x71a, 0x9a, 0x49a, 0x29a, - 0x69a, 0x19a, 0x59a, 0x39a, 0x79a, 0x5a, 0x45a, - 0x25a, 0x65a, 0x15a, 0x55a, 0x35a, 0x75a, 0xda, - 0x4da, 0x2da, 0x6da, 0x1da, 0x5da, 0x3da, 0x7da, - 0x3a, 0x43a, 0x23a, 0x63a, 0x13a, 0x53a, 0x33a, - 0x73a, 0xba, 0x4ba, 0x2ba, 0x6ba, 0x1ba, 0x5ba, - 0x3ba, 0x7ba, 0x7a, 0x47a, 0x27a, 0x67a, 0x17a, - 0x57a, 0x37a, 0x77a, 0xfa, 0x4fa, 0x2fa, 0x6fa, - 0x1fa, 0x5fa, 0x3fa, 0x7fa, 0x6, 0x406, 0x206, - 0x606, 0x106, 0x506, 0x306, 0x706, 0x86, 0x486, - 0x286, 0x686, 0x186, 0x586, 0x386, 0x786, 0x46, - 0x446, 0x246, 0x646, 0x146, 0x546, 0x346, 0x746, - 0xc6, 0x4c6, 0x2c6, 0x6c6, 0x1c6, 0x5c6, 0x3c6, - 0x7c6, 0x26, 0x426, 0x226, 0x626, 0x126, 0x526, - 0x326, 0x726, 0xa6, 0x4a6, 0x2a6, 0x6a6, 0x1a6, - 0x5a6, 0x3a6, 0x7a6, 0x66, 0x466, 0x266, 0x666, - 0x166, 0x566, 0x366, 0x766, 0xe6, 0x4e6, 0x2e6, - 0x6e6, 0x1e6, 0x5e6, 0x3e6, 0x7e6, 0x16, 0x416, - 0x216, 0x616, 0x116, 0x516, 0x316, 0x716, 0x96, - 0x496, 0x296, 0x696, 0x196, 0x596, 0x396, 0x796, - 0x56, 0x456, 0x256, 0x656, 0x156, 0x556, 0x356, - 0x756, 0xd6, 0x4d6, 0x2d6, 0x6d6, 0x1d6, 0x5d6, - 0x3d6, 0x7d6, 0x36, 0x436, 0x236, 0x636, 0x136, - 0x536, 0x336, 0x736, 0xb6, 0x4b6, 0x2b6, 0x6b6, - 0x1b6, 0x5b6, 0x3b6, 0x7b6, 0x76, 0x476, 0x276, - 0x676, 0x176, 0x576, 0x376, 0x776, 0xf6, 0x4f6, - 0x2f6, 0x6f6, 0x1f6, 0x5f6, 0x3f6, 0x7f6, 0xe, - 0x40e, 0x20e, 0x60e, 0x10e, 0x50e, 0x30e, 0x70e, - 0x8e, 0x48e, 0x28e, 0x68e, 0x18e, 0x58e, 0x38e, - 0x78e, 0x4e, 0x44e, 0x24e, 0x64e, 0x14e, 0x54e, - 0x34e, 0x74e, 0xce, 0x4ce, 0x2ce, 0x6ce, 0x1ce, - 0x5ce, 0x3ce, 0x7ce, 0x2e, 0x42e, 0x22e, 0x62e, - 0x12e, 0x52e, 0x32e, 0x72e, 0xae, 0x4ae, 0x2ae, - 0x6ae, 0x1ae, 0x5ae, 0x3ae, 0x7ae, 0x6e, 0x46e, - 0x26e, 0x66e, 0x16e, 0x56e, 0x36e, 0x76e, 0xee, - 0x4ee, 0x2ee, 0x6ee, 0x1ee, 0x5ee, 0x3ee, 0x7ee, - 0x1e, 0x41e, 0x21e, 0x61e, 0x11e, 0x51e, 0x31e, - 0x71e, 0x9e, 0x49e, 0x29e, 0x69e, 0x19e, 0x59e, - 0x39e, 0x79e, 0x5e, 0x45e, 0x25e, 0x65e, 0x15e, - 0x55e, 0x35e, 0x75e, 0xde, 0x4de, 0x2de, 0x6de, - 0x1de, 0x5de, 0x3de, 0x7de, 0x3e, 0x43e, 0x23e, - 0x63e, 0x13e, 0x53e, 0x33e, 0x73e, 0xbe, 0x4be, - 0x2be, 0x6be, 0x1be, 0x5be, 0x3be, 0x7be, 0x7e, - 0x47e, 0x27e, 0x67e, 0x17e, 0x57e, 0x37e, 0x77e, - 0xfe, 0x4fe, 0x2fe, 0x6fe, 0x1fe, 0x5fe, 0x3fe, - 0x7fe, 0x1 -}; - - -/* -* @brief Floating-point Twiddle factors Table Generation -*/ - - -/** -* \par -* Example code for Floating-point Twiddle factors Generation: -* \par -*
for(i = 0; i< 3N/4; i++)    
-* {    
-*	twiddleCoef[2*i]= cos(i * 2*PI/(float)N);    
-*	twiddleCoef[2*i+1]= sin(i * 2*PI/(float)N);    
-* } 
-* \par -* where N = 4096 and PI = 3.14159265358979 -* \par -* Cos and Sin values are in interleaved fashion -* -*/ -const float32_t twiddleCoef[6144] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999998823451701880f, - 0.001533980186284766f, 0.999995293809576190f, 0.003067956762965976f, - 0.999989411081928400f, 0.004601926120448571f, 0.999981175282601110f, - 0.006135884649154475f, 0.999970586430974140f, 0.007669828739531097f, - 0.999957644551963900f, 0.009203754782059819f, 0.999942349676023910f, - 0.010737659167264491f, 0.999924701839144500f, 0.012271538285719925f, - 0.999904701082852900f, 0.013805388528060391f, 0.999882347454212560f, - 0.015339206284988100f, 0.999857641005823860f, 0.016872987947281710f, - 0.999830581795823400f, 0.018406729905804820f, 0.999801169887884260f, - 0.019940428551514441f, 0.999769405351215280f, 0.021474080275469508f, - 0.999735288260561680f, 0.023007681468839369f, 0.999698818696204250f, - 0.024541228522912288f, 0.999659996743959220f, 0.026074717829103901f, - 0.999618822495178640f, 0.027608145778965740f, 0.999575296046749220f, - 0.029141508764193722f, 0.999529417501093140f, 0.030674803176636626f, - 0.999481186966166950f, 0.032208025408304586f, 0.999430604555461730f, - 0.033741171851377580f, 0.999377670388002850f, 0.035274238898213947f, - 0.999322384588349540f, 0.036807222941358832f, 0.999264747286594420f, - 0.038340120373552694f, 0.999204758618363890f, 0.039872927587739811f, - 0.999142418724816910f, 0.041405640977076739f, 0.999077727752645360f, - 0.042938256934940820f, 0.999010685854073380f, 0.044470771854938668f, - 0.998941293186856870f, 0.046003182130914623f, 0.998869549914283560f, - 0.047535484156959303f, 0.998795456205172410f, 0.049067674327418015f, - 0.998719012233872940f, 0.050599749036899282f, 0.998640218180265270f, - 0.052131704680283324f, 0.998559074229759310f, 0.053663537652730520f, - 0.998475580573294770f, 0.055195244349689934f, 0.998389737407340160f, - 0.056726821166907748f, 0.998301544933892890f, 0.058258264500435752f, - 0.998211003360478190f, 0.059789570746639868f, 0.998118112900149180f, - 0.061320736302208578f, 0.998022873771486240f, 0.062851757564161406f, - 0.997925286198596000f, 0.064382630929857465f, 0.997825350411111640f, - 0.065913352797003805f, 0.997723066644191640f, 0.067443919563664051f, - 0.997618435138519550f, 0.068974327628266746f, 0.997511456140303450f, - 0.070504573389613856f, 0.997402129901275300f, 0.072034653246889332f, - 0.997290456678690210f, 0.073564563599667426f, 0.997176436735326190f, - 0.075094300847921305f, 0.997060070339482960f, 0.076623861392031492f, - 0.996941357764982160f, 0.078153241632794232f, 0.996820299291165670f, - 0.079682437971430126f, 0.996696895202896060f, 0.081211446809592441f, - 0.996571145790554840f, 0.082740264549375692f, 0.996443051350042630f, - 0.084268887593324071f, 0.996312612182778000f, 0.085797312344439894f, - 0.996179828595696980f, 0.087325535206192059f, 0.996044700901251970f, - 0.088853552582524600f, 0.995907229417411720f, 0.090381360877864983f, - 0.995767414467659820f, 0.091908956497132724f, 0.995625256380994310f, - 0.093436335845747787f, 0.995480755491926940f, 0.094963495329638992f, - 0.995333912140482280f, 0.096490431355252593f, 0.995184726672196930f, - 0.098017140329560604f, 0.995033199438118630f, 0.099543618660069319f, - 0.994879330794805620f, 0.101069862754827820f, 0.994723121104325700f, - 0.102595869022436280f, 0.994564570734255420f, 0.104121633872054590f, - 0.994403680057679100f, 0.105647153713410620f, 0.994240449453187900f, - 0.107172424956808840f, 0.994074879304879370f, 0.108697444013138720f, - 0.993906970002356060f, 0.110222207293883060f, 0.993736721940724600f, - 0.111746711211126590f, 0.993564135520595300f, 0.113270952177564350f, - 0.993389211148080650f, 0.114794926606510080f, 0.993211949234794500f, - 0.116318630911904750f, 0.993032350197851410f, 0.117842061508324980f, - 0.992850414459865100f, 0.119365214810991350f, 0.992666142448948020f, - 0.120888087235777080f, 0.992479534598709970f, 0.122410675199216200f, - 0.992290591348257370f, 0.123932975118512160f, 0.992099313142191800f, - 0.125454983411546230f, 0.991905700430609330f, 0.126976696496885870f, - 0.991709753669099530f, 0.128498110793793170f, 0.991511473318743900f, - 0.130019222722233350f, 0.991310859846115440f, 0.131540028702883120f, - 0.991107913723276890f, 0.133060525157139060f, 0.990902635427780010f, - 0.134580708507126170f, 0.990695025442664630f, 0.136100575175706200f, - 0.990485084256457090f, 0.137620121586486040f, 0.990272812363169110f, - 0.139139344163826200f, 0.990058210262297120f, 0.140658239332849210f, - 0.989841278458820530f, 0.142176803519448030f, 0.989622017463200890f, - 0.143695033150294470f, 0.989400427791380380f, 0.145212924652847460f, - 0.989176509964781010f, 0.146730474455361750f, 0.988950264510302990f, - 0.148247678986896030f, 0.988721691960323780f, 0.149764534677321510f, - 0.988490792852696590f, 0.151281037957330220f, 0.988257567730749460f, - 0.152797185258443440f, 0.988022017143283530f, 0.154312973013020100f, - 0.987784141644572180f, 0.155828397654265230f, 0.987543941794359230f, - 0.157343455616238250f, 0.987301418157858430f, 0.158858143333861450f, - 0.987056571305750970f, 0.160372457242928280f, 0.986809401814185530f, - 0.161886393780111830f, 0.986559910264775410f, 0.163399949382973230f, - 0.986308097244598670f, 0.164913120489969890f, 0.986053963346195440f, - 0.166425903540464100f, 0.985797509167567480f, 0.167938294974731170f, - 0.985538735312176060f, 0.169450291233967960f, 0.985277642388941220f, - 0.170961888760301220f, 0.985014231012239840f, 0.172473083996795950f, - 0.984748501801904210f, 0.173983873387463820f, 0.984480455383220930f, - 0.175494253377271430f, 0.984210092386929030f, 0.177004220412148750f, - 0.983937413449218920f, 0.178513770938997510f, 0.983662419211730250f, - 0.180022901405699510f, 0.983385110321551180f, 0.181531608261124970f, - 0.983105487431216290f, 0.183039887955140950f, 0.982823551198705240f, - 0.184547736938619620f, 0.982539302287441240f, 0.186055151663446630f, - 0.982252741366289370f, 0.187562128582529600f, 0.981963869109555240f, - 0.189068664149806190f, 0.981672686196983110f, 0.190574754820252740f, - 0.981379193313754560f, 0.192080397049892440f, 0.981083391150486710f, - 0.193585587295803610f, 0.980785280403230430f, 0.195090322016128250f, - 0.980484861773469380f, 0.196594597670080220f, 0.980182135968117430f, - 0.198098410717953560f, 0.979877103699517640f, 0.199601757621130970f, - 0.979569765685440520f, 0.201104634842091900f, 0.979260122649082020f, - 0.202607038844421130f, 0.978948175319062200f, 0.204108966092816870f, - 0.978633924429423210f, 0.205610413053099240f, 0.978317370719627650f, - 0.207111376192218560f, 0.977998514934557140f, 0.208611851978263490f, - 0.977677357824509930f, 0.210111836880469610f, 0.977353900145199960f, - 0.211611327369227550f, 0.977028142657754390f, 0.213110319916091360f, - 0.976700086128711840f, 0.214608810993786760f, 0.976369731330021140f, - 0.216106797076219520f, 0.976037079039039020f, 0.217604274638483640f, - 0.975702130038528570f, 0.219101240156869800f, 0.975364885116656980f, - 0.220597690108873510f, 0.975025345066994120f, 0.222093620973203510f, - 0.974683510688510670f, 0.223589029229789990f, 0.974339382785575860f, - 0.225083911359792830f, 0.973992962167955830f, 0.226578263845610000f, - 0.973644249650811980f, 0.228072083170885730f, 0.973293246054698250f, - 0.229565365820518870f, 0.972939952205560180f, 0.231058108280671110f, - 0.972584368934732210f, 0.232550307038775240f, 0.972226497078936270f, - 0.234041958583543430f, 0.971866337480279400f, 0.235533059404975490f, - 0.971503890986251780f, 0.237023605994367200f, 0.971139158449725090f, - 0.238513594844318420f, 0.970772140728950350f, 0.240003022448741500f, - 0.970402838687555500f, 0.241491885302869330f, 0.970031253194543970f, - 0.242980179903263870f, 0.969657385124292450f, 0.244467902747824150f, - 0.969281235356548530f, 0.245955050335794590f, 0.968902804776428870f, - 0.247441619167773270f, 0.968522094274417380f, 0.248927605745720150f, - 0.968139104746362440f, 0.250413006572965220f, 0.967753837093475510f, - 0.251897818154216970f, 0.967366292222328510f, 0.253382036995570160f, - 0.966976471044852070f, 0.254865659604514570f, 0.966584374478333120f, - 0.256348682489942910f, 0.966190003445412500f, 0.257831102162158990f, - 0.965793358874083680f, 0.259312915132886230f, 0.965394441697689400f, - 0.260794117915275510f, 0.964993252854920320f, 0.262274707023913590f, - 0.964589793289812760f, 0.263754678974831350f, 0.964184063951745830f, - 0.265234030285511790f, 0.963776065795439840f, 0.266712757474898370f, - 0.963365799780954050f, 0.268190857063403180f, 0.962953266873683880f, - 0.269668325572915090f, 0.962538468044359160f, 0.271145159526808010f, - 0.962121404269041580f, 0.272621355449948980f, 0.961702076529122540f, - 0.274096909868706380f, 0.961280485811320640f, 0.275571819310958140f, - 0.960856633107679660f, 0.277046080306099900f, 0.960430519415565790f, - 0.278519689385053060f, 0.960002145737665960f, 0.279992643080273220f, - 0.959571513081984520f, 0.281464937925757940f, 0.959138622461841890f, - 0.282936570457055390f, 0.958703474895871600f, 0.284407537211271880f, - 0.958266071408017670f, 0.285877834727080620f, 0.957826413027532910f, - 0.287347459544729510f, 0.957384500788975860f, 0.288816408206049480f, - 0.956940335732208820f, 0.290284677254462330f, 0.956493918902395100f, - 0.291752263234989260f, 0.956045251349996410f, 0.293219162694258630f, - 0.955594334130771110f, 0.294685372180514330f, 0.955141168305770780f, - 0.296150888243623790f, 0.954685754941338340f, 0.297615707435086200f, - 0.954228095109105670f, 0.299079826308040480f, 0.953768189885990330f, - 0.300543241417273450f, 0.953306040354193860f, 0.302005949319228080f, - 0.952841647601198720f, 0.303467946572011320f, 0.952375012719765880f, - 0.304929229735402370f, 0.951906136807932350f, 0.306389795370860920f, - 0.951435020969008340f, 0.307849640041534870f, 0.950961666311575080f, - 0.309308760312268730f, 0.950486073949481700f, 0.310767152749611470f, - 0.950008245001843000f, 0.312224813921824880f, 0.949528180593036670f, - 0.313681740398891520f, 0.949045881852700560f, 0.315137928752522440f, - 0.948561349915730270f, 0.316593375556165850f, 0.948074585922276230f, - 0.318048077385014950f, 0.947585591017741090f, 0.319502030816015690f, - 0.947094366352777220f, 0.320955232427875210f, 0.946600913083283530f, - 0.322407678801069850f, 0.946105232370403450f, 0.323859366517852850f, - 0.945607325380521280f, 0.325310292162262930f, 0.945107193285260610f, - 0.326760452320131730f, 0.944604837261480260f, 0.328209843579092500f, - 0.944100258491272660f, 0.329658462528587490f, 0.943593458161960390f, - 0.331106305759876430f, 0.943084437466093490f, 0.332553369866044220f, - 0.942573197601446870f, 0.333999651442009380f, 0.942059739771017310f, - 0.335445147084531600f, 0.941544065183020810f, 0.336889853392220050f, - 0.941026175050889260f, 0.338333766965541130f, 0.940506070593268300f, - 0.339776884406826850f, 0.939983753034014050f, 0.341219202320282360f, - 0.939459223602189920f, 0.342660717311994380f, 0.938932483532064600f, - 0.344101425989938810f, 0.938403534063108060f, 0.345541324963989090f, - 0.937872376439989890f, 0.346980410845923680f, 0.937339011912574960f, - 0.348418680249434560f, 0.936803441735921560f, 0.349856129790134920f, - 0.936265667170278260f, 0.351292756085567090f, 0.935725689481080370f, - 0.352728555755210730f, 0.935183509938947610f, 0.354163525420490340f, - 0.934639129819680780f, 0.355597661704783850f, 0.934092550404258980f, - 0.357030961233429980f, 0.933543772978836170f, 0.358463420633736540f, - 0.932992798834738960f, 0.359895036534988110f, 0.932439629268462360f, - 0.361325805568454280f, 0.931884265581668150f, 0.362755724367397230f, - 0.931326709081180430f, 0.364184789567079890f, 0.930766961078983710f, - 0.365612997804773850f, 0.930205022892219070f, 0.367040345719767180f, - 0.929640895843181330f, 0.368466829953372320f, 0.929074581259315860f, - 0.369892447148934100f, 0.928506080473215590f, 0.371317193951837540f, - 0.927935394822617890f, 0.372741067009515760f, 0.927362525650401110f, - 0.374164062971457930f, 0.926787474304581750f, 0.375586178489217220f, - 0.926210242138311380f, 0.377007410216418260f, 0.925630830509872720f, - 0.378427754808765560f, 0.925049240782677580f, 0.379847208924051160f, - 0.924465474325262600f, 0.381265769222162380f, 0.923879532511286740f, - 0.382683432365089780f, 0.923291416719527640f, 0.384100195016935040f, - 0.922701128333878630f, 0.385516053843918850f, 0.922108668743345180f, - 0.386931005514388580f, 0.921514039342042010f, 0.388345046698826250f, - 0.920917241529189520f, 0.389758174069856410f, 0.920318276709110590f, - 0.391170384302253870f, 0.919717146291227360f, 0.392581674072951470f, - 0.919113851690057770f, 0.393992040061048100f, 0.918508394325212250f, - 0.395401478947816350f, 0.917900775621390500f, 0.396809987416710310f, - 0.917290997008377910f, 0.398217562153373560f, 0.916679059921042700f, - 0.399624199845646790f, 0.916064965799331720f, 0.401029897183575620f, - 0.915448716088267830f, 0.402434650859418430f, 0.914830312237946200f, - 0.403838457567654070f, 0.914209755703530690f, 0.405241314004989860f, - 0.913587047945250810f, 0.406643216870369030f, 0.912962190428398210f, - 0.408044162864978690f, 0.912335184623322750f, 0.409444148692257590f, - 0.911706032005429880f, 0.410843171057903910f, 0.911074734055176360f, - 0.412241226669882890f, 0.910441292258067250f, 0.413638312238434500f, - 0.909805708104652220f, 0.415034424476081630f, 0.909167983090522380f, - 0.416429560097637150f, 0.908528118716306120f, 0.417823715820212270f, - 0.907886116487666260f, 0.419216888363223910f, 0.907241977915295820f, - 0.420609074448402510f, 0.906595704514915330f, 0.422000270799799680f, - 0.905947297807268460f, 0.423390474143796050f, 0.905296759318118820f, - 0.424779681209108810f, 0.904644090578246240f, 0.426167888726799620f, - 0.903989293123443340f, 0.427555093430282080f, 0.903332368494511820f, - 0.428941292055329490f, 0.902673318237258830f, 0.430326481340082610f, - 0.902012143902493180f, 0.431710658025057260f, 0.901348847046022030f, - 0.433093818853151960f, 0.900683429228646970f, 0.434475960569655650f, - 0.900015892016160280f, 0.435857079922255470f, 0.899346236979341570f, - 0.437237173661044090f, 0.898674465693953820f, 0.438616238538527660f, - 0.898000579740739880f, 0.439994271309633260f, 0.897324580705418320f, - 0.441371268731716670f, 0.896646470178680150f, 0.442747227564570020f, - 0.895966249756185220f, 0.444122144570429200f, 0.895283921038557580f, - 0.445496016513981740f, 0.894599485631382700f, 0.446868840162374160f, - 0.893912945145203250f, 0.448240612285219890f, 0.893224301195515320f, - 0.449611329654606540f, 0.892533555402764580f, 0.450980989045103860f, - 0.891840709392342720f, 0.452349587233770890f, 0.891145764794583180f, - 0.453717121000163870f, 0.890448723244757880f, 0.455083587126343840f, - 0.889749586383072780f, 0.456448982396883920f, 0.889048355854664570f, - 0.457813303598877170f, 0.888345033309596350f, 0.459176547521944090f, - 0.887639620402853930f, 0.460538710958240010f, 0.886932118794342190f, - 0.461899790702462730f, 0.886222530148880640f, 0.463259783551860150f, - 0.885510856136199950f, 0.464618686306237820f, 0.884797098430937790f, - 0.465976495767966180f, 0.884081258712634990f, 0.467333208741988420f, - 0.883363338665731580f, 0.468688822035827900f, 0.882643339979562790f, - 0.470043332459595620f, 0.881921264348355050f, 0.471396736825997640f, - 0.881197113471222090f, 0.472749031950342790f, 0.880470889052160750f, - 0.474100214650549970f, 0.879742592800047410f, 0.475450281747155870f, - 0.879012226428633530f, 0.476799230063322090f, 0.878279791656541580f, - 0.478147056424843010f, 0.877545290207261350f, 0.479493757660153010f, - 0.876808723809145650f, 0.480839330600333960f, 0.876070094195406600f, - 0.482183772079122720f, 0.875329403104110890f, 0.483527078932918740f, - 0.874586652278176110f, 0.484869248000791060f, 0.873841843465366860f, - 0.486210276124486420f, 0.873094978418290090f, 0.487550160148436000f, - 0.872346058894391540f, 0.488888896919763170f, 0.871595086655950980f, - 0.490226483288291160f, 0.870842063470078980f, 0.491562916106549900f, - 0.870086991108711460f, 0.492898192229784040f, 0.869329871348606840f, - 0.494232308515959670f, 0.868570705971340900f, 0.495565261825772540f, - 0.867809496763303320f, 0.496897049022654470f, 0.867046245515692650f, - 0.498227666972781870f, 0.866280954024512990f, 0.499557112545081840f, - 0.865513624090569090f, 0.500885382611240710f, 0.864744257519462380f, - 0.502212474045710790f, 0.863972856121586810f, 0.503538383725717580f, - 0.863199421712124160f, 0.504863108531267590f, 0.862423956111040610f, - 0.506186645345155230f, 0.861646461143081300f, 0.507508991052970870f, - 0.860866938637767310f, 0.508830142543106990f, 0.860085390429390140f, - 0.510150096706766810f, 0.859301818357008470f, 0.511468850437970300f, - 0.858516224264442740f, 0.512786400633562960f, 0.857728610000272120f, - 0.514102744193221660f, 0.856938977417828760f, 0.515417878019462930f, - 0.856147328375194470f, 0.516731799017649870f, 0.855353664735196030f, - 0.518044504095999340f, 0.854557988365400530f, 0.519355990165589640f, - 0.853760301138111410f, 0.520666254140367160f, 0.852960604930363630f, - 0.521975292937154390f, 0.852158901623919830f, 0.523283103475656430f, - 0.851355193105265200f, 0.524589682678468950f, 0.850549481265603480f, - 0.525895027471084630f, 0.849741768000852550f, 0.527199134781901280f, - 0.848932055211639610f, 0.528502001542228480f, 0.848120344803297230f, - 0.529803624686294610f, 0.847306638685858320f, 0.531104001151255000f, - 0.846490938774052130f, 0.532403127877197900f, 0.845673246987299070f, - 0.533701001807152960f, 0.844853565249707120f, 0.534997619887097150f, - 0.844031895490066410f, 0.536292979065963180f, 0.843208239641845440f, - 0.537587076295645390f, 0.842382599643185850f, 0.538879908531008420f, - 0.841554977436898440f, 0.540171472729892850f, 0.840725374970458070f, - 0.541461765853123440f, 0.839893794195999520f, 0.542750784864515890f, - 0.839060237070312740f, 0.544038526730883820f, 0.838224705554838080f, - 0.545324988422046460f, 0.837387201615661940f, 0.546610166910834860f, - 0.836547727223512010f, 0.547894059173100190f, 0.835706284353752600f, - 0.549176662187719660f, 0.834862874986380010f, 0.550457972936604810f, - 0.834017501106018130f, 0.551737988404707340f, 0.833170164701913190f, - 0.553016705580027470f, 0.832320867767929680f, 0.554294121453620000f, - 0.831469612302545240f, 0.555570233019602180f, 0.830616400308846310f, - 0.556845037275160100f, 0.829761233794523050f, 0.558118531220556100f, - 0.828904114771864870f, 0.559390711859136140f, 0.828045045257755800f, - 0.560661576197336030f, 0.827184027273669130f, 0.561931121244689470f, - 0.826321062845663530f, 0.563199344013834090f, 0.825456154004377550f, - 0.564466241520519500f, 0.824589302785025290f, 0.565731810783613120f, - 0.823720511227391430f, 0.566996048825108680f, 0.822849781375826430f, - 0.568258952670131490f, 0.821977115279241550f, 0.569520519346947140f, - 0.821102514991104650f, 0.570780745886967260f, 0.820225982569434690f, - 0.572039629324757050f, 0.819347520076796900f, 0.573297166698042200f, - 0.818467129580298660f, 0.574553355047715760f, 0.817584813151583710f, - 0.575808191417845340f, 0.816700572866827850f, 0.577061672855679440f, - 0.815814410806733780f, 0.578313796411655590f, 0.814926329056526620f, - 0.579564559139405630f, 0.814036329705948410f, 0.580813958095764530f, - 0.813144414849253590f, 0.582061990340775440f, 0.812250586585203880f, - 0.583308652937698290f, 0.811354847017063730f, 0.584553942953015330f, - 0.810457198252594770f, 0.585797857456438860f, 0.809557642404051260f, - 0.587040393520917970f, 0.808656181588174980f, 0.588281548222645220f, - 0.807752817926190360f, 0.589521318641063940f, 0.806847553543799330f, - 0.590759701858874160f, 0.805940390571176280f, 0.591996694962040990f, - 0.805031331142963660f, 0.593232295039799800f, 0.804120377398265810f, - 0.594466499184664430f, 0.803207531480644940f, 0.595699304492433360f, - 0.802292795538115720f, 0.596930708062196500f, 0.801376171723140240f, - 0.598160706996342270f, 0.800457662192622820f, 0.599389298400564540f, - 0.799537269107905010f, 0.600616479383868970f, 0.798614994634760820f, - 0.601842247058580030f, 0.797690840943391160f, 0.603066598540348160f, - 0.796764810208418830f, 0.604289530948155960f, 0.795836904608883570f, - 0.605511041404325550f, 0.794907126328237010f, 0.606731127034524480f, - 0.793975477554337170f, 0.607949784967773630f, 0.793041960479443640f, - 0.609167012336453210f, 0.792106577300212390f, 0.610382806276309480f, - 0.791169330217690200f, 0.611597163926461910f, 0.790230221437310030f, - 0.612810082429409710f, 0.789289253168885650f, 0.614021558931038380f, - 0.788346427626606340f, 0.615231590580626820f, 0.787401747029031430f, - 0.616440174530853650f, 0.786455213599085770f, 0.617647307937803870f, - 0.785506829564053930f, 0.618852987960976320f, 0.784556597155575240f, - 0.620057211763289100f, 0.783604518609638200f, 0.621259976511087550f, - 0.782650596166575730f, 0.622461279374149970f, 0.781694832071059390f, - 0.623661117525694530f, 0.780737228572094490f, 0.624859488142386340f, - 0.779777787923014550f, 0.626056388404343520f, 0.778816512381475980f, - 0.627251815495144080f, 0.777853404209453150f, 0.628445766601832710f, - 0.776888465673232440f, 0.629638238914926980f, 0.775921699043407690f, - 0.630829229628424470f, 0.774953106594873930f, 0.632018735939809060f, - 0.773982690606822900f, 0.633206755050057190f, 0.773010453362736990f, - 0.634393284163645490f, 0.772036397150384520f, 0.635578320488556110f, - 0.771060524261813820f, 0.636761861236284200f, 0.770082836993347900f, - 0.637943903621844060f, 0.769103337645579700f, 0.639124444863775730f, - 0.768122028523365420f, 0.640303482184151670f, 0.767138911935820400f, - 0.641481012808583160f, 0.766153990196312920f, 0.642657033966226860f, - 0.765167265622458960f, 0.643831542889791390f, 0.764178740536116670f, - 0.645004536815543930f, 0.763188417263381270f, 0.646176012983316280f, - 0.762196298134578900f, 0.647345968636512060f, 0.761202385484261780f, - 0.648514401022112440f, 0.760206681651202420f, 0.649681307390683190f, - 0.759209188978388070f, 0.650846684996380880f, 0.758209909813015280f, - 0.652010531096959500f, 0.757208846506484570f, 0.653172842953776760f, - 0.756206001414394540f, 0.654333617831800440f, 0.755201376896536550f, - 0.655492852999615350f, 0.754194975316889170f, 0.656650545729428940f, - 0.753186799043612520f, 0.657806693297078640f, 0.752176850449042810f, - 0.658961292982037320f, 0.751165131909686480f, 0.660114342067420480f, - 0.750151645806215070f, 0.661265837839992270f, 0.749136394523459370f, - 0.662415777590171780f, 0.748119380450403600f, 0.663564158612039770f, - 0.747100605980180130f, 0.664710978203344790f, 0.746080073510063780f, - 0.665856233665509720f, 0.745057785441466060f, 0.666999922303637470f, - 0.744033744179929290f, 0.668142041426518450f, 0.743007952135121720f, - 0.669282588346636010f, 0.741980411720831070f, 0.670421560380173090f, - 0.740951125354959110f, 0.671558954847018330f, 0.739920095459516200f, - 0.672694769070772860f, 0.738887324460615110f, 0.673829000378756040f, - 0.737852814788465980f, 0.674961646102011930f, 0.736816568877369900f, - 0.676092703575315920f, 0.735778589165713590f, 0.677222170137180330f, - 0.734738878095963500f, 0.678350043129861470f, 0.733697438114660370f, - 0.679476319899364970f, 0.732654271672412820f, 0.680600997795453020f, - 0.731609381223892630f, 0.681724074171649710f, 0.730562769227827590f, - 0.682845546385248080f, 0.729514438146997010f, 0.683965411797315400f, - 0.728464390448225200f, 0.685083667772700360f, 0.727412628602375770f, - 0.686200311680038590f, 0.726359155084346010f, 0.687315340891759050f, - 0.725303972373060770f, 0.688428752784090440f, 0.724247082951467000f, - 0.689540544737066830f, 0.723188489306527460f, 0.690650714134534600f, - 0.722128193929215350f, 0.691759258364157750f, 0.721066199314508110f, - 0.692866174817424630f, 0.720002507961381650f, 0.693971460889654000f, - 0.718937122372804490f, 0.695075113980000880f, 0.717870045055731710f, - 0.696177131491462990f, 0.716801278521099540f, 0.697277510830886520f, - 0.715730825283818590f, 0.698376249408972920f, 0.714658687862769090f, - 0.699473344640283770f, 0.713584868780793640f, 0.700568793943248340f, - 0.712509370564692320f, 0.701662594740168450f, 0.711432195745216430f, - 0.702754744457225300f, 0.710353346857062420f, 0.703845240524484940f, - 0.709272826438865690f, 0.704934080375904880f, 0.708190637033195400f, - 0.706021261449339740f, 0.707106781186547570f, 0.707106781186547460f, - 0.706021261449339740f, 0.708190637033195290f, 0.704934080375904990f, - 0.709272826438865580f, 0.703845240524484940f, 0.710353346857062310f, - 0.702754744457225300f, 0.711432195745216430f, 0.701662594740168570f, - 0.712509370564692320f, 0.700568793943248450f, 0.713584868780793520f, - 0.699473344640283770f, 0.714658687862768980f, 0.698376249408972920f, - 0.715730825283818590f, 0.697277510830886630f, 0.716801278521099540f, - 0.696177131491462990f, 0.717870045055731710f, 0.695075113980000880f, - 0.718937122372804380f, 0.693971460889654000f, 0.720002507961381650f, - 0.692866174817424740f, 0.721066199314508110f, 0.691759258364157750f, - 0.722128193929215350f, 0.690650714134534720f, 0.723188489306527350f, - 0.689540544737066940f, 0.724247082951466890f, 0.688428752784090550f, - 0.725303972373060660f, 0.687315340891759160f, 0.726359155084346010f, - 0.686200311680038700f, 0.727412628602375770f, 0.685083667772700360f, - 0.728464390448225200f, 0.683965411797315510f, 0.729514438146996900f, - 0.682845546385248080f, 0.730562769227827590f, 0.681724074171649820f, - 0.731609381223892520f, 0.680600997795453130f, 0.732654271672412820f, - 0.679476319899365080f, 0.733697438114660260f, 0.678350043129861580f, - 0.734738878095963390f, 0.677222170137180450f, 0.735778589165713480f, - 0.676092703575316030f, 0.736816568877369790f, 0.674961646102012040f, - 0.737852814788465980f, 0.673829000378756150f, 0.738887324460615110f, - 0.672694769070772970f, 0.739920095459516090f, 0.671558954847018330f, - 0.740951125354959110f, 0.670421560380173090f, 0.741980411720830960f, - 0.669282588346636010f, 0.743007952135121720f, 0.668142041426518560f, - 0.744033744179929180f, 0.666999922303637470f, 0.745057785441465950f, - 0.665856233665509720f, 0.746080073510063780f, 0.664710978203344900f, - 0.747100605980180130f, 0.663564158612039880f, 0.748119380450403490f, - 0.662415777590171780f, 0.749136394523459260f, 0.661265837839992270f, - 0.750151645806214960f, 0.660114342067420480f, 0.751165131909686370f, - 0.658961292982037320f, 0.752176850449042700f, 0.657806693297078640f, - 0.753186799043612410f, 0.656650545729429050f, 0.754194975316889170f, - 0.655492852999615460f, 0.755201376896536550f, 0.654333617831800550f, - 0.756206001414394540f, 0.653172842953776760f, 0.757208846506484460f, - 0.652010531096959500f, 0.758209909813015280f, 0.650846684996380990f, - 0.759209188978387960f, 0.649681307390683190f, 0.760206681651202420f, - 0.648514401022112550f, 0.761202385484261780f, 0.647345968636512060f, - 0.762196298134578900f, 0.646176012983316390f, 0.763188417263381270f, - 0.645004536815544040f, 0.764178740536116670f, 0.643831542889791500f, - 0.765167265622458960f, 0.642657033966226860f, 0.766153990196312810f, - 0.641481012808583160f, 0.767138911935820400f, 0.640303482184151670f, - 0.768122028523365310f, 0.639124444863775730f, 0.769103337645579590f, - 0.637943903621844170f, 0.770082836993347900f, 0.636761861236284200f, - 0.771060524261813710f, 0.635578320488556230f, 0.772036397150384410f, - 0.634393284163645490f, 0.773010453362736990f, 0.633206755050057190f, - 0.773982690606822790f, 0.632018735939809060f, 0.774953106594873820f, - 0.630829229628424470f, 0.775921699043407580f, 0.629638238914927100f, - 0.776888465673232440f, 0.628445766601832710f, 0.777853404209453040f, - 0.627251815495144190f, 0.778816512381475870f, 0.626056388404343520f, - 0.779777787923014440f, 0.624859488142386450f, 0.780737228572094380f, - 0.623661117525694640f, 0.781694832071059390f, 0.622461279374150080f, - 0.782650596166575730f, 0.621259976511087660f, 0.783604518609638200f, - 0.620057211763289210f, 0.784556597155575240f, 0.618852987960976320f, - 0.785506829564053930f, 0.617647307937803980f, 0.786455213599085770f, - 0.616440174530853650f, 0.787401747029031320f, 0.615231590580626820f, - 0.788346427626606230f, 0.614021558931038490f, 0.789289253168885650f, - 0.612810082429409710f, 0.790230221437310030f, 0.611597163926462020f, - 0.791169330217690090f, 0.610382806276309480f, 0.792106577300212390f, - 0.609167012336453210f, 0.793041960479443640f, 0.607949784967773740f, - 0.793975477554337170f, 0.606731127034524480f, 0.794907126328237010f, - 0.605511041404325550f, 0.795836904608883460f, 0.604289530948156070f, - 0.796764810208418720f, 0.603066598540348280f, 0.797690840943391040f, - 0.601842247058580030f, 0.798614994634760820f, 0.600616479383868970f, - 0.799537269107905010f, 0.599389298400564540f, 0.800457662192622710f, - 0.598160706996342380f, 0.801376171723140130f, 0.596930708062196500f, - 0.802292795538115720f, 0.595699304492433470f, 0.803207531480644830f, - 0.594466499184664540f, 0.804120377398265700f, 0.593232295039799800f, - 0.805031331142963660f, 0.591996694962040990f, 0.805940390571176280f, - 0.590759701858874280f, 0.806847553543799220f, 0.589521318641063940f, - 0.807752817926190360f, 0.588281548222645330f, 0.808656181588174980f, - 0.587040393520918080f, 0.809557642404051260f, 0.585797857456438860f, - 0.810457198252594770f, 0.584553942953015330f, 0.811354847017063730f, - 0.583308652937698290f, 0.812250586585203880f, 0.582061990340775550f, - 0.813144414849253590f, 0.580813958095764530f, 0.814036329705948300f, - 0.579564559139405740f, 0.814926329056526620f, 0.578313796411655590f, - 0.815814410806733780f, 0.577061672855679550f, 0.816700572866827850f, - 0.575808191417845340f, 0.817584813151583710f, 0.574553355047715760f, - 0.818467129580298660f, 0.573297166698042320f, 0.819347520076796900f, - 0.572039629324757050f, 0.820225982569434690f, 0.570780745886967370f, - 0.821102514991104650f, 0.569520519346947250f, 0.821977115279241550f, - 0.568258952670131490f, 0.822849781375826320f, 0.566996048825108680f, - 0.823720511227391320f, 0.565731810783613230f, 0.824589302785025290f, - 0.564466241520519500f, 0.825456154004377440f, 0.563199344013834090f, - 0.826321062845663420f, 0.561931121244689470f, 0.827184027273669020f, - 0.560661576197336030f, 0.828045045257755800f, 0.559390711859136140f, - 0.828904114771864870f, 0.558118531220556100f, 0.829761233794523050f, - 0.556845037275160100f, 0.830616400308846200f, 0.555570233019602290f, - 0.831469612302545240f, 0.554294121453620110f, 0.832320867767929680f, - 0.553016705580027580f, 0.833170164701913190f, 0.551737988404707450f, - 0.834017501106018130f, 0.550457972936604810f, 0.834862874986380010f, - 0.549176662187719770f, 0.835706284353752600f, 0.547894059173100190f, - 0.836547727223511890f, 0.546610166910834860f, 0.837387201615661940f, - 0.545324988422046460f, 0.838224705554837970f, 0.544038526730883930f, - 0.839060237070312630f, 0.542750784864516000f, 0.839893794195999410f, - 0.541461765853123560f, 0.840725374970458070f, 0.540171472729892970f, - 0.841554977436898330f, 0.538879908531008420f, 0.842382599643185960f, - 0.537587076295645510f, 0.843208239641845440f, 0.536292979065963180f, - 0.844031895490066410f, 0.534997619887097260f, 0.844853565249707010f, - 0.533701001807152960f, 0.845673246987299070f, 0.532403127877198010f, - 0.846490938774052020f, 0.531104001151255000f, 0.847306638685858320f, - 0.529803624686294830f, 0.848120344803297120f, 0.528502001542228480f, - 0.848932055211639610f, 0.527199134781901390f, 0.849741768000852440f, - 0.525895027471084740f, 0.850549481265603370f, 0.524589682678468840f, - 0.851355193105265200f, 0.523283103475656430f, 0.852158901623919830f, - 0.521975292937154390f, 0.852960604930363630f, 0.520666254140367270f, - 0.853760301138111300f, 0.519355990165589530f, 0.854557988365400530f, - 0.518044504095999340f, 0.855353664735196030f, 0.516731799017649980f, - 0.856147328375194470f, 0.515417878019463150f, 0.856938977417828650f, - 0.514102744193221660f, 0.857728610000272120f, 0.512786400633563070f, - 0.858516224264442740f, 0.511468850437970520f, 0.859301818357008360f, - 0.510150096706766700f, 0.860085390429390140f, 0.508830142543106990f, - 0.860866938637767310f, 0.507508991052970870f, 0.861646461143081300f, - 0.506186645345155450f, 0.862423956111040500f, 0.504863108531267480f, - 0.863199421712124160f, 0.503538383725717580f, 0.863972856121586700f, - 0.502212474045710900f, 0.864744257519462380f, 0.500885382611240940f, - 0.865513624090568980f, 0.499557112545081890f, 0.866280954024512990f, - 0.498227666972781870f, 0.867046245515692650f, 0.496897049022654640f, - 0.867809496763303210f, 0.495565261825772490f, 0.868570705971340900f, - 0.494232308515959730f, 0.869329871348606730f, 0.492898192229784090f, - 0.870086991108711350f, 0.491562916106550060f, 0.870842063470078860f, - 0.490226483288291100f, 0.871595086655951090f, 0.488888896919763230f, - 0.872346058894391540f, 0.487550160148436050f, 0.873094978418290090f, - 0.486210276124486530f, 0.873841843465366750f, 0.484869248000791120f, - 0.874586652278176110f, 0.483527078932918740f, 0.875329403104110780f, - 0.482183772079122830f, 0.876070094195406600f, 0.480839330600333900f, - 0.876808723809145760f, 0.479493757660153010f, 0.877545290207261240f, - 0.478147056424843120f, 0.878279791656541460f, 0.476799230063322250f, - 0.879012226428633410f, 0.475450281747155870f, 0.879742592800047410f, - 0.474100214650550020f, 0.880470889052160750f, 0.472749031950342900f, - 0.881197113471221980f, 0.471396736825997810f, 0.881921264348354940f, - 0.470043332459595620f, 0.882643339979562790f, 0.468688822035827960f, - 0.883363338665731580f, 0.467333208741988530f, 0.884081258712634990f, - 0.465976495767966130f, 0.884797098430937790f, 0.464618686306237820f, - 0.885510856136199950f, 0.463259783551860260f, 0.886222530148880640f, - 0.461899790702462840f, 0.886932118794342080f, 0.460538710958240010f, - 0.887639620402853930f, 0.459176547521944150f, 0.888345033309596240f, - 0.457813303598877290f, 0.889048355854664570f, 0.456448982396883860f, - 0.889749586383072890f, 0.455083587126343840f, 0.890448723244757880f, - 0.453717121000163930f, 0.891145764794583180f, 0.452349587233771000f, - 0.891840709392342720f, 0.450980989045103810f, 0.892533555402764690f, - 0.449611329654606600f, 0.893224301195515320f, 0.448240612285220000f, - 0.893912945145203250f, 0.446868840162374330f, 0.894599485631382580f, - 0.445496016513981740f, 0.895283921038557580f, 0.444122144570429260f, - 0.895966249756185110f, 0.442747227564570130f, 0.896646470178680150f, - 0.441371268731716620f, 0.897324580705418320f, 0.439994271309633260f, - 0.898000579740739880f, 0.438616238538527710f, 0.898674465693953820f, - 0.437237173661044200f, 0.899346236979341460f, 0.435857079922255470f, - 0.900015892016160280f, 0.434475960569655710f, 0.900683429228646860f, - 0.433093818853152010f, 0.901348847046022030f, 0.431710658025057370f, - 0.902012143902493070f, 0.430326481340082610f, 0.902673318237258830f, - 0.428941292055329550f, 0.903332368494511820f, 0.427555093430282200f, - 0.903989293123443340f, 0.426167888726799620f, 0.904644090578246240f, - 0.424779681209108810f, 0.905296759318118820f, 0.423390474143796100f, - 0.905947297807268460f, 0.422000270799799790f, 0.906595704514915330f, - 0.420609074448402510f, 0.907241977915295930f, 0.419216888363223960f, - 0.907886116487666150f, 0.417823715820212380f, 0.908528118716306120f, - 0.416429560097637320f, 0.909167983090522270f, 0.415034424476081630f, - 0.909805708104652220f, 0.413638312238434560f, 0.910441292258067140f, - 0.412241226669883000f, 0.911074734055176250f, 0.410843171057903910f, - 0.911706032005429880f, 0.409444148692257590f, 0.912335184623322750f, - 0.408044162864978740f, 0.912962190428398100f, 0.406643216870369140f, - 0.913587047945250810f, 0.405241314004989860f, 0.914209755703530690f, - 0.403838457567654130f, 0.914830312237946090f, 0.402434650859418540f, - 0.915448716088267830f, 0.401029897183575790f, 0.916064965799331610f, - 0.399624199845646790f, 0.916679059921042700f, 0.398217562153373620f, - 0.917290997008377910f, 0.396809987416710420f, 0.917900775621390390f, - 0.395401478947816300f, 0.918508394325212250f, 0.393992040061048100f, - 0.919113851690057770f, 0.392581674072951530f, 0.919717146291227360f, - 0.391170384302253980f, 0.920318276709110480f, 0.389758174069856410f, - 0.920917241529189520f, 0.388345046698826300f, 0.921514039342041900f, - 0.386931005514388690f, 0.922108668743345070f, 0.385516053843919020f, - 0.922701128333878520f, 0.384100195016935040f, 0.923291416719527640f, - 0.382683432365089840f, 0.923879532511286740f, 0.381265769222162490f, - 0.924465474325262600f, 0.379847208924051110f, 0.925049240782677580f, - 0.378427754808765620f, 0.925630830509872720f, 0.377007410216418310f, - 0.926210242138311270f, 0.375586178489217330f, 0.926787474304581750f, - 0.374164062971457990f, 0.927362525650401110f, 0.372741067009515810f, - 0.927935394822617890f, 0.371317193951837600f, 0.928506080473215480f, - 0.369892447148934270f, 0.929074581259315750f, 0.368466829953372320f, - 0.929640895843181330f, 0.367040345719767240f, 0.930205022892219070f, - 0.365612997804773960f, 0.930766961078983710f, 0.364184789567079840f, - 0.931326709081180430f, 0.362755724367397230f, 0.931884265581668150f, - 0.361325805568454340f, 0.932439629268462360f, 0.359895036534988280f, - 0.932992798834738850f, 0.358463420633736540f, 0.933543772978836170f, - 0.357030961233430030f, 0.934092550404258870f, 0.355597661704783960f, - 0.934639129819680780f, 0.354163525420490510f, 0.935183509938947500f, - 0.352728555755210730f, 0.935725689481080370f, 0.351292756085567150f, - 0.936265667170278260f, 0.349856129790135030f, 0.936803441735921560f, - 0.348418680249434510f, 0.937339011912574960f, 0.346980410845923680f, - 0.937872376439989890f, 0.345541324963989150f, 0.938403534063108060f, - 0.344101425989938980f, 0.938932483532064490f, 0.342660717311994380f, - 0.939459223602189920f, 0.341219202320282410f, 0.939983753034013940f, - 0.339776884406826960f, 0.940506070593268300f, 0.338333766965541290f, - 0.941026175050889260f, 0.336889853392220050f, 0.941544065183020810f, - 0.335445147084531660f, 0.942059739771017310f, 0.333999651442009490f, - 0.942573197601446870f, 0.332553369866044220f, 0.943084437466093490f, - 0.331106305759876430f, 0.943593458161960390f, 0.329658462528587550f, - 0.944100258491272660f, 0.328209843579092660f, 0.944604837261480260f, - 0.326760452320131790f, 0.945107193285260610f, 0.325310292162262980f, - 0.945607325380521280f, 0.323859366517852960f, 0.946105232370403340f, - 0.322407678801070020f, 0.946600913083283530f, 0.320955232427875210f, - 0.947094366352777220f, 0.319502030816015750f, 0.947585591017741090f, - 0.318048077385015060f, 0.948074585922276230f, 0.316593375556165850f, - 0.948561349915730270f, 0.315137928752522440f, 0.949045881852700560f, - 0.313681740398891570f, 0.949528180593036670f, 0.312224813921825050f, - 0.950008245001843000f, 0.310767152749611470f, 0.950486073949481700f, - 0.309308760312268780f, 0.950961666311575080f, 0.307849640041534980f, - 0.951435020969008340f, 0.306389795370861080f, 0.951906136807932230f, - 0.304929229735402430f, 0.952375012719765880f, 0.303467946572011370f, - 0.952841647601198720f, 0.302005949319228200f, 0.953306040354193750f, - 0.300543241417273400f, 0.953768189885990330f, 0.299079826308040480f, - 0.954228095109105670f, 0.297615707435086310f, 0.954685754941338340f, - 0.296150888243623960f, 0.955141168305770670f, 0.294685372180514330f, - 0.955594334130771110f, 0.293219162694258680f, 0.956045251349996410f, - 0.291752263234989370f, 0.956493918902394990f, 0.290284677254462330f, - 0.956940335732208940f, 0.288816408206049480f, 0.957384500788975860f, - 0.287347459544729570f, 0.957826413027532910f, 0.285877834727080730f, - 0.958266071408017670f, 0.284407537211271820f, 0.958703474895871600f, - 0.282936570457055390f, 0.959138622461841890f, 0.281464937925758050f, - 0.959571513081984520f, 0.279992643080273380f, 0.960002145737665850f, - 0.278519689385053060f, 0.960430519415565790f, 0.277046080306099950f, - 0.960856633107679660f, 0.275571819310958250f, 0.961280485811320640f, - 0.274096909868706330f, 0.961702076529122540f, 0.272621355449948980f, - 0.962121404269041580f, 0.271145159526808070f, 0.962538468044359160f, - 0.269668325572915200f, 0.962953266873683880f, 0.268190857063403180f, - 0.963365799780954050f, 0.266712757474898420f, 0.963776065795439840f, - 0.265234030285511900f, 0.964184063951745720f, 0.263754678974831510f, - 0.964589793289812650f, 0.262274707023913590f, 0.964993252854920320f, - 0.260794117915275570f, 0.965394441697689400f, 0.259312915132886350f, - 0.965793358874083570f, 0.257831102162158930f, 0.966190003445412620f, - 0.256348682489942910f, 0.966584374478333120f, 0.254865659604514630f, - 0.966976471044852070f, 0.253382036995570270f, 0.967366292222328510f, - 0.251897818154216910f, 0.967753837093475510f, 0.250413006572965280f, - 0.968139104746362330f, 0.248927605745720260f, 0.968522094274417270f, - 0.247441619167773440f, 0.968902804776428870f, 0.245955050335794590f, - 0.969281235356548530f, 0.244467902747824210f, 0.969657385124292450f, - 0.242980179903263980f, 0.970031253194543970f, 0.241491885302869300f, - 0.970402838687555500f, 0.240003022448741500f, 0.970772140728950350f, - 0.238513594844318500f, 0.971139158449725090f, 0.237023605994367340f, - 0.971503890986251780f, 0.235533059404975460f, 0.971866337480279400f, - 0.234041958583543460f, 0.972226497078936270f, 0.232550307038775330f, - 0.972584368934732210f, 0.231058108280671280f, 0.972939952205560070f, - 0.229565365820518870f, 0.973293246054698250f, 0.228072083170885790f, - 0.973644249650811870f, 0.226578263845610110f, 0.973992962167955830f, - 0.225083911359792780f, 0.974339382785575860f, 0.223589029229790020f, - 0.974683510688510670f, 0.222093620973203590f, 0.975025345066994120f, - 0.220597690108873650f, 0.975364885116656870f, 0.219101240156869770f, - 0.975702130038528570f, 0.217604274638483670f, 0.976037079039039020f, - 0.216106797076219600f, 0.976369731330021140f, 0.214608810993786920f, - 0.976700086128711840f, 0.213110319916091360f, 0.977028142657754390f, - 0.211611327369227610f, 0.977353900145199960f, 0.210111836880469720f, - 0.977677357824509930f, 0.208611851978263460f, 0.977998514934557140f, - 0.207111376192218560f, 0.978317370719627650f, 0.205610413053099320f, - 0.978633924429423100f, 0.204108966092817010f, 0.978948175319062200f, - 0.202607038844421110f, 0.979260122649082020f, 0.201104634842091960f, - 0.979569765685440520f, 0.199601757621131050f, 0.979877103699517640f, - 0.198098410717953730f, 0.980182135968117320f, 0.196594597670080220f, - 0.980484861773469380f, 0.195090322016128330f, 0.980785280403230430f, - 0.193585587295803750f, 0.981083391150486590f, 0.192080397049892380f, - 0.981379193313754560f, 0.190574754820252800f, 0.981672686196983110f, - 0.189068664149806280f, 0.981963869109555240f, 0.187562128582529740f, - 0.982252741366289370f, 0.186055151663446630f, 0.982539302287441240f, - 0.184547736938619640f, 0.982823551198705240f, 0.183039887955141060f, - 0.983105487431216290f, 0.181531608261125130f, 0.983385110321551180f, - 0.180022901405699510f, 0.983662419211730250f, 0.178513770938997590f, - 0.983937413449218920f, 0.177004220412148860f, 0.984210092386929030f, - 0.175494253377271400f, 0.984480455383220930f, 0.173983873387463850f, - 0.984748501801904210f, 0.172473083996796030f, 0.985014231012239840f, - 0.170961888760301360f, 0.985277642388941220f, 0.169450291233967930f, - 0.985538735312176060f, 0.167938294974731230f, 0.985797509167567370f, - 0.166425903540464220f, 0.986053963346195440f, 0.164913120489970090f, - 0.986308097244598670f, 0.163399949382973230f, 0.986559910264775410f, - 0.161886393780111910f, 0.986809401814185420f, 0.160372457242928400f, - 0.987056571305750970f, 0.158858143333861390f, 0.987301418157858430f, - 0.157343455616238280f, 0.987543941794359230f, 0.155828397654265320f, - 0.987784141644572180f, 0.154312973013020240f, 0.988022017143283530f, - 0.152797185258443410f, 0.988257567730749460f, 0.151281037957330250f, - 0.988490792852696590f, 0.149764534677321620f, 0.988721691960323780f, - 0.148247678986896200f, 0.988950264510302990f, 0.146730474455361750f, - 0.989176509964781010f, 0.145212924652847520f, 0.989400427791380380f, - 0.143695033150294580f, 0.989622017463200780f, 0.142176803519448000f, - 0.989841278458820530f, 0.140658239332849240f, 0.990058210262297120f, - 0.139139344163826280f, 0.990272812363169110f, 0.137620121586486180f, - 0.990485084256456980f, 0.136100575175706200f, 0.990695025442664630f, - 0.134580708507126220f, 0.990902635427780010f, 0.133060525157139180f, - 0.991107913723276780f, 0.131540028702883280f, 0.991310859846115440f, - 0.130019222722233350f, 0.991511473318743900f, 0.128498110793793220f, - 0.991709753669099530f, 0.126976696496885980f, 0.991905700430609330f, - 0.125454983411546210f, 0.992099313142191800f, 0.123932975118512200f, - 0.992290591348257370f, 0.122410675199216280f, 0.992479534598709970f, - 0.120888087235777220f, 0.992666142448948020f, 0.119365214810991350f, - 0.992850414459865100f, 0.117842061508325020f, 0.993032350197851410f, - 0.116318630911904880f, 0.993211949234794500f, 0.114794926606510250f, - 0.993389211148080650f, 0.113270952177564360f, 0.993564135520595300f, - 0.111746711211126660f, 0.993736721940724600f, 0.110222207293883180f, - 0.993906970002356060f, 0.108697444013138670f, 0.994074879304879370f, - 0.107172424956808870f, 0.994240449453187900f, 0.105647153713410700f, - 0.994403680057679100f, 0.104121633872054730f, 0.994564570734255420f, - 0.102595869022436280f, 0.994723121104325700f, 0.101069862754827880f, - 0.994879330794805620f, 0.099543618660069444f, 0.995033199438118630f, - 0.098017140329560770f, 0.995184726672196820f, 0.096490431355252607f, - 0.995333912140482280f, 0.094963495329639061f, 0.995480755491926940f, - 0.093436335845747912f, 0.995625256380994310f, 0.091908956497132696f, - 0.995767414467659820f, 0.090381360877865011f, 0.995907229417411720f, - 0.088853552582524684f, 0.996044700901251970f, 0.087325535206192226f, - 0.996179828595696870f, 0.085797312344439880f, 0.996312612182778000f, - 0.084268887593324127f, 0.996443051350042630f, 0.082740264549375803f, - 0.996571145790554840f, 0.081211446809592386f, 0.996696895202896060f, - 0.079682437971430126f, 0.996820299291165670f, 0.078153241632794315f, - 0.996941357764982160f, 0.076623861392031617f, 0.997060070339482960f, - 0.075094300847921291f, 0.997176436735326190f, 0.073564563599667454f, - 0.997290456678690210f, 0.072034653246889416f, 0.997402129901275300f, - 0.070504573389614009f, 0.997511456140303450f, 0.068974327628266732f, - 0.997618435138519550f, 0.067443919563664106f, 0.997723066644191640f, - 0.065913352797003930f, 0.997825350411111640f, 0.064382630929857410f, - 0.997925286198596000f, 0.062851757564161420f, 0.998022873771486240f, - 0.061320736302208648f, 0.998118112900149180f, 0.059789570746640007f, - 0.998211003360478190f, 0.058258264500435732f, 0.998301544933892890f, - 0.056726821166907783f, 0.998389737407340160f, 0.055195244349690031f, - 0.998475580573294770f, 0.053663537652730679f, 0.998559074229759310f, - 0.052131704680283317f, 0.998640218180265270f, 0.050599749036899337f, - 0.998719012233872940f, 0.049067674327418126f, 0.998795456205172410f, - 0.047535484156959261f, 0.998869549914283560f, 0.046003182130914644f, - 0.998941293186856870f, 0.044470771854938744f, 0.999010685854073380f, - 0.042938256934940959f, 0.999077727752645360f, 0.041405640977076712f, - 0.999142418724816910f, 0.039872927587739845f, 0.999204758618363890f, - 0.038340120373552791f, 0.999264747286594420f, 0.036807222941358991f, - 0.999322384588349540f, 0.035274238898213947f, 0.999377670388002850f, - 0.033741171851377642f, 0.999430604555461730f, 0.032208025408304704f, - 0.999481186966166950f, 0.030674803176636581f, 0.999529417501093140f, - 0.029141508764193740f, 0.999575296046749220f, 0.027608145778965820f, - 0.999618822495178640f, 0.026074717829104040f, 0.999659996743959220f, - 0.024541228522912264f, 0.999698818696204250f, 0.023007681468839410f, - 0.999735288260561680f, 0.021474080275469605f, 0.999769405351215280f, - 0.019940428551514598f, 0.999801169887884260f, 0.018406729905804820f, - 0.999830581795823400f, 0.016872987947281773f, 0.999857641005823860f, - 0.015339206284988220f, 0.999882347454212560f, 0.013805388528060349f, - 0.999904701082852900f, 0.012271538285719944f, 0.999924701839144500f, - 0.010737659167264572f, 0.999942349676023910f, 0.009203754782059960f, - 0.999957644551963900f, 0.007669828739531077f, 0.999970586430974140f, - 0.006135884649154515f, 0.999981175282601110f, 0.004601926120448672f, - 0.999989411081928400f, 0.003067956762966138f, 0.999995293809576190f, - 0.001533980186284766f, 0.999998823451701880f, 0.000000000000000061f, - 1.000000000000000000f, -0.001533980186284644f, 0.999998823451701880f, - -0.003067956762966016f, 0.999995293809576190f, -0.004601926120448550f, - 0.999989411081928400f, -0.006135884649154393f, 0.999981175282601110f, - -0.007669828739530955f, 0.999970586430974140f, -0.009203754782059837f, - 0.999957644551963900f, -0.010737659167264449f, 0.999942349676023910f, - -0.012271538285719823f, 0.999924701839144500f, -0.013805388528060226f, - 0.999904701082852900f, -0.015339206284988098f, 0.999882347454212560f, - -0.016872987947281651f, 0.999857641005823860f, -0.018406729905804695f, - 0.999830581795823400f, -0.019940428551514476f, 0.999801169887884260f, - -0.021474080275469484f, 0.999769405351215280f, -0.023007681468839289f, - 0.999735288260561680f, -0.024541228522912142f, 0.999698818696204250f, - -0.026074717829103915f, 0.999659996743959220f, -0.027608145778965698f, - 0.999618822495178640f, -0.029141508764193618f, 0.999575296046749220f, - -0.030674803176636459f, 0.999529417501093140f, -0.032208025408304579f, - 0.999481186966166950f, -0.033741171851377517f, 0.999430604555461730f, - -0.035274238898213822f, 0.999377670388002850f, -0.036807222941358866f, - 0.999322384588349540f, -0.038340120373552666f, 0.999264747286594420f, - -0.039872927587739727f, 0.999204758618363890f, -0.041405640977076594f, - 0.999142418724816910f, -0.042938256934940834f, 0.999077727752645360f, - -0.044470771854938619f, 0.999010685854073380f, -0.046003182130914519f, - 0.998941293186856870f, -0.047535484156959136f, 0.998869549914283560f, - -0.049067674327418008f, 0.998795456205172410f, -0.050599749036899212f, - 0.998719012233872940f, -0.052131704680283192f, 0.998640218180265270f, - -0.053663537652730554f, 0.998559074229759310f, -0.055195244349689913f, - 0.998475580573294770f, -0.056726821166907658f, 0.998389737407340160f, - -0.058258264500435607f, 0.998301544933892890f, -0.059789570746639882f, - 0.998211003360478190f, -0.061320736302208530f, 0.998118112900149180f, - -0.062851757564161309f, 0.998022873771486240f, -0.064382630929857285f, - 0.997925286198596000f, -0.065913352797003805f, 0.997825350411111640f, - -0.067443919563663982f, 0.997723066644191640f, -0.068974327628266607f, - 0.997618435138519550f, -0.070504573389613898f, 0.997511456140303450f, - -0.072034653246889291f, 0.997402129901275300f, -0.073564563599667329f, - 0.997290456678690210f, -0.075094300847921167f, 0.997176436735326190f, - -0.076623861392031506f, 0.997060070339482960f, -0.078153241632794190f, - 0.996941357764982160f, -0.079682437971430015f, 0.996820299291165780f, - -0.081211446809592261f, 0.996696895202896060f, -0.082740264549375678f, - 0.996571145790554840f, -0.084268887593324002f, 0.996443051350042630f, - -0.085797312344439755f, 0.996312612182778000f, -0.087325535206192101f, - 0.996179828595696870f, -0.088853552582524559f, 0.996044700901251970f, - -0.090381360877864886f, 0.995907229417411720f, -0.091908956497132571f, - 0.995767414467659820f, -0.093436335845747787f, 0.995625256380994310f, - -0.094963495329638950f, 0.995480755491926940f, -0.096490431355252482f, - 0.995333912140482280f, -0.098017140329560645f, 0.995184726672196930f, - -0.099543618660069319f, 0.995033199438118630f, -0.101069862754827750f, - 0.994879330794805620f, -0.102595869022436160f, 0.994723121104325700f, - -0.104121633872054600f, 0.994564570734255420f, -0.105647153713410570f, - 0.994403680057679100f, -0.107172424956808760f, 0.994240449453187900f, - -0.108697444013138560f, 0.994074879304879480f, -0.110222207293883060f, - 0.993906970002356060f, -0.111746711211126550f, 0.993736721940724600f, - -0.113270952177564240f, 0.993564135520595300f, -0.114794926606510130f, - 0.993389211148080650f, -0.116318630911904750f, 0.993211949234794500f, - -0.117842061508324890f, 0.993032350197851410f, -0.119365214810991230f, - 0.992850414459865100f, -0.120888087235777100f, 0.992666142448948020f, - -0.122410675199216150f, 0.992479534598709970f, -0.123932975118512080f, - 0.992290591348257370f, -0.125454983411546070f, 0.992099313142191800f, - -0.126976696496885870f, 0.991905700430609330f, -0.128498110793793110f, - 0.991709753669099530f, -0.130019222722233240f, 0.991511473318744010f, - -0.131540028702883140f, 0.991310859846115440f, -0.133060525157139040f, - 0.991107913723276890f, -0.134580708507126110f, 0.990902635427780010f, - -0.136100575175706060f, 0.990695025442664630f, -0.137620121586486070f, - 0.990485084256456980f, -0.139139344163826170f, 0.990272812363169110f, - -0.140658239332849130f, 0.990058210262297120f, -0.142176803519447890f, - 0.989841278458820530f, -0.143695033150294440f, 0.989622017463200890f, - -0.145212924652847410f, 0.989400427791380380f, -0.146730474455361640f, - 0.989176509964781010f, -0.148247678986896090f, 0.988950264510302990f, - -0.149764534677321510f, 0.988721691960323780f, -0.151281037957330140f, - 0.988490792852696700f, -0.152797185258443300f, 0.988257567730749460f, - -0.154312973013020130f, 0.988022017143283530f, -0.155828397654265200f, - 0.987784141644572180f, -0.157343455616238160f, 0.987543941794359340f, - -0.158858143333861280f, 0.987301418157858430f, -0.160372457242928260f, - 0.987056571305750970f, -0.161886393780111770f, 0.986809401814185530f, - -0.163399949382973110f, 0.986559910264775520f, -0.164913120489969950f, - 0.986308097244598670f, -0.166425903540464100f, 0.986053963346195440f, - -0.167938294974731090f, 0.985797509167567480f, -0.169450291233967820f, - 0.985538735312176060f, -0.170961888760301240f, 0.985277642388941220f, - -0.172473083996795920f, 0.985014231012239840f, -0.173983873387463710f, - 0.984748501801904210f, -0.175494253377271260f, 0.984480455383220930f, - -0.177004220412148750f, 0.984210092386929030f, -0.178513770938997450f, - 0.983937413449218920f, -0.180022901405699400f, 0.983662419211730250f, - -0.181531608261125020f, 0.983385110321551180f, -0.183039887955140920f, - 0.983105487431216290f, -0.184547736938619530f, 0.982823551198705350f, - -0.186055151663446490f, 0.982539302287441240f, -0.187562128582529600f, - 0.982252741366289370f, -0.189068664149806160f, 0.981963869109555240f, - -0.190574754820252660f, 0.981672686196983110f, -0.192080397049892270f, - 0.981379193313754560f, -0.193585587295803610f, 0.981083391150486710f, - -0.195090322016128190f, 0.980785280403230430f, -0.196594597670080110f, - 0.980484861773469380f, -0.198098410717953620f, 0.980182135968117430f, - -0.199601757621130940f, 0.979877103699517640f, -0.201104634842091820f, - 0.979569765685440520f, -0.202607038844420970f, 0.979260122649082130f, - -0.204108966092816900f, 0.978948175319062200f, -0.205610413053099210f, - 0.978633924429423210f, -0.207111376192218450f, 0.978317370719627650f, - -0.208611851978263320f, 0.977998514934557140f, -0.210111836880469610f, - 0.977677357824509930f, -0.211611327369227500f, 0.977353900145200070f, - -0.213110319916091250f, 0.977028142657754390f, -0.214608810993786810f, - 0.976700086128711840f, -0.216106797076219490f, 0.976369731330021140f, - -0.217604274638483560f, 0.976037079039039130f, -0.219101240156869660f, - 0.975702130038528570f, -0.220597690108873530f, 0.975364885116656980f, - -0.222093620973203480f, 0.975025345066994120f, -0.223589029229789880f, - 0.974683510688510670f, -0.225083911359792670f, 0.974339382785575860f, - -0.226578263845610000f, 0.973992962167955830f, -0.228072083170885680f, - 0.973644249650811980f, -0.229565365820518760f, 0.973293246054698250f, - -0.231058108280671140f, 0.972939952205560180f, -0.232550307038775220f, - 0.972584368934732210f, -0.234041958583543320f, 0.972226497078936380f, - -0.235533059404975350f, 0.971866337480279400f, -0.237023605994367230f, - 0.971503890986251780f, -0.238513594844318390f, 0.971139158449725090f, - -0.240003022448741390f, 0.970772140728950350f, -0.241491885302869160f, - 0.970402838687555500f, -0.242980179903263870f, 0.970031253194543970f, - -0.244467902747824100f, 0.969657385124292450f, -0.245955050335794480f, - 0.969281235356548530f, -0.247441619167773320f, 0.968902804776428870f, - -0.248927605745720120f, 0.968522094274417380f, -0.250413006572965170f, - 0.968139104746362440f, -0.251897818154216800f, 0.967753837093475510f, - -0.253382036995570160f, 0.967366292222328510f, -0.254865659604514520f, - 0.966976471044852070f, -0.256348682489942800f, 0.966584374478333120f, - -0.257831102162158820f, 0.966190003445412620f, -0.259312915132886230f, - 0.965793358874083680f, -0.260794117915275460f, 0.965394441697689400f, - -0.262274707023913480f, 0.964993252854920440f, -0.263754678974831400f, - 0.964589793289812760f, -0.265234030285511790f, 0.964184063951745830f, - -0.266712757474898310f, 0.963776065795439840f, -0.268190857063403010f, - 0.963365799780954050f, -0.269668325572915090f, 0.962953266873683880f, - -0.271145159526807960f, 0.962538468044359160f, -0.272621355449948870f, - 0.962121404269041580f, -0.274096909868706220f, 0.961702076529122540f, - -0.275571819310958140f, 0.961280485811320640f, -0.277046080306099840f, - 0.960856633107679660f, -0.278519689385052950f, 0.960430519415565900f, - -0.279992643080273270f, 0.960002145737665850f, -0.281464937925757940f, - 0.959571513081984520f, -0.282936570457055280f, 0.959138622461842010f, - -0.284407537211271710f, 0.958703474895871600f, -0.285877834727080620f, - 0.958266071408017670f, -0.287347459544729460f, 0.957826413027532910f, - -0.288816408206049370f, 0.957384500788975970f, -0.290284677254462160f, - 0.956940335732208940f, -0.291752263234989260f, 0.956493918902395100f, - -0.293219162694258570f, 0.956045251349996520f, -0.294685372180514220f, - 0.955594334130771110f, -0.296150888243623840f, 0.955141168305770670f, - -0.297615707435086200f, 0.954685754941338340f, -0.299079826308040360f, - 0.954228095109105670f, -0.300543241417273290f, 0.953768189885990330f, - -0.302005949319228080f, 0.953306040354193860f, -0.303467946572011260f, - 0.952841647601198720f, -0.304929229735402260f, 0.952375012719765880f, - -0.306389795370860970f, 0.951906136807932350f, -0.307849640041534870f, - 0.951435020969008340f, -0.309308760312268620f, 0.950961666311575080f, - -0.310767152749611360f, 0.950486073949481810f, -0.312224813921824940f, - 0.950008245001843000f, -0.313681740398891410f, 0.949528180593036670f, - -0.315137928752522330f, 0.949045881852700670f, -0.316593375556165730f, - 0.948561349915730380f, -0.318048077385014950f, 0.948074585922276230f, - -0.319502030816015640f, 0.947585591017741200f, -0.320955232427875100f, - 0.947094366352777220f, -0.322407678801069850f, 0.946600913083283530f, - -0.323859366517852850f, 0.946105232370403450f, -0.325310292162262870f, - 0.945607325380521390f, -0.326760452320131620f, 0.945107193285260610f, - -0.328209843579092550f, 0.944604837261480260f, -0.329658462528587440f, - 0.944100258491272660f, -0.331106305759876320f, 0.943593458161960390f, - -0.332553369866044060f, 0.943084437466093490f, -0.333999651442009380f, - 0.942573197601446870f, -0.335445147084531550f, 0.942059739771017420f, - -0.336889853392219940f, 0.941544065183020810f, -0.338333766965541180f, - 0.941026175050889260f, -0.339776884406826850f, 0.940506070593268300f, - -0.341219202320282300f, 0.939983753034014050f, -0.342660717311994270f, - 0.939459223602189920f, -0.344101425989938870f, 0.938932483532064490f, - -0.345541324963989040f, 0.938403534063108170f, -0.346980410845923570f, - 0.937872376439989890f, -0.348418680249434400f, 0.937339011912574960f, - -0.349856129790134920f, 0.936803441735921560f, -0.351292756085567040f, - 0.936265667170278260f, -0.352728555755210620f, 0.935725689481080370f, - -0.354163525420490400f, 0.935183509938947610f, -0.355597661704783850f, - 0.934639129819680780f, -0.357030961233429920f, 0.934092550404258980f, - -0.358463420633736430f, 0.933543772978836280f, -0.359895036534988170f, - 0.932992798834738850f, -0.361325805568454230f, 0.932439629268462360f, - -0.362755724367397110f, 0.931884265581668150f, -0.364184789567079730f, - 0.931326709081180540f, -0.365612997804773850f, 0.930766961078983710f, - -0.367040345719767120f, 0.930205022892219070f, -0.368466829953372210f, - 0.929640895843181330f, -0.369892447148934160f, 0.929074581259315750f, - -0.371317193951837490f, 0.928506080473215590f, -0.372741067009515700f, - 0.927935394822617890f, -0.374164062971457880f, 0.927362525650401110f, - -0.375586178489217220f, 0.926787474304581750f, -0.377007410216418200f, - 0.926210242138311380f, -0.378427754808765450f, 0.925630830509872830f, - -0.379847208924050990f, 0.925049240782677700f, -0.381265769222162380f, - 0.924465474325262600f, -0.382683432365089730f, 0.923879532511286740f, - -0.384100195016934930f, 0.923291416719527750f, -0.385516053843918900f, - 0.922701128333878520f, -0.386931005514388580f, 0.922108668743345180f, - -0.388345046698826190f, 0.921514039342042010f, -0.389758174069856300f, - 0.920917241529189520f, -0.391170384302253870f, 0.920318276709110590f, - -0.392581674072951410f, 0.919717146291227360f, -0.393992040061047990f, - 0.919113851690057770f, -0.395401478947816190f, 0.918508394325212250f, - -0.396809987416710310f, 0.917900775621390500f, -0.398217562153373510f, - 0.917290997008378020f, -0.399624199845646680f, 0.916679059921042700f, - -0.401029897183575680f, 0.916064965799331720f, -0.402434650859418430f, - 0.915448716088267830f, -0.403838457567654020f, 0.914830312237946200f, - -0.405241314004989750f, 0.914209755703530690f, -0.406643216870369030f, - 0.913587047945250810f, -0.408044162864978630f, 0.912962190428398210f, - -0.409444148692257480f, 0.912335184623322860f, -0.410843171057903800f, - 0.911706032005429880f, -0.412241226669882890f, 0.911074734055176360f, - -0.413638312238434450f, 0.910441292258067250f, -0.415034424476081520f, - 0.909805708104652330f, -0.416429560097636990f, 0.909167983090522490f, - -0.417823715820212270f, 0.908528118716306120f, -0.419216888363224070f, - 0.907886116487666150f, -0.420609074448402400f, 0.907241977915295930f, - -0.422000270799799680f, 0.906595704514915330f, -0.423390474143795770f, - 0.905947297807268570f, -0.424779681209108690f, 0.905296759318118820f, - -0.426167888726799670f, 0.904644090578246130f, -0.427555093430281860f, - 0.903989293123443450f, -0.428941292055329440f, 0.903332368494511820f, - -0.430326481340082720f, 0.902673318237258830f, -0.431710658025057090f, - 0.902012143902493290f, -0.433093818853151900f, 0.901348847046022030f, - -0.434475960569655820f, 0.900683429228646860f, -0.435857079922255360f, - 0.900015892016160280f, -0.437237173661044090f, 0.899346236979341570f, - -0.438616238538527380f, 0.898674465693953930f, -0.439994271309633140f, - 0.898000579740739880f, -0.441371268731716730f, 0.897324580705418320f, - -0.442747227564569800f, 0.896646470178680270f, -0.444122144570429140f, - 0.895966249756185220f, -0.445496016513981800f, 0.895283921038557470f, - -0.446868840162373990f, 0.894599485631382810f, -0.448240612285219890f, - 0.893912945145203250f, -0.449611329654606710f, 0.893224301195515210f, - -0.450980989045103700f, 0.892533555402764690f, -0.452349587233770890f, - 0.891840709392342720f, -0.453717121000163590f, 0.891145764794583410f, - -0.455083587126343720f, 0.890448723244757990f, -0.456448982396883970f, - 0.889749586383072780f, -0.457813303598877010f, 0.889048355854664680f, - -0.459176547521944030f, 0.888345033309596350f, -0.460538710958240060f, - 0.887639620402853930f, -0.461899790702462560f, 0.886932118794342310f, - -0.463259783551860150f, 0.886222530148880640f, -0.464618686306237930f, - 0.885510856136199840f, -0.465976495767966010f, 0.884797098430937900f, - -0.467333208741988420f, 0.884081258712634990f, -0.468688822035827680f, - 0.883363338665731690f, -0.470043332459595510f, 0.882643339979562900f, - -0.471396736825997700f, 0.881921264348355050f, -0.472749031950342570f, - 0.881197113471222200f, -0.474100214650549910f, 0.880470889052160870f, - -0.475450281747155980f, 0.879742592800047410f, -0.476799230063321920f, - 0.879012226428633530f, -0.478147056424843010f, 0.878279791656541580f, - -0.479493757660153120f, 0.877545290207261240f, -0.480839330600333790f, - 0.876808723809145760f, -0.482183772079122720f, 0.876070094195406600f, - -0.483527078932918460f, 0.875329403104111000f, -0.484869248000791010f, - 0.874586652278176220f, -0.486210276124486420f, 0.873841843465366860f, - -0.487550160148435720f, 0.873094978418290200f, -0.488888896919763120f, - 0.872346058894391540f, -0.490226483288291210f, 0.871595086655950980f, - -0.491562916106549790f, 0.870842063470078980f, -0.492898192229783980f, - 0.870086991108711460f, -0.494232308515959840f, 0.869329871348606730f, - -0.495565261825772370f, 0.868570705971341010f, -0.496897049022654520f, - 0.867809496763303210f, -0.498227666972781590f, 0.867046245515692760f, - -0.499557112545081780f, 0.866280954024513110f, -0.500885382611240830f, - 0.865513624090569090f, -0.502212474045710570f, 0.864744257519462490f, - -0.503538383725717460f, 0.863972856121586810f, -0.504863108531267590f, - 0.863199421712124160f, -0.506186645345155120f, 0.862423956111040610f, - -0.507508991052970760f, 0.861646461143081300f, -0.508830142543107100f, - 0.860866938637767200f, -0.510150096706766590f, 0.860085390429390250f, - -0.511468850437970410f, 0.859301818357008360f, -0.512786400633562730f, - 0.858516224264442960f, -0.514102744193221660f, 0.857728610000272120f, - -0.515417878019463040f, 0.856938977417828760f, -0.516731799017649650f, - 0.856147328375194580f, -0.518044504095999230f, 0.855353664735196030f, - -0.519355990165589640f, 0.854557988365400530f, -0.520666254140366940f, - 0.853760301138111520f, -0.521975292937154280f, 0.852960604930363740f, - -0.523283103475656540f, 0.852158901623919720f, -0.524589682678468730f, - 0.851355193105265200f, -0.525895027471084630f, 0.850549481265603480f, - -0.527199134781901060f, 0.849741768000852660f, -0.528502001542228370f, - 0.848932055211639720f, -0.529803624686294720f, 0.848120344803297230f, - -0.531104001151254780f, 0.847306638685858540f, -0.532403127877197900f, - 0.846490938774052130f, -0.533701001807152960f, 0.845673246987299070f, - -0.534997619887097040f, 0.844853565249707230f, -0.536292979065963070f, - 0.844031895490066410f, -0.537587076295645620f, 0.843208239641845440f, - -0.538879908531008310f, 0.842382599643185960f, -0.540171472729892850f, - 0.841554977436898440f, -0.541461765853123220f, 0.840725374970458180f, - -0.542750784864515780f, 0.839893794195999630f, -0.544038526730883930f, - 0.839060237070312630f, -0.545324988422046240f, 0.838224705554838190f, - -0.546610166910834860f, 0.837387201615661940f, -0.547894059173100190f, - 0.836547727223512010f, -0.549176662187719540f, 0.835706284353752720f, - -0.550457972936604700f, 0.834862874986380120f, -0.551737988404707450f, - 0.834017501106018020f, -0.553016705580027360f, 0.833170164701913300f, - -0.554294121453620110f, 0.832320867767929680f, -0.555570233019601960f, - 0.831469612302545460f, -0.556845037275159990f, 0.830616400308846310f, - -0.558118531220556100f, 0.829761233794523050f, -0.559390711859135800f, - 0.828904114771865100f, -0.560661576197335920f, 0.828045045257755800f, - -0.561931121244689470f, 0.827184027273669130f, -0.563199344013833980f, - 0.826321062845663650f, -0.564466241520519390f, 0.825456154004377550f, - -0.565731810783613230f, 0.824589302785025180f, -0.566996048825108460f, - 0.823720511227391540f, -0.568258952670131490f, 0.822849781375826320f, - -0.569520519346947250f, 0.821977115279241440f, -0.570780745886967140f, - 0.821102514991104760f, -0.572039629324757050f, 0.820225982569434690f, - -0.573297166698041980f, 0.819347520076797120f, -0.574553355047715760f, - 0.818467129580298770f, -0.575808191417845340f, 0.817584813151583710f, - -0.577061672855679330f, 0.816700572866827960f, -0.578313796411655480f, - 0.815814410806733780f, -0.579564559139405850f, 0.814926329056526510f, - -0.580813958095764420f, 0.814036329705948520f, -0.582061990340775550f, - 0.813144414849253590f, -0.583308652937698400f, 0.812250586585203880f, - -0.584553942953015220f, 0.811354847017063840f, -0.585797857456438860f, - 0.810457198252594770f, -0.587040393520917750f, 0.809557642404051480f, - -0.588281548222645220f, 0.808656181588175090f, -0.589521318641063940f, - 0.807752817926190360f, -0.590759701858874050f, 0.806847553543799450f, - -0.591996694962040880f, 0.805940390571176390f, -0.593232295039799910f, - 0.805031331142963550f, -0.594466499184664320f, 0.804120377398265810f, - -0.595699304492433360f, 0.803207531480644940f, -0.596930708062196610f, - 0.802292795538115610f, -0.598160706996342160f, 0.801376171723140350f, - -0.599389298400564540f, 0.800457662192622820f, -0.600616479383868750f, - 0.799537269107905240f, -0.601842247058579920f, 0.798614994634760930f, - -0.603066598540348280f, 0.797690840943391040f, -0.604289530948155850f, - 0.796764810208418940f, -0.605511041404325430f, 0.795836904608883570f, - -0.606731127034524590f, 0.794907126328236900f, -0.607949784967773520f, - 0.793975477554337280f, -0.609167012336453210f, 0.793041960479443640f, - -0.610382806276309590f, 0.792106577300212280f, -0.611597163926461800f, - 0.791169330217690310f, -0.612810082429409710f, 0.790230221437310030f, - -0.614021558931038160f, 0.789289253168885870f, -0.615231590580626710f, - 0.788346427626606340f, -0.616440174530853650f, 0.787401747029031320f, - -0.617647307937803760f, 0.786455213599085880f, -0.618852987960976210f, - 0.785506829564054040f, -0.620057211763289210f, 0.784556597155575130f, - -0.621259976511087440f, 0.783604518609638310f, -0.622461279374149970f, - 0.782650596166575730f, -0.623661117525694640f, 0.781694832071059280f, - -0.624859488142386230f, 0.780737228572094600f, -0.626056388404343520f, - 0.779777787923014440f, -0.627251815495143860f, 0.778816512381476090f, - -0.628445766601832600f, 0.777853404209453150f, -0.629638238914927100f, - 0.776888465673232440f, -0.630829229628424360f, 0.775921699043407800f, - -0.632018735939808950f, 0.774953106594873930f, -0.633206755050057300f, - 0.773982690606822790f, -0.634393284163645380f, 0.773010453362737100f, - -0.635578320488556110f, 0.772036397150384520f, -0.636761861236284310f, - 0.771060524261813710f, -0.637943903621843940f, 0.770082836993348010f, - -0.639124444863775730f, 0.769103337645579590f, -0.640303482184151450f, - 0.768122028523365530f, -0.641481012808583050f, 0.767138911935820510f, - -0.642657033966226860f, 0.766153990196312920f, -0.643831542889791280f, - 0.765167265622459070f, -0.645004536815543930f, 0.764178740536116790f, - -0.646176012983316390f, 0.763188417263381270f, -0.647345968636511950f, - 0.762196298134579010f, -0.648514401022112440f, 0.761202385484261890f, - -0.649681307390683300f, 0.760206681651202310f, -0.650846684996380760f, - 0.759209188978388180f, -0.652010531096959500f, 0.758209909813015280f, - -0.653172842953776530f, 0.757208846506484680f, -0.654333617831800440f, - 0.756206001414394540f, -0.655492852999615460f, 0.755201376896536550f, - -0.656650545729428830f, 0.754194975316889280f, -0.657806693297078640f, - 0.753186799043612520f, -0.658961292982037430f, 0.752176850449042700f, - -0.660114342067420370f, 0.751165131909686590f, -0.661265837839992150f, - 0.750151645806215070f, -0.662415777590171890f, 0.749136394523459260f, - -0.663564158612039660f, 0.748119380450403710f, -0.664710978203344900f, - 0.747100605980180130f, -0.665856233665509500f, 0.746080073510064000f, - -0.666999922303637360f, 0.745057785441466060f, -0.668142041426518560f, - 0.744033744179929290f, -0.669282588346635900f, 0.743007952135121830f, - -0.670421560380173090f, 0.741980411720831070f, -0.671558954847018440f, - 0.740951125354958990f, -0.672694769070772750f, 0.739920095459516310f, - -0.673829000378756040f, 0.738887324460615220f, -0.674961646102012150f, - 0.737852814788465870f, -0.676092703575315810f, 0.736816568877370020f, - -0.677222170137180450f, 0.735778589165713480f, -0.678350043129861250f, - 0.734738878095963610f, -0.679476319899364970f, 0.733697438114660370f, - -0.680600997795453020f, 0.732654271672412820f, -0.681724074171649600f, - 0.731609381223892740f, -0.682845546385247970f, 0.730562769227827590f, - -0.683965411797315510f, 0.729514438146997010f, -0.685083667772700240f, - 0.728464390448225310f, -0.686200311680038590f, 0.727412628602375770f, - -0.687315340891759160f, 0.726359155084345900f, -0.688428752784090330f, - 0.725303972373060880f, -0.689540544737066940f, 0.724247082951466890f, - -0.690650714134534380f, 0.723188489306527570f, -0.691759258364157640f, - 0.722128193929215460f, -0.692866174817424740f, 0.721066199314508110f, - -0.693971460889653780f, 0.720002507961381770f, -0.695075113980000770f, - 0.718937122372804490f, -0.696177131491462990f, 0.717870045055731710f, - -0.697277510830886400f, 0.716801278521099650f, -0.698376249408972800f, - 0.715730825283818710f, -0.699473344640283880f, 0.714658687862768980f, - -0.700568793943248220f, 0.713584868780793750f, -0.701662594740168450f, - 0.712509370564692320f, -0.702754744457225080f, 0.711432195745216660f, - -0.703845240524484830f, 0.710353346857062420f, -0.704934080375904880f, - 0.709272826438865580f, -0.706021261449339630f, 0.708190637033195510f, - -0.707106781186547460f, 0.707106781186547570f, -0.708190637033195400f, - 0.706021261449339740f, -0.709272826438865470f, 0.704934080375905100f, - -0.710353346857062310f, 0.703845240524485050f, -0.711432195745216540f, - 0.702754744457225190f, -0.712509370564692210f, 0.701662594740168680f, - -0.713584868780793640f, 0.700568793943248340f, -0.714658687862768870f, - 0.699473344640283990f, -0.715730825283818590f, 0.698376249408972920f, - -0.716801278521099540f, 0.697277510830886520f, -0.717870045055731600f, - 0.696177131491463100f, -0.718937122372804380f, 0.695075113980000990f, - -0.720002507961381650f, 0.693971460889654000f, -0.721066199314507990f, - 0.692866174817424850f, -0.722128193929215230f, 0.691759258364157860f, - -0.723188489306527460f, 0.690650714134534600f, -0.724247082951466780f, - 0.689540544737067050f, -0.725303972373060770f, 0.688428752784090440f, - -0.726359155084345790f, 0.687315340891759270f, -0.727412628602375650f, - 0.686200311680038700f, -0.728464390448225200f, 0.685083667772700360f, - -0.729514438146996790f, 0.683965411797315630f, -0.730562769227827480f, - 0.682845546385248190f, -0.731609381223892630f, 0.681724074171649710f, - -0.732654271672412700f, 0.680600997795453240f, -0.733697438114660260f, - 0.679476319899365080f, -0.734738878095963500f, 0.678350043129861360f, - -0.735778589165713370f, 0.677222170137180560f, -0.736816568877369900f, - 0.676092703575315920f, -0.737852814788465760f, 0.674961646102012260f, - -0.738887324460615000f, 0.673829000378756150f, -0.739920095459516200f, - 0.672694769070772860f, -0.740951125354958880f, 0.671558954847018550f, - -0.741980411720830960f, 0.670421560380173200f, -0.743007952135121720f, - 0.669282588346636010f, -0.744033744179929070f, 0.668142041426518670f, - -0.745057785441465950f, 0.666999922303637580f, -0.746080073510063890f, - 0.665856233665509610f, -0.747100605980180020f, 0.664710978203345020f, - -0.748119380450403600f, 0.663564158612039770f, -0.749136394523459150f, - 0.662415777590172010f, -0.750151645806214960f, 0.661265837839992380f, - -0.751165131909686480f, 0.660114342067420480f, -0.752176850449042480f, - 0.658961292982037540f, -0.753186799043612410f, 0.657806693297078750f, - -0.754194975316889170f, 0.656650545729429050f, -0.755201376896536440f, - 0.655492852999615570f, -0.756206001414394420f, 0.654333617831800550f, - -0.757208846506484570f, 0.653172842953776640f, -0.758209909813015170f, - 0.652010531096959720f, -0.759209188978388070f, 0.650846684996380990f, - -0.760206681651202200f, 0.649681307390683420f, -0.761202385484261670f, - 0.648514401022112550f, -0.762196298134578900f, 0.647345968636512060f, - -0.763188417263381050f, 0.646176012983316620f, -0.764178740536116670f, - 0.645004536815544040f, -0.765167265622458960f, 0.643831542889791390f, - -0.766153990196312700f, 0.642657033966227090f, -0.767138911935820290f, - 0.641481012808583160f, -0.768122028523365420f, 0.640303482184151560f, - -0.769103337645579480f, 0.639124444863775840f, -0.770082836993347900f, - 0.637943903621844060f, -0.771060524261813600f, 0.636761861236284420f, - -0.772036397150384410f, 0.635578320488556230f, -0.773010453362736990f, - 0.634393284163645490f, -0.773982690606822680f, 0.633206755050057410f, - -0.774953106594873820f, 0.632018735939809060f, -0.775921699043407690f, - 0.630829229628424470f, -0.776888465673232330f, 0.629638238914927210f, - -0.777853404209453040f, 0.628445766601832710f, -0.778816512381475980f, - 0.627251815495144080f, -0.779777787923014330f, 0.626056388404343630f, - -0.780737228572094490f, 0.624859488142386340f, -0.781694832071059160f, - 0.623661117525694860f, -0.782650596166575620f, 0.622461279374150080f, - -0.783604518609638200f, 0.621259976511087550f, -0.784556597155575020f, - 0.620057211763289430f, -0.785506829564053930f, 0.618852987960976430f, - -0.786455213599085770f, 0.617647307937803870f, -0.787401747029031210f, - 0.616440174530853760f, -0.788346427626606230f, 0.615231590580626930f, - -0.789289253168885760f, 0.614021558931038380f, -0.790230221437309920f, - 0.612810082429409820f, -0.791169330217690200f, 0.611597163926461910f, - -0.792106577300212170f, 0.610382806276309700f, -0.793041960479443530f, - 0.609167012336453320f, -0.793975477554337170f, 0.607949784967773630f, - -0.794907126328236790f, 0.606731127034524700f, -0.795836904608883460f, - 0.605511041404325660f, -0.796764810208418830f, 0.604289530948155960f, - -0.797690840943390930f, 0.603066598540348390f, -0.798614994634760820f, - 0.601842247058580140f, -0.799537269107905120f, 0.600616479383868860f, - -0.800457662192622710f, 0.599389298400564650f, -0.801376171723140240f, - 0.598160706996342380f, -0.802292795538115500f, 0.596930708062196720f, - -0.803207531480644830f, 0.595699304492433470f, -0.804120377398265700f, - 0.594466499184664430f, -0.805031331142963440f, 0.593232295039800020f, - -0.805940390571176280f, 0.591996694962040990f, -0.806847553543799330f, - 0.590759701858874160f, -0.807752817926190250f, 0.589521318641064050f, - -0.808656181588174980f, 0.588281548222645330f, -0.809557642404051370f, - 0.587040393520917970f, -0.810457198252594660f, 0.585797857456438980f, - -0.811354847017063730f, 0.584553942953015330f, -0.812250586585203770f, - 0.583308652937698510f, -0.813144414849253480f, 0.582061990340775660f, - -0.814036329705948410f, 0.580813958095764530f, -0.814926329056526400f, - 0.579564559139405970f, -0.815814410806733670f, 0.578313796411655700f, - -0.816700572866827850f, 0.577061672855679440f, -0.817584813151583600f, - 0.575808191417845450f, -0.818467129580298660f, 0.574553355047715870f, - -0.819347520076797010f, 0.573297166698042090f, -0.820225982569434580f, - 0.572039629324757270f, -0.821102514991104650f, 0.570780745886967260f, - -0.821977115279241330f, 0.569520519346947470f, -0.822849781375826210f, - 0.568258952670131710f, -0.823720511227391430f, 0.566996048825108680f, - -0.824589302785025070f, 0.565731810783613450f, -0.825456154004377440f, - 0.564466241520519500f, -0.826321062845663530f, 0.563199344013834090f, - -0.827184027273669020f, 0.561931121244689580f, -0.828045045257755690f, - 0.560661576197336140f, -0.828904114771864990f, 0.559390711859136030f, - -0.829761233794522930f, 0.558118531220556320f, -0.830616400308846310f, - 0.556845037275160100f, -0.831469612302545350f, 0.555570233019602180f, - -0.832320867767929570f, 0.554294121453620230f, -0.833170164701913190f, - 0.553016705580027580f, -0.834017501106018020f, 0.551737988404707670f, - -0.834862874986380010f, 0.550457972936604920f, -0.835706284353752600f, - 0.549176662187719660f, -0.836547727223511890f, 0.547894059173100410f, - -0.837387201615661820f, 0.546610166910834970f, -0.838224705554838080f, - 0.545324988422046350f, -0.839060237070312630f, 0.544038526730884040f, - -0.839893794195999520f, 0.542750784864515890f, -0.840725374970458070f, - 0.541461765853123330f, -0.841554977436898330f, 0.540171472729892970f, - -0.842382599643185850f, 0.538879908531008420f, -0.843208239641845330f, - 0.537587076295645730f, -0.844031895490066410f, 0.536292979065963290f, - -0.844853565249707120f, 0.534997619887097150f, -0.845673246987298950f, - 0.533701001807153190f, -0.846490938774052020f, 0.532403127877198010f, - -0.847306638685858430f, 0.531104001151254890f, -0.848120344803297120f, - 0.529803624686294830f, -0.848932055211639610f, 0.528502001542228480f, - -0.849741768000852550f, 0.527199134781901280f, -0.850549481265603370f, - 0.525895027471084850f, -0.851355193105265200f, 0.524589682678468950f, - -0.852158901623919610f, 0.523283103475656650f, -0.852960604930363630f, - 0.521975292937154500f, -0.853760301138111410f, 0.520666254140367160f, - -0.854557988365400420f, 0.519355990165589750f, -0.855353664735195920f, - 0.518044504095999450f, -0.856147328375194470f, 0.516731799017649760f, - -0.856938977417828650f, 0.515417878019463150f, -0.857728610000272010f, - 0.514102744193221770f, -0.858516224264442850f, 0.512786400633562960f, - -0.859301818357008360f, 0.511468850437970520f, -0.860085390429390140f, - 0.510150096706766810f, -0.860866938637767090f, 0.508830142543107320f, - -0.861646461143081300f, 0.507508991052970980f, -0.862423956111040500f, - 0.506186645345155230f, -0.863199421712124050f, 0.504863108531267700f, - -0.863972856121586700f, 0.503538383725717690f, -0.864744257519462380f, - 0.502212474045710680f, -0.865513624090568980f, 0.500885382611240940f, - -0.866280954024512990f, 0.499557112545081950f, -0.867046245515692760f, - 0.498227666972781760f, -0.867809496763303210f, 0.496897049022654690f, - -0.868570705971340900f, 0.495565261825772540f, -0.869329871348606620f, - 0.494232308515960010f, -0.870086991108711350f, 0.492898192229784150f, - -0.870842063470078980f, 0.491562916106549900f, -0.871595086655950870f, - 0.490226483288291380f, -0.872346058894391430f, 0.488888896919763280f, - -0.873094978418290090f, 0.487550160148435880f, -0.873841843465366750f, - 0.486210276124486580f, -0.874586652278176110f, 0.484869248000791120f, - -0.875329403104110890f, 0.483527078932918630f, -0.876070094195406490f, - 0.482183772079122890f, -0.876808723809145650f, 0.480839330600333960f, - -0.877545290207261130f, 0.479493757660153290f, -0.878279791656541460f, - 0.478147056424843180f, -0.879012226428633530f, 0.476799230063322090f, - -0.879742592800047300f, 0.475450281747156090f, -0.880470889052160750f, - 0.474100214650550080f, -0.881197113471222090f, 0.472749031950342740f, - -0.881921264348354940f, 0.471396736825997860f, -0.882643339979562790f, - 0.470043332459595680f, -0.883363338665731690f, 0.468688822035827850f, - -0.884081258712634880f, 0.467333208741988580f, -0.884797098430937790f, - 0.465976495767966180f, -0.885510856136199840f, 0.464618686306238090f, - -0.886222530148880530f, 0.463259783551860320f, -0.886932118794342190f, - 0.461899790702462730f, -0.887639620402853820f, 0.460538710958240230f, - -0.888345033309596240f, 0.459176547521944200f, -0.889048355854664570f, - 0.457813303598877170f, -0.889749586383072670f, 0.456448982396884140f, - -0.890448723244757880f, 0.455083587126343890f, -0.891145764794583290f, - 0.453717121000163760f, -0.891840709392342610f, 0.452349587233771060f, - -0.892533555402764580f, 0.450980989045103860f, -0.893224301195515210f, - 0.449611329654606870f, -0.893912945145203140f, 0.448240612285220050f, - -0.894599485631382700f, 0.446868840162374160f, -0.895283921038557360f, - 0.445496016513981960f, -0.895966249756185110f, 0.444122144570429310f, - -0.896646470178680270f, 0.442747227564569970f, -0.897324580705418210f, - 0.441371268731716890f, -0.898000579740739770f, 0.439994271309633310f, - -0.898674465693953930f, 0.438616238538527550f, -0.899346236979341460f, - 0.437237173661044250f, -0.900015892016160170f, 0.435857079922255530f, - -0.900683429228646750f, 0.434475960569655980f, -0.901348847046021920f, - 0.433093818853152070f, -0.902012143902493180f, 0.431710658025057260f, - -0.902673318237258710f, 0.430326481340082890f, -0.903332368494511820f, - 0.428941292055329600f, -0.903989293123443340f, 0.427555093430282030f, - -0.904644090578246130f, 0.426167888726799840f, -0.905296759318118700f, - 0.424779681209108860f, -0.905947297807268460f, 0.423390474143795940f, - -0.906595704514915330f, 0.422000270799799850f, -0.907241977915295820f, - 0.420609074448402560f, -0.907886116487666040f, 0.419216888363224240f, - -0.908528118716306120f, 0.417823715820212440f, -0.909167983090522380f, - 0.416429560097637150f, -0.909805708104652110f, 0.415034424476081850f, - -0.910441292258067140f, 0.413638312238434610f, -0.911074734055176360f, - 0.412241226669882830f, -0.911706032005429770f, 0.410843171057904130f, - -0.912335184623322750f, 0.409444148692257650f, -0.912962190428398210f, - 0.408044162864978580f, -0.913587047945250700f, 0.406643216870369200f, - -0.914209755703530690f, 0.405241314004989920f, -0.914830312237945980f, - 0.403838457567654410f, -0.915448716088267720f, 0.402434650859418600f, - -0.916064965799331720f, 0.401029897183575620f, -0.916679059921042590f, - 0.399624199845647070f, -0.917290997008377910f, 0.398217562153373670f, - -0.917900775621390500f, 0.396809987416710250f, -0.918508394325212140f, - 0.395401478947816520f, -0.919113851690057770f, 0.393992040061048150f, - -0.919717146291227360f, 0.392581674072951410f, -0.920318276709110480f, - 0.391170384302254040f, -0.920917241529189410f, 0.389758174069856470f, - -0.921514039342041790f, 0.388345046698826580f, -0.922108668743345070f, - 0.386931005514388750f, -0.922701128333878630f, 0.385516053843918850f, - -0.923291416719527520f, 0.384100195016935320f, -0.923879532511286740f, - 0.382683432365089890f, -0.924465474325262600f, 0.381265769222162320f, - -0.925049240782677470f, 0.379847208924051380f, -0.925630830509872720f, - 0.378427754808765670f, -0.926210242138311380f, 0.377007410216418150f, - -0.926787474304581750f, 0.375586178489217380f, -0.927362525650401110f, - 0.374164062971458040f, -0.927935394822617780f, 0.372741067009516090f, - -0.928506080473215480f, 0.371317193951837710f, -0.929074581259315750f, - 0.369892447148934100f, -0.929640895843181210f, 0.368466829953372600f, - -0.930205022892219070f, 0.367040345719767290f, -0.930766961078983710f, - 0.365612997804773800f, -0.931326709081180320f, 0.364184789567080110f, - -0.931884265581668040f, 0.362755724367397280f, -0.932439629268462470f, - 0.361325805568454170f, -0.932992798834738850f, 0.359895036534988330f, - -0.933543772978836170f, 0.358463420633736600f, -0.934092550404258760f, - 0.357030961233430310f, -0.934639129819680670f, 0.355597661704784020f, - -0.935183509938947610f, 0.354163525420490400f, -0.935725689481080260f, - 0.352728555755210950f, -0.936265667170278260f, 0.351292756085567200f, - -0.936803441735921670f, 0.349856129790134860f, -0.937339011912574850f, - 0.348418680249434790f, -0.937872376439989770f, 0.346980410845923740f, - -0.938403534063108170f, 0.345541324963988980f, -0.938932483532064490f, - 0.344101425989939040f, -0.939459223602189920f, 0.342660717311994430f, - -0.939983753034013820f, 0.341219202320282690f, -0.940506070593268300f, - 0.339776884406827020f, -0.941026175050889260f, 0.338333766965541180f, - -0.941544065183020700f, 0.336889853392220330f, -0.942059739771017310f, - 0.335445147084531710f, -0.942573197601446870f, 0.333999651442009380f, - -0.943084437466093380f, 0.332553369866044450f, -0.943593458161960390f, - 0.331106305759876480f, -0.944100258491272660f, 0.329658462528587440f, - -0.944604837261480150f, 0.328209843579092720f, -0.945107193285260610f, - 0.326760452320131840f, -0.945607325380521170f, 0.325310292162263260f, - -0.946105232370403340f, 0.323859366517853020f, -0.946600913083283530f, - 0.322407678801069850f, -0.947094366352777110f, 0.320955232427875490f, - -0.947585591017741090f, 0.319502030816015800f, -0.948074585922276230f, - 0.318048077385014890f, -0.948561349915730270f, 0.316593375556166070f, - -0.949045881852700560f, 0.315137928752522500f, -0.949528180593036670f, - 0.313681740398891410f, -0.950008245001843000f, 0.312224813921825110f, - -0.950486073949481700f, 0.310767152749611530f, -0.950961666311574970f, - 0.309308760312269000f, -0.951435020969008340f, 0.307849640041535030f, - -0.951906136807932350f, 0.306389795370860920f, -0.952375012719765770f, - 0.304929229735402650f, -0.952841647601198600f, 0.303467946572011430f, - -0.953306040354193860f, 0.302005949319228030f, -0.953768189885990210f, - 0.300543241417273680f, -0.954228095109105560f, 0.299079826308040530f, - -0.954685754941338340f, 0.297615707435086140f, -0.955141168305770670f, - 0.296150888243624010f, -0.955594334130771110f, 0.294685372180514380f, - -0.956045251349996290f, 0.293219162694258960f, -0.956493918902394990f, - 0.291752263234989430f, -0.956940335732208820f, 0.290284677254462390f, - -0.957384500788975860f, 0.288816408206049760f, -0.957826413027532910f, - 0.287347459544729620f, -0.958266071408017670f, 0.285877834727080560f, - -0.958703474895871490f, 0.284407537211272100f, -0.959138622461841890f, - 0.282936570457055450f, -0.959571513081984520f, 0.281464937925757890f, - -0.960002145737665850f, 0.279992643080273440f, -0.960430519415565790f, - 0.278519689385053170f, -0.960856633107679550f, 0.277046080306100230f, - -0.961280485811320640f, 0.275571819310958310f, -0.961702076529122540f, - 0.274096909868706380f, -0.962121404269041470f, 0.272621355449949250f, - -0.962538468044359160f, 0.271145159526808120f, -0.962953266873683880f, - 0.269668325572915090f, -0.963365799780953940f, 0.268190857063403400f, - -0.963776065795439840f, 0.266712757474898480f, -0.964184063951745830f, - 0.265234030285511730f, -0.964589793289812650f, 0.263754678974831570f, - -0.964993252854920320f, 0.262274707023913700f, -0.965394441697689290f, - 0.260794117915275850f, -0.965793358874083570f, 0.259312915132886400f, - -0.966190003445412500f, 0.257831102162158990f, -0.966584374478333010f, - 0.256348682489943190f, -0.966976471044852070f, 0.254865659604514680f, - -0.967366292222328510f, 0.253382036995570100f, -0.967753837093475400f, - 0.251897818154217190f, -0.968139104746362330f, 0.250413006572965340f, - -0.968522094274417380f, 0.248927605745720090f, -0.968902804776428870f, - 0.247441619167773490f, -0.969281235356548420f, 0.245955050335794650f, - -0.969657385124292340f, 0.244467902747824480f, -0.970031253194543970f, - 0.242980179903264070f, -0.970402838687555500f, 0.241491885302869360f, - -0.970772140728950240f, 0.240003022448741780f, -0.971139158449725090f, - 0.238513594844318550f, -0.971503890986251780f, 0.237023605994367170f, - -0.971866337480279290f, 0.235533059404975740f, -0.972226497078936270f, - 0.234041958583543510f, -0.972584368934732210f, 0.232550307038775160f, - -0.972939952205560070f, 0.231058108280671330f, -0.973293246054698250f, - 0.229565365820518920f, -0.973644249650811870f, 0.228072083170886060f, - -0.973992962167955830f, 0.226578263845610170f, -0.974339382785575860f, - 0.225083911359792830f, -0.974683510688510670f, 0.223589029229790290f, - -0.975025345066994120f, 0.222093620973203650f, -0.975364885116656980f, - 0.220597690108873510f, -0.975702130038528460f, 0.219101240156870050f, - -0.976037079039039020f, 0.217604274638483720f, -0.976369731330021140f, - 0.216106797076219440f, -0.976700086128711730f, 0.214608810993786980f, - -0.977028142657754390f, 0.213110319916091420f, -0.977353900145199960f, - 0.211611327369227890f, -0.977677357824509930f, 0.210111836880469800f, - -0.977998514934557140f, 0.208611851978263510f, -0.978317370719627540f, - 0.207111376192218840f, -0.978633924429423100f, 0.205610413053099380f, - -0.978948175319062200f, 0.204108966092816840f, -0.979260122649082020f, - 0.202607038844421380f, -0.979569765685440520f, 0.201104634842092010f, - -0.979877103699517640f, 0.199601757621130920f, -0.980182135968117320f, - 0.198098410717953810f, -0.980484861773469380f, 0.196594597670080280f, - -0.980785280403230430f, 0.195090322016128610f, -0.981083391150486590f, - 0.193585587295803800f, -0.981379193313754560f, 0.192080397049892470f, - -0.981672686196983110f, 0.190574754820253070f, -0.981963869109555240f, - 0.189068664149806360f, -0.982252741366289370f, 0.187562128582529570f, - -0.982539302287441240f, 0.186055151663446910f, -0.982823551198705240f, - 0.184547736938619700f, -0.983105487431216290f, 0.183039887955140900f, - -0.983385110321551180f, 0.181531608261125220f, -0.983662419211730250f, - 0.180022901405699570f, -0.983937413449218920f, 0.178513770938997420f, - -0.984210092386929030f, 0.177004220412148940f, -0.984480455383220930f, - 0.175494253377271450f, -0.984748501801904210f, 0.173983873387464130f, - -0.985014231012239840f, 0.172473083996796120f, -0.985277642388941220f, - 0.170961888760301220f, -0.985538735312176060f, 0.169450291233968210f, - -0.985797509167567370f, 0.167938294974731280f, -0.986053963346195440f, - 0.166425903540464050f, -0.986308097244598560f, 0.164913120489970140f, - -0.986559910264775410f, 0.163399949382973280f, -0.986809401814185530f, - 0.161886393780111740f, -0.987056571305750970f, 0.160372457242928450f, - -0.987301418157858430f, 0.158858143333861470f, -0.987543941794359230f, - 0.157343455616238550f, -0.987784141644572180f, 0.155828397654265370f, - -0.988022017143283530f, 0.154312973013020080f, -0.988257567730749460f, - 0.152797185258443690f, -0.988490792852696590f, 0.151281037957330310f, - -0.988721691960323780f, 0.149764534677321450f, -0.988950264510302990f, - 0.148247678986896250f, -0.989176509964781010f, 0.146730474455361800f, - -0.989400427791380380f, 0.145212924652847350f, -0.989622017463200780f, - 0.143695033150294640f, -0.989841278458820530f, 0.142176803519448090f, - -0.990058210262297010f, 0.140658239332849540f, -0.990272812363169110f, - 0.139139344163826340f, -0.990485084256457090f, 0.137620121586486040f, - -0.990695025442664630f, 0.136100575175706480f, -0.990902635427780010f, - 0.134580708507126280f, -0.991107913723276890f, 0.133060525157139010f, - -0.991310859846115440f, 0.131540028702883340f, -0.991511473318743900f, - 0.130019222722233430f, -0.991709753669099530f, 0.128498110793793090f, - -0.991905700430609330f, 0.126976696496886060f, -0.992099313142191800f, - 0.125454983411546260f, -0.992290591348257260f, 0.123932975118512480f, - -0.992479534598709970f, 0.122410675199216350f, -0.992666142448948020f, - 0.120888087235777060f, -0.992850414459865100f, 0.119365214810991630f, - -0.993032350197851410f, 0.117842061508325090f, -0.993211949234794500f, - 0.116318630911904710f, -0.993389211148080650f, 0.114794926606510310f, - -0.993564135520595300f, 0.113270952177564420f, -0.993736721940724600f, - 0.111746711211126500f, -0.993906970002356060f, 0.110222207293883240f, - -0.994074879304879370f, 0.108697444013138740f, -0.994240449453187900f, - 0.107172424956809160f, -0.994403680057679100f, 0.105647153713410750f, - -0.994564570734255420f, 0.104121633872054570f, -0.994723121104325700f, - 0.102595869022436560f, -0.994879330794805620f, 0.101069862754827930f, - -0.995033199438118630f, 0.099543618660069277f, -0.995184726672196820f, - 0.098017140329560826f, -0.995333912140482280f, 0.096490431355252662f, - -0.995480755491926940f, 0.094963495329638908f, -0.995625256380994310f, - 0.093436335845747967f, -0.995767414467659820f, 0.091908956497132752f, - -0.995907229417411720f, 0.090381360877865288f, -0.996044700901251970f, - 0.088853552582524753f, -0.996179828595696980f, 0.087325535206192059f, - -0.996312612182778000f, 0.085797312344440158f, -0.996443051350042630f, - 0.084268887593324182f, -0.996571145790554840f, 0.082740264549375636f, - -0.996696895202896060f, 0.081211446809592663f, -0.996820299291165670f, - 0.079682437971430195f, -0.996941357764982160f, 0.078153241632794149f, - -0.997060070339482960f, 0.076623861392031686f, -0.997176436735326080f, - 0.075094300847921347f, -0.997290456678690210f, 0.073564563599667732f, - -0.997402129901275300f, 0.072034653246889471f, -0.997511456140303450f, - 0.070504573389613856f, -0.997618435138519550f, 0.068974327628267024f, - -0.997723066644191640f, 0.067443919563664176f, -0.997825350411111640f, - 0.065913352797003763f, -0.997925286198596000f, 0.064382630929857701f, - -0.998022873771486240f, 0.062851757564161490f, -0.998118112900149180f, - 0.061320736302208488f, -0.998211003360478190f, 0.059789570746640069f, - -0.998301544933892890f, 0.058258264500435794f, -0.998389737407340160f, - 0.056726821166908067f, -0.998475580573294770f, 0.055195244349690094f, - -0.998559074229759310f, 0.053663537652730520f, -0.998640218180265160f, - 0.052131704680283594f, -0.998719012233872940f, 0.050599749036899393f, - -0.998795456205172410f, 0.049067674327417966f, -0.998869549914283560f, - 0.047535484156959538f, -0.998941293186856870f, 0.046003182130914706f, - -0.999010685854073380f, 0.044470771854938584f, -0.999077727752645360f, - 0.042938256934941021f, -0.999142418724816910f, 0.041405640977076774f, - -0.999204758618363890f, 0.039872927587740130f, -0.999264747286594420f, - 0.038340120373552854f, -0.999322384588349540f, 0.036807222941358832f, - -0.999377670388002850f, 0.035274238898214232f, -0.999430604555461730f, - 0.033741171851377705f, -0.999481186966166950f, 0.032208025408304544f, - -0.999529417501093140f, 0.030674803176636865f, -0.999575296046749220f, - 0.029141508764193802f, -0.999618822495178640f, 0.027608145778965660f, - -0.999659996743959220f, 0.026074717829104099f, -0.999698818696204250f, - 0.024541228522912326f, -0.999735288260561680f, 0.023007681468839695f, - -0.999769405351215280f, 0.021474080275469667f, -0.999801169887884260f, - 0.019940428551514438f, -0.999830581795823400f, 0.018406729905805101f, - -0.999857641005823860f, 0.016872987947281835f, -0.999882347454212560f, - 0.015339206284988060f, -0.999904701082852790f, 0.013805388528060632f, - -0.999924701839144500f, 0.012271538285720007f, -0.999942349676023910f, - 0.010737659167264411f, -0.999957644551963900f, 0.009203754782060021f, - -0.999970586430974140f, 0.007669828739531138f, -0.999981175282601110f, - 0.006135884649154799f, -0.999989411081928400f, 0.004601926120448733f, - -0.999995293809576190f, 0.003067956762965977f, -0.999998823451701880f, - 0.001533980186285049f, -1.000000000000000000f, 0.000000000000000122f, - -0.999998823451701880f, -0.001533980186284804f, -0.999995293809576190f, - -0.003067956762965732f, -0.999989411081928400f, -0.004601926120448488f, - -0.999981175282601110f, -0.006135884649154554f, -0.999970586430974140f, - -0.007669828739530893f, -0.999957644551963900f, -0.009203754782059776f, - -0.999942349676023910f, -0.010737659167264166f, -0.999924701839144500f, - -0.012271538285719762f, -0.999904701082852900f, -0.013805388528060387f, - -0.999882347454212560f, -0.015339206284987816f, -0.999857641005823860f, - -0.016872987947281589f, -0.999830581795823400f, -0.018406729905804858f, - -0.999801169887884260f, -0.019940428551514192f, -0.999769405351215280f, - -0.021474080275469421f, -0.999735288260561680f, -0.023007681468839448f, - -0.999698818696204250f, -0.024541228522912080f, -0.999659996743959220f, - -0.026074717829103856f, -0.999618822495178640f, -0.027608145778965414f, - -0.999575296046749220f, -0.029141508764193556f, -0.999529417501093140f, - -0.030674803176636619f, -0.999481186966166950f, -0.032208025408304294f, - -0.999430604555461730f, -0.033741171851377455f, -0.999377670388002850f, - -0.035274238898213982f, -0.999322384588349540f, -0.036807222941358582f, - -0.999264747286594420f, -0.038340120373552611f, -0.999204758618363890f, - -0.039872927587739887f, -0.999142418724816910f, -0.041405640977076531f, - -0.999077727752645360f, -0.042938256934940779f, -0.999010685854073380f, - -0.044470771854938335f, -0.998941293186856870f, -0.046003182130914456f, - -0.998869549914283560f, -0.047535484156959296f, -0.998795456205172410f, - -0.049067674327417724f, -0.998719012233872940f, -0.050599749036899150f, - -0.998640218180265270f, -0.052131704680283351f, -0.998559074229759310f, - -0.053663537652730277f, -0.998475580573294770f, -0.055195244349689851f, - -0.998389737407340160f, -0.056726821166907818f, -0.998301544933892890f, - -0.058258264500435551f, -0.998211003360478190f, -0.059789570746639827f, - -0.998118112900149180f, -0.061320736302208245f, -0.998022873771486240f, - -0.062851757564161240f, -0.997925286198596000f, -0.064382630929857451f, - -0.997825350411111640f, -0.065913352797003527f, -0.997723066644191640f, - -0.067443919563663926f, -0.997618435138519550f, -0.068974327628266774f, - -0.997511456140303450f, -0.070504573389613606f, -0.997402129901275300f, - -0.072034653246889235f, -0.997290456678690210f, -0.073564563599667496f, - -0.997176436735326190f, -0.075094300847921097f, -0.997060070339482960f, - -0.076623861392031437f, -0.996941357764982160f, -0.078153241632793899f, - -0.996820299291165780f, -0.079682437971429945f, -0.996696895202896060f, - -0.081211446809592427f, -0.996571145790554840f, -0.082740264549375400f, - -0.996443051350042630f, -0.084268887593323932f, -0.996312612182778000f, - -0.085797312344439922f, -0.996179828595696980f, -0.087325535206191809f, - -0.996044700901251970f, -0.088853552582524503f, -0.995907229417411720f, - -0.090381360877865052f, -0.995767414467659820f, -0.091908956497132516f, - -0.995625256380994310f, -0.093436335845747731f, -0.995480755491926940f, - -0.094963495329638659f, -0.995333912140482280f, -0.096490431355252412f, - -0.995184726672196930f, -0.098017140329560590f, -0.995033199438118630f, - -0.099543618660069041f, -0.994879330794805620f, -0.101069862754827680f, - -0.994723121104325700f, -0.102595869022436310f, -0.994564570734255530f, - -0.104121633872054320f, -0.994403680057679100f, -0.105647153713410520f, - -0.994240449453187900f, -0.107172424956808910f, -0.994074879304879480f, - -0.108697444013138490f, -0.993906970002356060f, -0.110222207293883000f, - -0.993736721940724710f, -0.111746711211126250f, -0.993564135520595300f, - -0.113270952177564170f, -0.993389211148080650f, -0.114794926606510070f, - -0.993211949234794610f, -0.116318630911904470f, -0.993032350197851410f, - -0.117842061508324840f, -0.992850414459865100f, -0.119365214810991380f, - -0.992666142448948020f, -0.120888087235776820f, -0.992479534598709970f, - -0.122410675199216100f, -0.992290591348257370f, -0.123932975118512230f, - -0.992099313142191800f, -0.125454983411546010f, -0.991905700430609330f, - -0.126976696496885810f, -0.991709753669099530f, -0.128498110793792840f, - -0.991511473318744010f, -0.130019222722233180f, -0.991310859846115440f, - -0.131540028702883090f, -0.991107913723276890f, -0.133060525157138760f, - -0.990902635427780010f, -0.134580708507126060f, -0.990695025442664630f, - -0.136100575175706230f, -0.990485084256457090f, -0.137620121586485790f, - -0.990272812363169110f, -0.139139344163826120f, -0.990058210262297120f, - -0.140658239332849290f, -0.989841278458820530f, -0.142176803519447840f, - -0.989622017463200890f, -0.143695033150294390f, -0.989400427791380380f, - -0.145212924652847130f, -0.989176509964781010f, -0.146730474455361580f, - -0.988950264510302990f, -0.148247678986896030f, -0.988721691960323780f, - -0.149764534677321200f, -0.988490792852696700f, -0.151281037957330080f, - -0.988257567730749460f, -0.152797185258443440f, -0.988022017143283640f, - -0.154312973013019830f, -0.987784141644572180f, -0.155828397654265120f, - -0.987543941794359230f, -0.157343455616238300f, -0.987301418157858430f, - -0.158858143333861220f, -0.987056571305750970f, -0.160372457242928200f, - -0.986809401814185530f, -0.161886393780111490f, -0.986559910264775520f, - -0.163399949382973060f, -0.986308097244598670f, -0.164913120489969890f, - -0.986053963346195440f, -0.166425903540463830f, -0.985797509167567480f, - -0.167938294974731030f, -0.985538735312176060f, -0.169450291233967990f, - -0.985277642388941330f, -0.170961888760300970f, -0.985014231012239840f, - -0.172473083996795870f, -0.984748501801904210f, -0.173983873387463880f, - -0.984480455383220930f, -0.175494253377271200f, -0.984210092386929140f, - -0.177004220412148690f, -0.983937413449218920f, -0.178513770938997170f, - -0.983662419211730250f, -0.180022901405699350f, -0.983385110321551180f, - -0.181531608261124970f, -0.983105487431216400f, -0.183039887955140650f, - -0.982823551198705350f, -0.184547736938619480f, -0.982539302287441240f, - -0.186055151663446660f, -0.982252741366289480f, -0.187562128582529320f, - -0.981963869109555240f, -0.189068664149806110f, -0.981672686196983110f, - -0.190574754820252820f, -0.981379193313754670f, -0.192080397049892220f, - -0.981083391150486710f, -0.193585587295803550f, -0.980785280403230430f, - -0.195090322016128360f, -0.980484861773469380f, -0.196594597670080030f, - -0.980182135968117430f, -0.198098410717953560f, -0.979877103699517750f, - -0.199601757621130670f, -0.979569765685440520f, -0.201104634842091760f, - -0.979260122649082020f, -0.202607038844421130f, -0.978948175319062200f, - -0.204108966092816620f, -0.978633924429423210f, -0.205610413053099160f, - -0.978317370719627650f, -0.207111376192218590f, -0.977998514934557140f, - -0.208611851978263260f, -0.977677357824510040f, -0.210111836880469550f, - -0.977353900145199960f, -0.211611327369227660f, -0.977028142657754390f, - -0.213110319916091200f, -0.976700086128711840f, -0.214608810993786730f, - -0.976369731330021250f, -0.216106797076219210f, -0.976037079039039130f, - -0.217604274638483470f, -0.975702130038528570f, -0.219101240156869800f, - -0.975364885116656980f, -0.220597690108873260f, -0.975025345066994120f, - -0.222093620973203430f, -0.974683510688510670f, -0.223589029229790040f, - -0.974339382785575860f, -0.225083911359792610f, -0.973992962167955940f, - -0.226578263845609920f, -0.973644249650811870f, -0.228072083170885810f, - -0.973293246054698250f, -0.229565365820518700f, -0.972939952205560180f, - -0.231058108280671080f, -0.972584368934732320f, -0.232550307038774940f, - -0.972226497078936380f, -0.234041958583543260f, -0.971866337480279400f, - -0.235533059404975510f, -0.971503890986251890f, -0.237023605994366950f, - -0.971139158449725200f, -0.238513594844318330f, -0.970772140728950240f, - -0.240003022448741530f, -0.970402838687555500f, -0.241491885302869110f, - -0.970031253194543970f, -0.242980179903263820f, -0.969657385124292450f, - -0.244467902747824260f, -0.969281235356548530f, -0.245955050335794430f, - -0.968902804776428870f, -0.247441619167773270f, -0.968522094274417380f, - -0.248927605745719870f, -0.968139104746362440f, -0.250413006572965110f, - -0.967753837093475510f, -0.251897818154216970f, -0.967366292222328620f, - -0.253382036995569880f, -0.966976471044852180f, -0.254865659604514460f, - -0.966584374478333120f, -0.256348682489942910f, -0.966190003445412620f, - -0.257831102162158770f, -0.965793358874083680f, -0.259312915132886180f, - -0.965394441697689400f, -0.260794117915275630f, -0.964993252854920440f, - -0.262274707023913420f, -0.964589793289812760f, -0.263754678974831350f, - -0.964184063951745830f, -0.265234030285511510f, -0.963776065795439950f, - -0.266712757474898250f, -0.963365799780954050f, -0.268190857063403180f, - -0.962953266873683990f, -0.269668325572914810f, -0.962538468044359160f, - -0.271145159526807900f, -0.962121404269041580f, -0.272621355449949030f, - -0.961702076529122540f, -0.274096909868706160f, -0.961280485811320640f, - -0.275571819310958090f, -0.960856633107679550f, -0.277046080306100010f, - -0.960430519415565900f, -0.278519689385052890f, -0.960002145737665960f, - -0.279992643080273220f, -0.959571513081984630f, -0.281464937925757660f, - -0.959138622461842010f, -0.282936570457055170f, -0.958703474895871600f, - -0.284407537211271820f, -0.958266071408017780f, -0.285877834727080340f, - -0.957826413027532910f, -0.287347459544729400f, -0.957384500788975860f, - -0.288816408206049540f, -0.956940335732208940f, -0.290284677254462110f, - -0.956493918902395100f, -0.291752263234989210f, -0.956045251349996410f, - -0.293219162694258740f, -0.955594334130771110f, -0.294685372180514160f, - -0.955141168305770780f, -0.296150888243623790f, -0.954685754941338450f, - -0.297615707435085920f, -0.954228095109105670f, -0.299079826308040310f, - -0.953768189885990330f, -0.300543241417273450f, -0.953306040354193970f, - -0.302005949319227810f, -0.952841647601198720f, -0.303467946572011200f, - -0.952375012719765880f, -0.304929229735402430f, -0.951906136807932350f, - -0.306389795370860700f, -0.951435020969008450f, -0.307849640041534810f, - -0.950961666311575080f, -0.309308760312268780f, -0.950486073949481810f, - -0.310767152749611310f, -0.950008245001843000f, -0.312224813921824880f, - -0.949528180593036790f, -0.313681740398891180f, -0.949045881852700670f, - -0.315137928752522220f, -0.948561349915730270f, -0.316593375556165850f, - -0.948074585922276340f, -0.318048077385014670f, -0.947585591017741200f, - -0.319502030816015580f, -0.947094366352777220f, -0.320955232427875270f, - -0.946600913083283650f, -0.322407678801069630f, -0.946105232370403450f, - -0.323859366517852800f, -0.945607325380521280f, -0.325310292162262980f, - -0.945107193285260610f, -0.326760452320131570f, -0.944604837261480260f, - -0.328209843579092500f, -0.944100258491272770f, -0.329658462528587210f, - -0.943593458161960390f, -0.331106305759876260f, -0.943084437466093490f, - -0.332553369866044220f, -0.942573197601446980f, -0.333999651442009100f, - -0.942059739771017420f, -0.335445147084531490f, -0.941544065183020810f, - -0.336889853392220110f, -0.941026175050889370f, -0.338333766965540910f, - -0.940506070593268410f, -0.339776884406826800f, -0.939983753034013940f, - -0.341219202320282470f, -0.939459223602190030f, -0.342660717311994210f, - -0.938932483532064600f, -0.344101425989938810f, -0.938403534063108280f, - -0.345541324963988760f, -0.937872376439989890f, -0.346980410845923510f, - -0.937339011912574960f, -0.348418680249434560f, -0.936803441735921670f, - -0.349856129790134640f, -0.936265667170278260f, -0.351292756085566980f, - -0.935725689481080370f, -0.352728555755210730f, -0.935183509938947720f, - -0.354163525420490120f, -0.934639129819680780f, -0.355597661704783800f, - -0.934092550404258870f, -0.357030961233430090f, -0.933543772978836280f, - -0.358463420633736370f, -0.932992798834738960f, -0.359895036534988110f, - -0.932439629268462470f, -0.361325805568453950f, -0.931884265581668150f, - -0.362755724367397060f, -0.931326709081180430f, -0.364184789567079890f, - -0.930766961078983820f, -0.365612997804773580f, -0.930205022892219070f, - -0.367040345719767070f, -0.929640895843181210f, -0.368466829953372380f, - -0.929074581259315860f, -0.369892447148933880f, -0.928506080473215590f, - -0.371317193951837430f, -0.927935394822617780f, -0.372741067009515870f, - -0.927362525650401110f, -0.374164062971457820f, -0.926787474304581860f, - -0.375586178489217160f, -0.926210242138311490f, -0.377007410216417930f, - -0.925630830509872830f, -0.378427754808765390f, -0.925049240782677580f, - -0.379847208924051160f, -0.924465474325262710f, -0.381265769222162100f, - -0.923879532511286850f, -0.382683432365089670f, -0.923291416719527640f, - -0.384100195016935100f, -0.922701128333878630f, -0.385516053843918630f, - -0.922108668743345180f, -0.386931005514388530f, -0.921514039342041900f, - -0.388345046698826360f, -0.920917241529189520f, -0.389758174069856240f, - -0.920318276709110590f, -0.391170384302253820f, -0.919717146291227470f, - -0.392581674072951190f, -0.919113851690057770f, -0.393992040061047930f, - -0.918508394325212250f, -0.395401478947816300f, -0.917900775621390610f, - -0.396809987416710030f, -0.917290997008378020f, -0.398217562153373450f, - -0.916679059921042700f, -0.399624199845646840f, -0.916064965799331830f, - -0.401029897183575400f, -0.915448716088267830f, -0.402434650859418370f, - -0.914830312237946090f, -0.403838457567654190f, -0.914209755703530690f, - -0.405241314004989690f, -0.913587047945250810f, -0.406643216870368970f, - -0.912962190428398320f, -0.408044162864978350f, -0.912335184623322860f, - -0.409444148692257430f, -0.911706032005429880f, -0.410843171057903910f, - -0.911074734055176470f, -0.412241226669882610f, -0.910441292258067250f, - -0.413638312238434390f, -0.909805708104652220f, -0.415034424476081630f, - -0.909167983090522490f, -0.416429560097636930f, -0.908528118716306230f, - -0.417823715820212220f, -0.907886116487666150f, -0.419216888363224020f, - -0.907241977915295930f, -0.420609074448402340f, -0.906595704514915450f, - -0.422000270799799630f, -0.905947297807268570f, -0.423390474143795710f, - -0.905296759318118820f, -0.424779681209108640f, -0.904644090578246240f, - -0.426167888726799620f, -0.903989293123443450f, -0.427555093430281810f, - -0.903332368494511930f, -0.428941292055329380f, -0.902673318237258830f, - -0.430326481340082670f, -0.902012143902493290f, -0.431710658025057040f, - -0.901348847046022030f, -0.433093818853151850f, -0.900683429228646860f, - -0.434475960569655760f, -0.900015892016160280f, -0.435857079922255310f, - -0.899346236979341570f, -0.437237173661044030f, -0.898674465693954040f, - -0.438616238538527330f, -0.898000579740739880f, -0.439994271309633090f, - -0.897324580705418320f, -0.441371268731716670f, -0.896646470178680380f, - -0.442747227564569750f, -0.895966249756185220f, -0.444122144570429090f, - -0.895283921038557470f, -0.445496016513981740f, -0.894599485631382810f, - -0.446868840162373940f, -0.893912945145203250f, -0.448240612285219830f, - -0.893224301195515320f, -0.449611329654606650f, -0.892533555402764690f, - -0.450980989045103640f, -0.891840709392342720f, -0.452349587233770830f, - -0.891145764794583410f, -0.453717121000163540f, -0.890448723244757990f, - -0.455083587126343670f, -0.889749586383072780f, -0.456448982396883920f, - -0.889048355854664680f, -0.457813303598876950f, -0.888345033309596350f, - -0.459176547521943980f, -0.887639620402853930f, -0.460538710958240060f, - -0.886932118794342310f, -0.461899790702462510f, -0.886222530148880640f, - -0.463259783551860090f, -0.885510856136199950f, -0.464618686306237870f, - -0.884797098430937900f, -0.465976495767965960f, -0.884081258712634990f, - -0.467333208741988360f, -0.883363338665731800f, -0.468688822035827620f, - -0.882643339979562900f, -0.470043332459595450f, -0.881921264348355050f, - -0.471396736825997640f, -0.881197113471222200f, -0.472749031950342510f, - -0.880470889052160870f, -0.474100214650549860f, -0.879742592800047410f, - -0.475450281747155920f, -0.879012226428633640f, -0.476799230063321870f, - -0.878279791656541580f, -0.478147056424842950f, -0.877545290207261240f, - -0.479493757660153060f, -0.876808723809145760f, -0.480839330600333740f, - -0.876070094195406600f, -0.482183772079122660f, -0.875329403104111000f, - -0.483527078932918410f, -0.874586652278176220f, -0.484869248000790950f, - -0.873841843465366860f, -0.486210276124486360f, -0.873094978418290200f, - -0.487550160148435660f, -0.872346058894391540f, -0.488888896919763060f, - -0.871595086655950980f, -0.490226483288291160f, -0.870842063470079090f, - -0.491562916106549730f, -0.870086991108711460f, -0.492898192229783930f, - -0.869329871348606730f, -0.494232308515959780f, -0.868570705971341010f, - -0.495565261825772320f, -0.867809496763303320f, -0.496897049022654470f, - -0.867046245515692870f, -0.498227666972781540f, -0.866280954024513110f, - -0.499557112545081730f, -0.865513624090569090f, -0.500885382611240710f, - -0.864744257519462490f, -0.502212474045710570f, -0.863972856121586810f, - -0.503538383725717460f, -0.863199421712124160f, -0.504863108531267590f, - -0.862423956111040720f, -0.506186645345155010f, -0.861646461143081410f, - -0.507508991052970760f, -0.860866938637767310f, -0.508830142543107100f, - -0.860085390429390250f, -0.510150096706766590f, -0.859301818357008470f, - -0.511468850437970300f, -0.858516224264442960f, -0.512786400633562730f, - -0.857728610000272120f, -0.514102744193221550f, -0.856938977417828760f, - -0.515417878019462930f, -0.856147328375194690f, -0.516731799017649650f, - -0.855353664735196140f, -0.518044504095999230f, -0.854557988365400530f, - -0.519355990165589640f, -0.853760301138111520f, -0.520666254140366940f, - -0.852960604930363740f, -0.521975292937154280f, -0.852158901623919830f, - -0.523283103475656430f, -0.851355193105265310f, -0.524589682678468730f, - -0.850549481265603480f, -0.525895027471084630f, -0.849741768000852660f, - -0.527199134781901060f, -0.848932055211639720f, -0.528502001542228260f, - -0.848120344803297230f, -0.529803624686294610f, -0.847306638685858540f, - -0.531104001151254670f, -0.846490938774052130f, -0.532403127877197790f, - -0.845673246987299070f, -0.533701001807152960f, -0.844853565249707230f, - -0.534997619887096930f, -0.844031895490066520f, -0.536292979065963070f, - -0.843208239641845440f, -0.537587076295645510f, -0.842382599643185960f, - -0.538879908531008200f, -0.841554977436898440f, -0.540171472729892850f, - -0.840725374970458180f, -0.541461765853123220f, -0.839893794195999630f, - -0.542750784864515780f, -0.839060237070312740f, -0.544038526730883820f, - -0.838224705554838190f, -0.545324988422046130f, -0.837387201615662050f, - -0.546610166910834750f, -0.836547727223512010f, -0.547894059173100190f, - -0.835706284353752720f, -0.549176662187719540f, -0.834862874986380120f, - -0.550457972936604700f, -0.834017501106018130f, -0.551737988404707450f, - -0.833170164701913300f, -0.553016705580027360f, -0.832320867767929680f, - -0.554294121453620000f, -0.831469612302545460f, -0.555570233019601960f, - -0.830616400308846430f, -0.556845037275159880f, -0.829761233794523050f, - -0.558118531220556100f, -0.828904114771865100f, -0.559390711859135800f, - -0.828045045257755800f, -0.560661576197335920f, -0.827184027273669130f, - -0.561931121244689360f, -0.826321062845663650f, -0.563199344013833870f, - -0.825456154004377550f, -0.564466241520519390f, -0.824589302785025290f, - -0.565731810783613230f, -0.823720511227391540f, -0.566996048825108460f, - -0.822849781375826430f, -0.568258952670131490f, -0.821977115279241550f, - -0.569520519346947250f, -0.821102514991104760f, -0.570780745886967140f, - -0.820225982569434690f, -0.572039629324757050f, -0.819347520076797120f, - -0.573297166698041980f, -0.818467129580298770f, -0.574553355047715650f, - -0.817584813151583710f, -0.575808191417845340f, -0.816700572866827960f, - -0.577061672855679330f, -0.815814410806733890f, -0.578313796411655480f, - -0.814926329056526620f, -0.579564559139405740f, -0.814036329705948520f, - -0.580813958095764300f, -0.813144414849253590f, -0.582061990340775440f, - -0.812250586585203880f, -0.583308652937698400f, -0.811354847017063840f, - -0.584553942953015100f, -0.810457198252594770f, -0.585797857456438860f, - -0.809557642404051480f, -0.587040393520917750f, -0.808656181588175090f, - -0.588281548222645110f, -0.807752817926190360f, -0.589521318641063940f, - -0.806847553543799450f, -0.590759701858873940f, -0.805940390571176390f, - -0.591996694962040880f, -0.805031331142963550f, -0.593232295039799800f, - -0.804120377398265920f, -0.594466499184664210f, -0.803207531480644940f, - -0.595699304492433250f, -0.802292795538115720f, -0.596930708062196500f, - -0.801376171723140350f, -0.598160706996342160f, -0.800457662192622820f, - -0.599389298400564540f, -0.799537269107905240f, -0.600616479383868640f, - -0.798614994634760930f, -0.601842247058579920f, -0.797690840943391160f, - -0.603066598540348160f, -0.796764810208418940f, -0.604289530948155850f, - -0.795836904608883570f, -0.605511041404325430f, -0.794907126328236900f, - -0.606731127034524480f, -0.793975477554337280f, -0.607949784967773410f, - -0.793041960479443750f, -0.609167012336453100f, -0.792106577300212280f, - -0.610382806276309480f, -0.791169330217690310f, -0.611597163926461800f, - -0.790230221437310140f, -0.612810082429409710f, -0.789289253168885870f, - -0.614021558931038160f, -0.788346427626606340f, -0.615231590580626710f, - -0.787401747029031430f, -0.616440174530853650f, -0.786455213599085990f, - -0.617647307937803650f, -0.785506829564054040f, -0.618852987960976210f, - -0.784556597155575240f, -0.620057211763289210f, -0.783604518609638420f, - -0.621259976511087440f, -0.782650596166575840f, -0.622461279374149860f, - -0.781694832071059390f, -0.623661117525694640f, -0.780737228572094600f, - -0.624859488142386230f, -0.779777787923014550f, -0.626056388404343520f, - -0.778816512381476200f, -0.627251815495143860f, -0.777853404209453150f, - -0.628445766601832600f, -0.776888465673232440f, -0.629638238914926980f, - -0.775921699043407800f, -0.630829229628424250f, -0.774953106594873930f, - -0.632018735939808950f, -0.773982690606822790f, -0.633206755050057300f, - -0.773010453362737100f, -0.634393284163645270f, -0.772036397150384520f, - -0.635578320488556110f, -0.771060524261813710f, -0.636761861236284310f, - -0.770082836993348120f, -0.637943903621843940f, -0.769103337645579700f, - -0.639124444863775730f, -0.768122028523365640f, -0.640303482184151450f, - -0.767138911935820510f, -0.641481012808583050f, -0.766153990196312920f, - -0.642657033966226860f, -0.765167265622459070f, -0.643831542889791280f, - -0.764178740536116790f, -0.645004536815543820f, -0.763188417263381270f, - -0.646176012983316390f, -0.762196298134579120f, -0.647345968636511840f, - -0.761202385484261890f, -0.648514401022112330f, -0.760206681651202420f, - -0.649681307390683190f, -0.759209188978388180f, -0.650846684996380760f, - -0.758209909813015280f, -0.652010531096959500f, -0.757208846506484790f, - -0.653172842953776530f, -0.756206001414394650f, -0.654333617831800330f, - -0.755201376896536550f, -0.655492852999615350f, -0.754194975316889390f, - -0.656650545729428830f, -0.753186799043612630f, -0.657806693297078530f, - -0.752176850449042700f, -0.658961292982037320f, -0.751165131909686590f, - -0.660114342067420260f, -0.750151645806215070f, -0.661265837839992150f, - -0.749136394523459260f, -0.662415777590171780f, -0.748119380450403710f, - -0.663564158612039660f, -0.747100605980180130f, -0.664710978203344790f, - -0.746080073510064000f, -0.665856233665509390f, -0.745057785441466060f, - -0.666999922303637360f, -0.744033744179929290f, -0.668142041426518450f, - -0.743007952135121940f, -0.669282588346635790f, -0.741980411720831070f, - -0.670421560380172980f, -0.740951125354959110f, -0.671558954847018440f, - -0.739920095459516310f, -0.672694769070772750f, -0.738887324460615220f, - -0.673829000378756040f, -0.737852814788465980f, -0.674961646102012040f, - -0.736816568877370020f, -0.676092703575315810f, -0.735778589165713590f, - -0.677222170137180330f, -0.734738878095963720f, -0.678350043129861250f, - -0.733697438114660370f, -0.679476319899364860f, -0.732654271672412820f, - -0.680600997795453020f, -0.731609381223892740f, -0.681724074171649600f, - -0.730562769227827700f, -0.682845546385247970f, -0.729514438146997010f, - -0.683965411797315400f, -0.728464390448225420f, -0.685083667772700130f, - -0.727412628602375880f, -0.686200311680038480f, -0.726359155084345900f, - -0.687315340891759160f, -0.725303972373060880f, -0.688428752784090330f, - -0.724247082951467000f, -0.689540544737066830f, -0.723188489306527680f, - -0.690650714134534380f, -0.722128193929215460f, -0.691759258364157640f, - -0.721066199314508110f, -0.692866174817424630f, -0.720002507961381880f, - -0.693971460889653780f, -0.718937122372804490f, -0.695075113980000770f, - -0.717870045055731710f, -0.696177131491462990f, -0.716801278521099650f, - -0.697277510830886400f, -0.715730825283818710f, -0.698376249408972800f, - -0.714658687862768980f, -0.699473344640283880f, -0.713584868780793750f, - -0.700568793943248220f, -0.712509370564692320f, -0.701662594740168450f, - -0.711432195745216660f, -0.702754744457225080f, -0.710353346857062420f, - -0.703845240524484830f, -0.709272826438865690f, -0.704934080375904880f, - -0.708190637033195510f, -0.706021261449339520f, -0.707106781186547680f, - -0.707106781186547460f, -0.706021261449339740f, -0.708190637033195290f, - -0.704934080375905100f, -0.709272826438865470f, -0.703845240524485050f, - -0.710353346857062310f, -0.702754744457225300f, -0.711432195745216430f, - -0.701662594740168680f, -0.712509370564692210f, -0.700568793943248450f, - -0.713584868780793520f, -0.699473344640284100f, -0.714658687862768760f, - -0.698376249408973030f, -0.715730825283818480f, -0.697277510830886630f, - -0.716801278521099540f, -0.696177131491463210f, -0.717870045055731490f, - -0.695075113980000990f, -0.718937122372804380f, -0.693971460889654000f, - -0.720002507961381650f, -0.692866174817424850f, -0.721066199314507880f, - -0.691759258364157860f, -0.722128193929215230f, -0.690650714134534600f, - -0.723188489306527460f, -0.689540544737067050f, -0.724247082951466780f, - -0.688428752784090550f, -0.725303972373060660f, -0.687315340891759390f, - -0.726359155084345680f, -0.686200311680038700f, -0.727412628602375650f, - -0.685083667772700360f, -0.728464390448225200f, -0.683965411797315630f, - -0.729514438146996790f, -0.682845546385248190f, -0.730562769227827480f, - -0.681724074171649820f, -0.731609381223892520f, -0.680600997795453240f, - -0.732654271672412590f, -0.679476319899365080f, -0.733697438114660150f, - -0.678350043129861470f, -0.734738878095963500f, -0.677222170137180560f, - -0.735778589165713370f, -0.676092703575316030f, -0.736816568877369790f, - -0.674961646102012260f, -0.737852814788465760f, -0.673829000378756260f, - -0.738887324460615000f, -0.672694769070772970f, -0.739920095459516090f, - -0.671558954847018660f, -0.740951125354958880f, -0.670421560380173200f, - -0.741980411720830960f, -0.669282588346636120f, -0.743007952135121720f, - -0.668142041426518670f, -0.744033744179929070f, -0.666999922303637580f, - -0.745057785441465840f, -0.665856233665509610f, -0.746080073510063780f, - -0.664710978203345020f, -0.747100605980180020f, -0.663564158612039880f, - -0.748119380450403490f, -0.662415777590172010f, -0.749136394523459040f, - -0.661265837839992380f, -0.750151645806214960f, -0.660114342067420480f, - -0.751165131909686370f, -0.658961292982037540f, -0.752176850449042480f, - -0.657806693297078750f, -0.753186799043612410f, -0.656650545729429050f, - -0.754194975316889170f, -0.655492852999615570f, -0.755201376896536320f, - -0.654333617831800660f, -0.756206001414394420f, -0.653172842953777090f, - -0.757208846506484230f, -0.652010531096959720f, -0.758209909813015170f, - -0.650846684996380990f, -0.759209188978387960f, -0.649681307390683080f, - -0.760206681651202420f, -0.648514401022112220f, -0.761202385484262000f, - -0.647345968636512500f, -0.762196298134578560f, -0.646176012983316620f, - -0.763188417263381050f, -0.645004536815544040f, -0.764178740536116560f, - -0.643831542889791500f, -0.765167265622458960f, -0.642657033966226750f, - -0.766153990196313030f, -0.641481012808583610f, -0.767138911935820070f, - -0.640303482184152010f, -0.768122028523365090f, -0.639124444863775950f, - -0.769103337645579480f, -0.637943903621844170f, -0.770082836993347900f, - -0.636761861236284200f, -0.771060524261813820f, -0.635578320488556000f, - -0.772036397150384630f, -0.634393284163645930f, -0.773010453362736660f, - -0.633206755050057520f, -0.773982690606822570f, -0.632018735939809170f, - -0.774953106594873820f, -0.630829229628424580f, -0.775921699043407580f, - -0.629638238914926870f, -0.776888465673232550f, -0.628445766601833160f, - -0.777853404209452700f, -0.627251815495144420f, -0.778816512381475650f, - -0.626056388404343740f, -0.779777787923014330f, -0.624859488142386450f, - -0.780737228572094380f, -0.623661117525694530f, -0.781694832071059500f, - -0.622461279374149750f, -0.782650596166575840f, -0.621259976511088000f, - -0.783604518609637980f, -0.620057211763289430f, -0.784556597155575020f, - -0.618852987960976430f, -0.785506829564053820f, -0.617647307937803980f, - -0.786455213599085770f, -0.616440174530853540f, -0.787401747029031430f, - -0.615231590580627260f, -0.788346427626605890f, -0.614021558931038710f, - -0.789289253168885430f, -0.612810082429409930f, -0.790230221437309920f, - -0.611597163926462020f, -0.791169330217690090f, -0.610382806276309360f, - -0.792106577300212390f, -0.609167012336452980f, -0.793041960479443860f, - -0.607949784967774080f, -0.793975477554336840f, -0.606731127034524810f, - -0.794907126328236790f, -0.605511041404325660f, -0.795836904608883460f, - -0.604289530948156070f, -0.796764810208418720f, -0.603066598540348050f, - -0.797690840943391160f, -0.601842247058580470f, -0.798614994634760490f, - -0.600616479383869310f, -0.799537269107904790f, -0.599389298400564760f, - -0.800457662192622600f, -0.598160706996342380f, -0.801376171723140130f, - -0.596930708062196390f, -0.802292795538115720f, -0.595699304492433130f, - -0.803207531480645050f, -0.594466499184664880f, -0.804120377398265470f, - -0.593232295039800130f, -0.805031331142963440f, -0.591996694962041100f, - -0.805940390571176170f, -0.590759701858874280f, -0.806847553543799220f, - -0.589521318641063830f, -0.807752817926190470f, -0.588281548222645780f, - -0.808656181588174650f, -0.587040393520918300f, -0.809557642404051040f, - -0.585797857456439090f, -0.810457198252594660f, -0.584553942953015330f, - -0.811354847017063730f, -0.583308652937698290f, -0.812250586585203990f, - -0.582061990340775330f, -0.813144414849253700f, -0.580813958095764970f, - -0.814036329705948080f, -0.579564559139405970f, -0.814926329056526400f, - -0.578313796411655700f, -0.815814410806733670f, -0.577061672855679550f, - -0.816700572866827730f, -0.575808191417845230f, -0.817584813151583820f, - -0.574553355047716320f, -0.818467129580298320f, -0.573297166698042540f, - -0.819347520076796680f, -0.572039629324757270f, -0.820225982569434460f, - -0.570780745886967370f, -0.821102514991104650f, -0.569520519346947140f, - -0.821977115279241550f, -0.568258952670131380f, -0.822849781375826430f, - -0.566996048825109010f, -0.823720511227391090f, -0.565731810783613450f, - -0.824589302785025070f, -0.564466241520519610f, -0.825456154004377440f, - -0.563199344013834090f, -0.826321062845663420f, -0.561931121244689250f, - -0.827184027273669240f, -0.560661576197336480f, -0.828045045257755460f, - -0.559390711859136470f, -0.828904114771864650f, -0.558118531220556320f, - -0.829761233794522930f, -0.556845037275160100f, -0.830616400308846200f, - -0.555570233019602180f, -0.831469612302545240f, -0.554294121453619890f, - -0.832320867767929800f, -0.553016705580027910f, -0.833170164701912960f, - -0.551737988404707670f, -0.834017501106017910f, -0.550457972936604920f, - -0.834862874986380010f, -0.549176662187719770f, -0.835706284353752600f, - -0.547894059173100080f, -0.836547727223512120f, -0.546610166910835420f, - -0.837387201615661600f, -0.545324988422046800f, -0.838224705554837860f, - -0.544038526730884150f, -0.839060237070312520f, -0.542750784864516000f, - -0.839893794195999410f, -0.541461765853123440f, -0.840725374970458070f, - -0.540171472729892740f, -0.841554977436898550f, -0.538879908531008870f, - -0.842382599643185630f, -0.537587076295645730f, -0.843208239641845210f, - -0.536292979065963290f, -0.844031895490066300f, -0.534997619887097260f, - -0.844853565249707010f, -0.533701001807152850f, -0.845673246987299180f, - -0.532403127877198460f, -0.846490938774051790f, -0.531104001151255330f, - -0.847306638685858090f, -0.529803624686294940f, -0.848120344803297120f, - -0.528502001542228590f, -0.848932055211639610f, -0.527199134781901280f, - -0.849741768000852550f, -0.525895027471084520f, -0.850549481265603590f, - -0.524589682678469390f, -0.851355193105264860f, -0.523283103475656760f, - -0.852158901623919610f, -0.521975292937154500f, -0.852960604930363520f, - -0.520666254140367160f, -0.853760301138111410f, -0.519355990165589420f, - -0.854557988365400640f, -0.518044504095999890f, -0.855353664735195700f, - -0.516731799017650210f, -0.856147328375194250f, -0.515417878019463260f, - -0.856938977417828540f, -0.514102744193221770f, -0.857728610000272010f, - -0.512786400633562960f, -0.858516224264442850f, -0.511468850437970190f, - -0.859301818357008470f, -0.510150096706767250f, -0.860085390429389920f, - -0.508830142543107320f, -0.860866938637767090f, -0.507508991052970980f, - -0.861646461143081190f, -0.506186645345155340f, -0.862423956111040500f, - -0.504863108531267370f, -0.863199421712124270f, -0.503538383725718020f, - -0.863972856121586470f, -0.502212474045711120f, -0.864744257519462160f, - -0.500885382611241050f, -0.865513624090568980f, -0.499557112545082000f, - -0.866280954024512880f, -0.498227666972781810f, -0.867046245515692650f, - -0.496897049022654360f, -0.867809496763303320f, -0.495565261825772980f, - -0.868570705971340670f, -0.494232308515960060f, -0.869329871348606620f, - -0.492898192229784200f, -0.870086991108711350f, -0.491562916106549950f, - -0.870842063470078860f, -0.490226483288291050f, -0.871595086655951090f, - -0.488888896919763730f, -0.872346058894391210f, -0.487550160148436330f, - -0.873094978418289870f, -0.486210276124486640f, -0.873841843465366750f, - -0.484869248000791180f, -0.874586652278176110f, -0.483527078932918690f, - -0.875329403104110890f, -0.482183772079122550f, -0.876070094195406710f, - -0.480839330600334400f, -0.876808723809145430f, -0.479493757660153340f, - -0.877545290207261130f, -0.478147056424843230f, -0.878279791656541460f, - -0.476799230063322140f, -0.879012226428633410f, -0.475450281747155760f, - -0.879742592800047520f, -0.474100214650550520f, -0.880470889052160530f, - -0.472749031950343180f, -0.881197113471221870f, -0.471396736825997860f, - -0.881921264348354940f, -0.470043332459595730f, -0.882643339979562680f, - -0.468688822035827900f, -0.883363338665731580f, -0.467333208741988250f, - -0.884081258712635100f, -0.465976495767966630f, -0.884797098430937570f, - -0.464618686306238150f, -0.885510856136199730f, -0.463259783551860370f, - -0.886222530148880530f, -0.461899790702462790f, -0.886932118794342190f, - -0.460538710958239890f, -0.887639620402854050f, -0.459176547521944640f, - -0.888345033309596020f, -0.457813303598877620f, -0.889048355854664350f, - -0.456448982396884200f, -0.889749586383072670f, -0.455083587126343950f, - -0.890448723244757880f, -0.453717121000163810f, -0.891145764794583290f, - -0.452349587233770670f, -0.891840709392342830f, -0.450980989045104310f, - -0.892533555402764360f, -0.449611329654606930f, -0.893224301195515210f, - -0.448240612285220110f, -0.893912945145203140f, -0.446868840162374210f, - -0.894599485631382700f, -0.445496016513981630f, -0.895283921038557580f, - -0.444122144570429760f, -0.895966249756184880f, -0.442747227564570410f, - -0.896646470178680040f, -0.441371268731716950f, -0.897324580705418210f, - -0.439994271309633370f, -0.898000579740739770f, -0.438616238538527600f, - -0.898674465693953820f, -0.437237173661043920f, -0.899346236979341680f, - -0.435857079922255970f, -0.900015892016159950f, -0.434475960569656040f, - -0.900683429228646750f, -0.433093818853152120f, -0.901348847046021920f, - -0.431710658025057310f, -0.902012143902493180f, -0.430326481340082500f, - -0.902673318237258830f, -0.428941292055330050f, -0.903332368494511600f, - -0.427555093430282470f, -0.903989293123443120f, -0.426167888726799890f, - -0.904644090578246130f, -0.424779681209108920f, -0.905296759318118700f, - -0.423390474143795990f, -0.905947297807268460f, -0.422000270799799520f, - -0.906595704514915450f, -0.420609074448403010f, -0.907241977915295590f, - -0.419216888363224290f, -0.907886116487666040f, -0.417823715820212490f, - -0.908528118716306010f, -0.416429560097637210f, -0.909167983090522380f, - -0.415034424476081520f, -0.909805708104652330f, -0.413638312238435110f, - -0.910441292258066910f, -0.412241226669883280f, -0.911074734055176140f, - -0.410843171057904190f, -0.911706032005429770f, -0.409444148692257760f, - -0.912335184623322750f, -0.408044162864978630f, -0.912962190428398210f, - -0.406643216870368810f, -0.913587047945250920f, -0.405241314004990360f, - -0.914209755703530470f, -0.403838457567654460f, -0.914830312237945980f, - -0.402434650859418650f, -0.915448716088267720f, -0.401029897183575680f, - -0.916064965799331720f, -0.399624199845646730f, -0.916679059921042700f, - -0.398217562153374170f, -0.917290997008377680f, -0.396809987416710750f, - -0.917900775621390270f, -0.395401478947816580f, -0.918508394325212140f, - -0.393992040061048210f, -0.919113851690057660f, -0.392581674072951470f, - -0.919717146291227360f, -0.391170384302253700f, -0.920318276709110590f, - -0.389758174069856970f, -0.920917241529189300f, -0.388345046698826630f, - -0.921514039342041790f, -0.386931005514388800f, -0.922108668743345070f, - -0.385516053843918900f, -0.922701128333878520f, -0.384100195016934930f, - -0.923291416719527640f, -0.382683432365090340f, -0.923879532511286520f, - -0.381265769222162760f, -0.924465474325262490f, -0.379847208924051440f, - -0.925049240782677470f, -0.378427754808765730f, -0.925630830509872720f, - -0.377007410216418200f, -0.926210242138311380f, -0.375586178489217050f, - -0.926787474304581860f, -0.374164062971458490f, -0.927362525650400890f, - -0.372741067009516150f, -0.927935394822617670f, -0.371317193951837770f, - -0.928506080473215480f, -0.369892447148934160f, -0.929074581259315750f, - -0.368466829953372210f, -0.929640895843181330f, -0.367040345719766960f, - -0.930205022892219180f, -0.365612997804774300f, -0.930766961078983600f, - -0.364184789567080170f, -0.931326709081180320f, -0.362755724367397340f, - -0.931884265581668040f, -0.361325805568454230f, -0.932439629268462360f, - -0.359895036534987940f, -0.932992798834738960f, -0.358463420633737040f, - -0.933543772978835950f, -0.357030961233430370f, -0.934092550404258760f, - -0.355597661704784070f, -0.934639129819680670f, -0.354163525420490450f, - -0.935183509938947610f, -0.352728555755210620f, -0.935725689481080370f, - -0.351292756085566870f, -0.936265667170278370f, -0.349856129790135360f, - -0.936803441735921450f, -0.348418680249434840f, -0.937339011912574850f, - -0.346980410845923790f, -0.937872376439989770f, -0.345541324963989040f, - -0.938403534063108170f, -0.344101425989938650f, -0.938932483532064600f, - -0.342660717311994880f, -0.939459223602189700f, -0.341219202320282740f, - -0.939983753034013820f, -0.339776884406827070f, -0.940506070593268300f, - -0.338333766965541240f, -0.941026175050889260f, -0.336889853392219940f, - -0.941544065183020810f, -0.335445147084531380f, -0.942059739771017420f, - -0.333999651442009830f, -0.942573197601446760f, -0.332553369866044500f, - -0.943084437466093380f, -0.331106305759876540f, -0.943593458161960270f, - -0.329658462528587490f, -0.944100258491272660f, -0.328209843579092330f, - -0.944604837261480370f, -0.326760452320132290f, -0.945107193285260380f, - -0.325310292162263310f, -0.945607325380521170f, -0.323859366517853080f, - -0.946105232370403340f, -0.322407678801069910f, -0.946600913083283530f, - -0.320955232427875160f, -0.947094366352777220f, -0.319502030816015410f, - -0.947585591017741200f, -0.318048077385015390f, -0.948074585922276110f, - -0.316593375556166180f, -0.948561349915730160f, -0.315137928752522560f, - -0.949045881852700560f, -0.313681740398891460f, -0.949528180593036670f, - -0.312224813921824770f, -0.950008245001843110f, -0.310767152749612030f, - -0.950486073949481590f, -0.309308760312269060f, -0.950961666311574970f, - -0.307849640041535090f, -0.951435020969008340f, -0.306389795370861030f, - -0.951906136807932350f, -0.304929229735402320f, -0.952375012719765880f, - -0.303467946572011040f, -0.952841647601198720f, -0.302005949319228530f, - -0.953306040354193750f, -0.300543241417273730f, -0.953768189885990210f, - -0.299079826308040590f, -0.954228095109105560f, -0.297615707435086200f, - -0.954685754941338340f, -0.296150888243623680f, -0.955141168305770780f, - -0.294685372180514880f, -0.955594334130770880f, -0.293219162694259020f, - -0.956045251349996290f, -0.291752263234989480f, -0.956493918902394990f, - -0.290284677254462440f, -0.956940335732208820f, -0.288816408206049370f, - -0.957384500788975970f, -0.287347459544729290f, -0.957826413027533020f, - -0.285877834727081060f, -0.958266071408017560f, -0.284407537211272150f, - -0.958703474895871490f, -0.282936570457055500f, -0.959138622461841890f, - -0.281464937925757940f, -0.959571513081984520f, -0.279992643080273050f, - -0.960002145737665960f, -0.278519689385053610f, -0.960430519415565680f, - -0.277046080306100280f, -0.960856633107679550f, -0.275571819310958370f, - -0.961280485811320530f, -0.274096909868706440f, -0.961702076529122540f, - -0.272621355449948870f, -0.962121404269041580f, -0.271145159526807790f, - -0.962538468044359270f, -0.269668325572915530f, -0.962953266873683770f, - -0.268190857063403510f, -0.963365799780953940f, -0.266712757474898530f, - -0.963776065795439840f, -0.265234030285511790f, -0.964184063951745830f, - -0.263754678974831240f, -0.964589793289812760f, -0.262274707023914140f, - -0.964993252854920210f, -0.260794117915275900f, -0.965394441697689290f, - -0.259312915132886460f, -0.965793358874083570f, -0.257831102162159040f, - -0.966190003445412500f, -0.256348682489942800f, -0.966584374478333120f, - -0.254865659604514350f, -0.966976471044852180f, -0.253382036995570600f, - -0.967366292222328390f, -0.251897818154217250f, -0.967753837093475400f, - -0.250413006572965390f, -0.968139104746362330f, -0.248927605745720150f, - -0.968522094274417270f, -0.247441619167773130f, -0.968902804776428870f, - -0.245955050335795150f, -0.969281235356548310f, -0.244467902747824540f, - -0.969657385124292340f, -0.242980179903264120f, -0.970031253194543970f, - -0.241491885302869410f, -0.970402838687555500f, -0.240003022448741390f, - -0.970772140728950350f, -0.238513594844318190f, -0.971139158449725200f, - -0.237023605994367670f, -0.971503890986251670f, -0.235533059404975790f, - -0.971866337480279290f, -0.234041958583543570f, -0.972226497078936270f, - -0.232550307038775220f, -0.972584368934732210f, -0.231058108280670940f, - -0.972939952205560180f, -0.229565365820519420f, -0.973293246054698140f, - -0.228072083170886120f, -0.973644249650811870f, -0.226578263845610220f, - -0.973992962167955830f, -0.225083911359792920f, -0.974339382785575860f, - -0.223589029229789900f, -0.974683510688510670f, -0.222093620973203290f, - -0.975025345066994230f, -0.220597690108873980f, -0.975364885116656870f, - -0.219101240156870100f, -0.975702130038528460f, -0.217604274638483780f, - -0.976037079039039020f, -0.216106797076219490f, -0.976369731330021140f, - -0.214608810993786620f, -0.976700086128711840f, -0.213110319916091920f, - -0.977028142657754280f, -0.211611327369227970f, -0.977353900145199960f, - -0.210111836880469860f, -0.977677357824509930f, -0.208611851978263570f, - -0.977998514934557030f, -0.207111376192218480f, -0.978317370719627650f, - -0.205610413053099020f, -0.978633924429423210f, -0.204108966092817340f, - -0.978948175319062090f, -0.202607038844421440f, -0.979260122649082020f, - -0.201104634842092070f, -0.979569765685440520f, -0.199601757621130970f, - -0.979877103699517640f, -0.198098410717953420f, -0.980182135968117430f, - -0.196594597670080780f, -0.980484861773469270f, -0.195090322016128660f, - -0.980785280403230320f, -0.193585587295803860f, -0.981083391150486590f, - -0.192080397049892520f, -0.981379193313754560f, -0.190574754820252680f, - -0.981672686196983110f, -0.189068664149805970f, -0.981963869109555350f, - -0.187562128582530070f, -0.982252741366289370f, -0.186055151663446970f, - -0.982539302287441240f, -0.184547736938619780f, -0.982823551198705240f, - -0.183039887955140950f, -0.983105487431216290f, -0.181531608261124830f, - -0.983385110321551290f, -0.180022901405700070f, -0.983662419211730140f, - -0.178513770938997920f, -0.983937413449218810f, -0.177004220412149000f, - -0.984210092386929030f, -0.175494253377271510f, -0.984480455383220930f, - -0.173983873387463740f, -0.984748501801904210f, -0.172473083996795730f, - -0.985014231012239840f, -0.170961888760301690f, -0.985277642388941110f, - -0.169450291233968290f, -0.985538735312176060f, -0.167938294974731340f, - -0.985797509167567370f, -0.166425903540464100f, -0.986053963346195440f, - -0.164913120489969760f, -0.986308097244598670f, -0.163399949382973780f, - -0.986559910264775410f, -0.161886393780112240f, -0.986809401814185420f, - -0.160372457242928510f, -0.987056571305750970f, -0.158858143333861530f, - -0.987301418157858320f, -0.157343455616238190f, -0.987543941794359340f, - -0.155828397654264980f, -0.987784141644572180f, -0.154312973013020580f, - -0.988022017143283530f, -0.152797185258443740f, -0.988257567730749460f, - -0.151281037957330360f, -0.988490792852696590f, -0.149764534677321510f, - -0.988721691960323780f, -0.148247678986895890f, -0.988950264510302990f, - -0.146730474455362300f, -0.989176509964780900f, -0.145212924652847850f, - -0.989400427791380270f, -0.143695033150294690f, -0.989622017463200780f, - -0.142176803519448140f, -0.989841278458820530f, -0.140658239332849160f, - -0.990058210262297120f, -0.139139344163825980f, -0.990272812363169110f, - -0.137620121586486540f, -0.990485084256456980f, -0.136100575175706530f, - -0.990695025442664630f, -0.134580708507126360f, -0.990902635427780010f, - -0.133060525157139060f, -0.991107913723276890f, -0.131540028702882950f, - -0.991310859846115440f, -0.130019222722233930f, -0.991511473318743900f, - -0.128498110793793590f, -0.991709753669099530f, -0.126976696496886120f, - -0.991905700430609330f, -0.125454983411546320f, -0.992099313142191800f, - -0.123932975118512090f, -0.992290591348257370f, -0.122410675199215960f, - -0.992479534598710080f, -0.120888087235777570f, -0.992666142448947910f, - -0.119365214810991690f, -0.992850414459865100f, -0.117842061508325140f, - -0.993032350197851410f, -0.116318630911904770f, -0.993211949234794500f, - -0.114794926606509930f, -0.993389211148080650f, -0.113270952177564920f, - -0.993564135520595300f, -0.111746711211127000f, -0.993736721940724600f, - -0.110222207293883310f, -0.993906970002356060f, -0.108697444013138800f, - -0.994074879304879370f, -0.107172424956808770f, -0.994240449453187900f, - -0.105647153713410380f, -0.994403680057679100f, -0.104121633872055070f, - -0.994564570734255420f, -0.102595869022436610f, -0.994723121104325700f, - -0.101069862754827990f, -0.994879330794805620f, -0.099543618660069347f, - -0.995033199438118630f, -0.098017140329560451f, -0.995184726672196930f, - -0.096490431355253162f, -0.995333912140482170f, -0.094963495329639408f, - -0.995480755491926940f, -0.093436335845748036f, -0.995625256380994310f, - -0.091908956497132821f, -0.995767414467659820f, -0.090381360877864914f, - -0.995907229417411720f, -0.088853552582524364f, -0.996044700901251970f, - -0.087325535206192559f, -0.996179828595696870f, -0.085797312344440227f, - -0.996312612182778000f, -0.084268887593324238f, -0.996443051350042630f, - -0.082740264549375706f, -0.996571145790554840f, -0.081211446809592289f, - -0.996696895202896060f, -0.079682437971430695f, -0.996820299291165670f, - -0.078153241632794648f, -0.996941357764982050f, -0.076623861392031742f, - -0.997060070339482960f, -0.075094300847921402f, -0.997176436735326080f, - -0.073564563599667357f, -0.997290456678690210f, -0.072034653246889097f, - -0.997402129901275300f, -0.070504573389614356f, -0.997511456140303450f, - -0.068974327628267079f, -0.997618435138519550f, -0.067443919563664231f, - -0.997723066644191640f, -0.065913352797003832f, -0.997825350411111640f, - -0.064382630929857312f, -0.997925286198596000f, -0.062851757564161989f, - -0.998022873771486130f, -0.061320736302208995f, -0.998118112900149180f, - -0.059789570746640132f, -0.998211003360478190f, -0.058258264500435857f, - -0.998301544933892780f, -0.056726821166907686f, -0.998389737407340160f, - -0.055195244349689712f, -0.998475580573294770f, -0.053663537652731026f, - -0.998559074229759310f, -0.052131704680283657f, -0.998640218180265160f, - -0.050599749036899455f, -0.998719012233872940f, -0.049067674327418029f, - -0.998795456205172410f, -0.047535484156959157f, -0.998869549914283560f, - -0.046003182130915206f, -0.998941293186856870f, -0.044470771854939084f, - -0.999010685854073270f, -0.042938256934941084f, -0.999077727752645360f, - -0.041405640977076837f, -0.999142418724816910f, -0.039872927587739748f, - -0.999204758618363890f, -0.038340120373552472f, -0.999264747286594420f, - -0.036807222941359331f, -0.999322384588349430f, -0.035274238898214294f, - -0.999377670388002850f, -0.033741171851377760f, -0.999430604555461730f, - -0.032208025408304600f, -0.999481186966166950f, -0.030674803176636484f, - -0.999529417501093140f, -0.029141508764194309f, -0.999575296046749220f, - -0.027608145778966163f, -0.999618822495178640f, -0.026074717829104161f, - -0.999659996743959220f, -0.024541228522912389f, -0.999698818696204250f, - -0.023007681468839310f, -0.999735288260561680f, -0.021474080275469286f, - -0.999769405351215280f, -0.019940428551514944f, -0.999801169887884260f, - -0.018406729905805164f, -0.999830581795823400f, -0.016872987947281894f, - -0.999857641005823860f, -0.015339206284988121f, -0.999882347454212560f, - -0.013805388528060250f, -0.999904701082852900f, -0.012271538285720512f, - -0.999924701839144500f, -0.010737659167264916f, -0.999942349676023910f, - -0.009203754782060083f, -0.999957644551963900f, -0.007669828739531199f, - -0.999970586430974140f, -0.006135884649154416f, -0.999981175282601110f, - -0.004601926120448350f, -0.999989411081928400f, -0.003067956762966483f, - -0.999995293809576190f, -0.001533980186285111f, -0.999998823451701880f, -}; - -/* -* @brief Q31 Twiddle factors Table -*/ - -/** -* \par -* Example code for Q31 Twiddle factors Generation:: -* \par -*
for(i = 0; i< 3N/4; i++)    
-* {    
-*    twiddleCoefQ31[2*i]= cos(i * 2*PI/(float)N);    
-*    twiddleCoefQ31[2*i+1]= sin(i * 2*PI/(float)N);    
-* } 
-* \par -* where N = 4096 and PI = 3.14159265358979 -* \par -* Cos and Sin values are interleaved fashion -* \par -* Convert Floating point to Q31(Fixed point 1.31): -* round(twiddleCoefQ31(i) * pow(2, 31)) -* -*/ - -const q31_t twiddleCoefQ31[6144] = { - 0x7fffffff, 0x0, 0x7ffff621, 0x3243f5, 0x7fffd886, 0x6487e3, 0x7fffa72c, - 0x96cbc1, - 0x7fff6216, 0xc90f88, 0x7fff0943, 0xfb5330, 0x7ffe9cb2, 0x12d96b1, - 0x7ffe1c65, 0x15fda03, - 0x7ffd885a, 0x1921d20, 0x7ffce093, 0x1c45ffe, 0x7ffc250f, 0x1f6a297, - 0x7ffb55ce, 0x228e4e2, - 0x7ffa72d1, 0x25b26d7, 0x7ff97c18, 0x28d6870, 0x7ff871a2, 0x2bfa9a4, - 0x7ff75370, 0x2f1ea6c, - 0x7ff62182, 0x3242abf, 0x7ff4dbd9, 0x3566a96, 0x7ff38274, 0x388a9ea, - 0x7ff21553, 0x3bae8b2, - 0x7ff09478, 0x3ed26e6, 0x7feeffe1, 0x41f6480, 0x7fed5791, 0x451a177, - 0x7feb9b85, 0x483ddc3, - 0x7fe9cbc0, 0x4b6195d, 0x7fe7e841, 0x4e8543e, 0x7fe5f108, 0x51a8e5c, - 0x7fe3e616, 0x54cc7b1, - 0x7fe1c76b, 0x57f0035, 0x7fdf9508, 0x5b137df, 0x7fdd4eec, 0x5e36ea9, - 0x7fdaf519, 0x615a48b, - 0x7fd8878e, 0x647d97c, 0x7fd6064c, 0x67a0d76, 0x7fd37153, 0x6ac406f, - 0x7fd0c8a3, 0x6de7262, - 0x7fce0c3e, 0x710a345, 0x7fcb3c23, 0x742d311, 0x7fc85854, 0x77501be, - 0x7fc560cf, 0x7a72f45, - 0x7fc25596, 0x7d95b9e, 0x7fbf36aa, 0x80b86c2, 0x7fbc040a, 0x83db0a7, - 0x7fb8bdb8, 0x86fd947, - 0x7fb563b3, 0x8a2009a, 0x7fb1f5fc, 0x8d42699, 0x7fae7495, 0x9064b3a, - 0x7faadf7c, 0x9386e78, - 0x7fa736b4, 0x96a9049, 0x7fa37a3c, 0x99cb0a7, 0x7f9faa15, 0x9cecf89, - 0x7f9bc640, 0xa00ece8, - 0x7f97cebd, 0xa3308bd, 0x7f93c38c, 0xa6522fe, 0x7f8fa4b0, 0xa973ba5, - 0x7f8b7227, 0xac952aa, - 0x7f872bf3, 0xafb6805, 0x7f82d214, 0xb2d7baf, 0x7f7e648c, 0xb5f8d9f, - 0x7f79e35a, 0xb919dcf, - 0x7f754e80, 0xbc3ac35, 0x7f70a5fe, 0xbf5b8cb, 0x7f6be9d4, 0xc27c389, - 0x7f671a05, 0xc59cc68, - 0x7f62368f, 0xc8bd35e, 0x7f5d3f75, 0xcbdd865, 0x7f5834b7, 0xcefdb76, - 0x7f531655, 0xd21dc87, - 0x7f4de451, 0xd53db92, 0x7f489eaa, 0xd85d88f, 0x7f434563, 0xdb7d376, - 0x7f3dd87c, 0xde9cc40, - 0x7f3857f6, 0xe1bc2e4, 0x7f32c3d1, 0xe4db75b, 0x7f2d1c0e, 0xe7fa99e, - 0x7f2760af, 0xeb199a4, - 0x7f2191b4, 0xee38766, 0x7f1baf1e, 0xf1572dc, 0x7f15b8ee, 0xf475bff, - 0x7f0faf25, 0xf7942c7, - 0x7f0991c4, 0xfab272b, 0x7f0360cb, 0xfdd0926, 0x7efd1c3c, 0x100ee8ad, - 0x7ef6c418, 0x1040c5bb, - 0x7ef05860, 0x1072a048, 0x7ee9d914, 0x10a4784b, 0x7ee34636, 0x10d64dbd, - 0x7edc9fc6, 0x11082096, - 0x7ed5e5c6, 0x1139f0cf, 0x7ecf1837, 0x116bbe60, 0x7ec8371a, 0x119d8941, - 0x7ec14270, 0x11cf516a, - 0x7eba3a39, 0x120116d5, 0x7eb31e78, 0x1232d979, 0x7eabef2c, 0x1264994e, - 0x7ea4ac58, 0x1296564d, - 0x7e9d55fc, 0x12c8106f, 0x7e95ec1a, 0x12f9c7aa, 0x7e8e6eb2, 0x132b7bf9, - 0x7e86ddc6, 0x135d2d53, - 0x7e7f3957, 0x138edbb1, 0x7e778166, 0x13c0870a, 0x7e6fb5f4, 0x13f22f58, - 0x7e67d703, 0x1423d492, - 0x7e5fe493, 0x145576b1, 0x7e57dea7, 0x148715ae, 0x7e4fc53e, 0x14b8b17f, - 0x7e47985b, 0x14ea4a1f, - 0x7e3f57ff, 0x151bdf86, 0x7e37042a, 0x154d71aa, 0x7e2e9cdf, 0x157f0086, - 0x7e26221f, 0x15b08c12, - 0x7e1d93ea, 0x15e21445, 0x7e14f242, 0x16139918, 0x7e0c3d29, 0x16451a83, - 0x7e0374a0, 0x1676987f, - 0x7dfa98a8, 0x16a81305, 0x7df1a942, 0x16d98a0c, 0x7de8a670, 0x170afd8d, - 0x7ddf9034, 0x173c6d80, - 0x7dd6668f, 0x176dd9de, 0x7dcd2981, 0x179f429f, 0x7dc3d90d, 0x17d0a7bc, - 0x7dba7534, 0x1802092c, - 0x7db0fdf8, 0x183366e9, 0x7da77359, 0x1864c0ea, 0x7d9dd55a, 0x18961728, - 0x7d9423fc, 0x18c7699b, - 0x7d8a5f40, 0x18f8b83c, 0x7d808728, 0x192a0304, 0x7d769bb5, 0x195b49ea, - 0x7d6c9ce9, 0x198c8ce7, - 0x7d628ac6, 0x19bdcbf3, 0x7d58654d, 0x19ef0707, 0x7d4e2c7f, 0x1a203e1b, - 0x7d43e05e, 0x1a517128, - 0x7d3980ec, 0x1a82a026, 0x7d2f0e2b, 0x1ab3cb0d, 0x7d24881b, 0x1ae4f1d6, - 0x7d19eebf, 0x1b161479, - 0x7d0f4218, 0x1b4732ef, 0x7d048228, 0x1b784d30, 0x7cf9aef0, 0x1ba96335, - 0x7ceec873, 0x1bda74f6, - 0x7ce3ceb2, 0x1c0b826a, 0x7cd8c1ae, 0x1c3c8b8c, 0x7ccda169, 0x1c6d9053, - 0x7cc26de5, 0x1c9e90b8, - 0x7cb72724, 0x1ccf8cb3, 0x7cabcd28, 0x1d00843d, 0x7ca05ff1, 0x1d31774d, - 0x7c94df83, 0x1d6265dd, - 0x7c894bde, 0x1d934fe5, 0x7c7da505, 0x1dc4355e, 0x7c71eaf9, 0x1df5163f, - 0x7c661dbc, 0x1e25f282, - 0x7c5a3d50, 0x1e56ca1e, 0x7c4e49b7, 0x1e879d0d, 0x7c4242f2, 0x1eb86b46, - 0x7c362904, 0x1ee934c3, - 0x7c29fbee, 0x1f19f97b, 0x7c1dbbb3, 0x1f4ab968, 0x7c116853, 0x1f7b7481, - 0x7c0501d2, 0x1fac2abf, - 0x7bf88830, 0x1fdcdc1b, 0x7bebfb70, 0x200d888d, 0x7bdf5b94, 0x203e300d, - 0x7bd2a89e, 0x206ed295, - 0x7bc5e290, 0x209f701c, 0x7bb9096b, 0x20d0089c, 0x7bac1d31, 0x21009c0c, - 0x7b9f1de6, 0x21312a65, - 0x7b920b89, 0x2161b3a0, 0x7b84e61f, 0x219237b5, 0x7b77ada8, 0x21c2b69c, - 0x7b6a6227, 0x21f3304f, - 0x7b5d039e, 0x2223a4c5, 0x7b4f920e, 0x225413f8, 0x7b420d7a, 0x22847de0, - 0x7b3475e5, 0x22b4e274, - 0x7b26cb4f, 0x22e541af, 0x7b190dbc, 0x23159b88, 0x7b0b3d2c, 0x2345eff8, - 0x7afd59a4, 0x23763ef7, - 0x7aef6323, 0x23a6887f, 0x7ae159ae, 0x23d6cc87, 0x7ad33d45, 0x24070b08, - 0x7ac50dec, 0x243743fa, - 0x7ab6cba4, 0x24677758, 0x7aa8766f, 0x2497a517, 0x7a9a0e50, 0x24c7cd33, - 0x7a8b9348, 0x24f7efa2, - 0x7a7d055b, 0x25280c5e, 0x7a6e648a, 0x2558235f, 0x7a5fb0d8, 0x2588349d, - 0x7a50ea47, 0x25b84012, - 0x7a4210d8, 0x25e845b6, 0x7a332490, 0x26184581, 0x7a24256f, 0x26483f6c, - 0x7a151378, 0x26783370, - 0x7a05eead, 0x26a82186, 0x79f6b711, 0x26d809a5, 0x79e76ca7, 0x2707ebc7, - 0x79d80f6f, 0x2737c7e3, - 0x79c89f6e, 0x27679df4, 0x79b91ca4, 0x27976df1, 0x79a98715, 0x27c737d3, - 0x7999dec4, 0x27f6fb92, - 0x798a23b1, 0x2826b928, 0x797a55e0, 0x2856708d, 0x796a7554, 0x288621b9, - 0x795a820e, 0x28b5cca5, - 0x794a7c12, 0x28e5714b, 0x793a6361, 0x29150fa1, 0x792a37fe, 0x2944a7a2, - 0x7919f9ec, 0x29743946, - 0x7909a92d, 0x29a3c485, 0x78f945c3, 0x29d34958, 0x78e8cfb2, 0x2a02c7b8, - 0x78d846fb, 0x2a323f9e, - 0x78c7aba2, 0x2a61b101, 0x78b6fda8, 0x2a911bdc, 0x78a63d11, 0x2ac08026, - 0x789569df, 0x2aefddd8, - 0x78848414, 0x2b1f34eb, 0x78738bb3, 0x2b4e8558, 0x786280bf, 0x2b7dcf17, - 0x7851633b, 0x2bad1221, - 0x78403329, 0x2bdc4e6f, 0x782ef08b, 0x2c0b83fa, 0x781d9b65, 0x2c3ab2b9, - 0x780c33b8, 0x2c69daa6, - 0x77fab989, 0x2c98fbba, 0x77e92cd9, 0x2cc815ee, 0x77d78daa, 0x2cf72939, - 0x77c5dc01, 0x2d263596, - 0x77b417df, 0x2d553afc, 0x77a24148, 0x2d843964, 0x7790583e, 0x2db330c7, - 0x777e5cc3, 0x2de2211e, - 0x776c4edb, 0x2e110a62, 0x775a2e89, 0x2e3fec8b, 0x7747fbce, 0x2e6ec792, - 0x7735b6af, 0x2e9d9b70, - 0x77235f2d, 0x2ecc681e, 0x7710f54c, 0x2efb2d95, 0x76fe790e, 0x2f29ebcc, - 0x76ebea77, 0x2f58a2be, - 0x76d94989, 0x2f875262, 0x76c69647, 0x2fb5fab2, 0x76b3d0b4, 0x2fe49ba7, - 0x76a0f8d2, 0x30133539, - 0x768e0ea6, 0x3041c761, 0x767b1231, 0x30705217, 0x76680376, 0x309ed556, - 0x7654e279, 0x30cd5115, - 0x7641af3d, 0x30fbc54d, 0x762e69c4, 0x312a31f8, 0x761b1211, 0x3158970e, - 0x7607a828, 0x3186f487, - 0x75f42c0b, 0x31b54a5e, 0x75e09dbd, 0x31e39889, 0x75ccfd42, 0x3211df04, - 0x75b94a9c, 0x32401dc6, - 0x75a585cf, 0x326e54c7, 0x7591aedd, 0x329c8402, 0x757dc5ca, 0x32caab6f, - 0x7569ca99, 0x32f8cb07, - 0x7555bd4c, 0x3326e2c3, 0x75419de7, 0x3354f29b, 0x752d6c6c, 0x3382fa88, - 0x751928e0, 0x33b0fa84, - 0x7504d345, 0x33def287, 0x74f06b9e, 0x340ce28b, 0x74dbf1ef, 0x343aca87, - 0x74c7663a, 0x3468aa76, - 0x74b2c884, 0x34968250, 0x749e18cd, 0x34c4520d, 0x7489571c, 0x34f219a8, - 0x74748371, 0x351fd918, - 0x745f9dd1, 0x354d9057, 0x744aa63f, 0x357b3f5d, 0x74359cbd, 0x35a8e625, - 0x74208150, 0x35d684a6, - 0x740b53fb, 0x36041ad9, 0x73f614c0, 0x3631a8b8, 0x73e0c3a3, 0x365f2e3b, - 0x73cb60a8, 0x368cab5c, - 0x73b5ebd1, 0x36ba2014, 0x73a06522, 0x36e78c5b, 0x738acc9e, 0x3714f02a, - 0x73752249, 0x37424b7b, - 0x735f6626, 0x376f9e46, 0x73499838, 0x379ce885, 0x7333b883, 0x37ca2a30, - 0x731dc70a, 0x37f76341, - 0x7307c3d0, 0x382493b0, 0x72f1aed9, 0x3851bb77, 0x72db8828, 0x387eda8e, - 0x72c54fc1, 0x38abf0ef, - 0x72af05a7, 0x38d8fe93, 0x7298a9dd, 0x39060373, 0x72823c67, 0x3932ff87, - 0x726bbd48, 0x395ff2c9, - 0x72552c85, 0x398cdd32, 0x723e8a20, 0x39b9bebc, 0x7227d61c, 0x39e6975e, - 0x7211107e, 0x3a136712, - 0x71fa3949, 0x3a402dd2, 0x71e35080, 0x3a6ceb96, 0x71cc5626, 0x3a99a057, - 0x71b54a41, 0x3ac64c0f, - 0x719e2cd2, 0x3af2eeb7, 0x7186fdde, 0x3b1f8848, 0x716fbd68, 0x3b4c18ba, - 0x71586b74, 0x3b78a007, - 0x71410805, 0x3ba51e29, 0x7129931f, 0x3bd19318, 0x71120cc5, 0x3bfdfecd, - 0x70fa74fc, 0x3c2a6142, - 0x70e2cbc6, 0x3c56ba70, 0x70cb1128, 0x3c830a50, 0x70b34525, 0x3caf50da, - 0x709b67c0, 0x3cdb8e09, - 0x708378ff, 0x3d07c1d6, 0x706b78e3, 0x3d33ec39, 0x70536771, 0x3d600d2c, - 0x703b44ad, 0x3d8c24a8, - 0x7023109a, 0x3db832a6, 0x700acb3c, 0x3de4371f, 0x6ff27497, 0x3e10320d, - 0x6fda0cae, 0x3e3c2369, - 0x6fc19385, 0x3e680b2c, 0x6fa90921, 0x3e93e950, 0x6f906d84, 0x3ebfbdcd, - 0x6f77c0b3, 0x3eeb889c, - 0x6f5f02b2, 0x3f1749b8, 0x6f463383, 0x3f430119, 0x6f2d532c, 0x3f6eaeb8, - 0x6f1461b0, 0x3f9a5290, - 0x6efb5f12, 0x3fc5ec98, 0x6ee24b57, 0x3ff17cca, 0x6ec92683, 0x401d0321, - 0x6eaff099, 0x40487f94, - 0x6e96a99d, 0x4073f21d, 0x6e7d5193, 0x409f5ab6, 0x6e63e87f, 0x40cab958, - 0x6e4a6e66, 0x40f60dfb, - 0x6e30e34a, 0x4121589b, 0x6e174730, 0x414c992f, 0x6dfd9a1c, 0x4177cfb1, - 0x6de3dc11, 0x41a2fc1a, - 0x6dca0d14, 0x41ce1e65, 0x6db02d29, 0x41f93689, 0x6d963c54, 0x42244481, - 0x6d7c3a98, 0x424f4845, - 0x6d6227fa, 0x427a41d0, 0x6d48047e, 0x42a5311b, 0x6d2dd027, 0x42d0161e, - 0x6d138afb, 0x42faf0d4, - 0x6cf934fc, 0x4325c135, 0x6cdece2f, 0x4350873c, 0x6cc45698, 0x437b42e1, - 0x6ca9ce3b, 0x43a5f41e, - 0x6c8f351c, 0x43d09aed, 0x6c748b3f, 0x43fb3746, 0x6c59d0a9, 0x4425c923, - 0x6c3f055d, 0x4450507e, - 0x6c242960, 0x447acd50, 0x6c093cb6, 0x44a53f93, 0x6bee3f62, 0x44cfa740, - 0x6bd3316a, 0x44fa0450, - 0x6bb812d1, 0x452456bd, 0x6b9ce39b, 0x454e9e80, 0x6b81a3cd, 0x4578db93, - 0x6b66536b, 0x45a30df0, - 0x6b4af279, 0x45cd358f, 0x6b2f80fb, 0x45f7526b, 0x6b13fef5, 0x4621647d, - 0x6af86c6c, 0x464b6bbe, - 0x6adcc964, 0x46756828, 0x6ac115e2, 0x469f59b4, 0x6aa551e9, 0x46c9405c, - 0x6a897d7d, 0x46f31c1a, - 0x6a6d98a4, 0x471cece7, 0x6a51a361, 0x4746b2bc, 0x6a359db9, 0x47706d93, - 0x6a1987b0, 0x479a1d67, - 0x69fd614a, 0x47c3c22f, 0x69e12a8c, 0x47ed5be6, 0x69c4e37a, 0x4816ea86, - 0x69a88c19, 0x48406e08, - 0x698c246c, 0x4869e665, 0x696fac78, 0x48935397, 0x69532442, 0x48bcb599, - 0x69368bce, 0x48e60c62, - 0x6919e320, 0x490f57ee, 0x68fd2a3d, 0x49389836, 0x68e06129, 0x4961cd33, - 0x68c387e9, 0x498af6df, - 0x68a69e81, 0x49b41533, 0x6889a4f6, 0x49dd282a, 0x686c9b4b, 0x4a062fbd, - 0x684f8186, 0x4a2f2be6, - 0x683257ab, 0x4a581c9e, 0x68151dbe, 0x4a8101de, 0x67f7d3c5, 0x4aa9dba2, - 0x67da79c3, 0x4ad2a9e2, - 0x67bd0fbd, 0x4afb6c98, 0x679f95b7, 0x4b2423be, 0x67820bb7, 0x4b4ccf4d, - 0x676471c0, 0x4b756f40, - 0x6746c7d8, 0x4b9e0390, 0x67290e02, 0x4bc68c36, 0x670b4444, 0x4bef092d, - 0x66ed6aa1, 0x4c177a6e, - 0x66cf8120, 0x4c3fdff4, 0x66b187c3, 0x4c6839b7, 0x66937e91, 0x4c9087b1, - 0x6675658c, 0x4cb8c9dd, - 0x66573cbb, 0x4ce10034, 0x66390422, 0x4d092ab0, 0x661abbc5, 0x4d31494b, - 0x65fc63a9, 0x4d595bfe, - 0x65ddfbd3, 0x4d8162c4, 0x65bf8447, 0x4da95d96, 0x65a0fd0b, 0x4dd14c6e, - 0x65826622, 0x4df92f46, - 0x6563bf92, 0x4e210617, 0x6545095f, 0x4e48d0dd, 0x6526438f, 0x4e708f8f, - 0x65076e25, 0x4e984229, - 0x64e88926, 0x4ebfe8a5, 0x64c99498, 0x4ee782fb, 0x64aa907f, 0x4f0f1126, - 0x648b7ce0, 0x4f369320, - 0x646c59bf, 0x4f5e08e3, 0x644d2722, 0x4f857269, 0x642de50d, 0x4faccfab, - 0x640e9386, 0x4fd420a4, - 0x63ef3290, 0x4ffb654d, 0x63cfc231, 0x50229da1, 0x63b0426d, 0x5049c999, - 0x6390b34a, 0x5070e92f, - 0x637114cc, 0x5097fc5e, 0x635166f9, 0x50bf031f, 0x6331a9d4, 0x50e5fd6d, - 0x6311dd64, 0x510ceb40, - 0x62f201ac, 0x5133cc94, 0x62d216b3, 0x515aa162, 0x62b21c7b, 0x518169a5, - 0x6292130c, 0x51a82555, - 0x6271fa69, 0x51ced46e, 0x6251d298, 0x51f576ea, 0x62319b9d, 0x521c0cc2, - 0x6211557e, 0x524295f0, - 0x61f1003f, 0x5269126e, 0x61d09be5, 0x528f8238, 0x61b02876, 0x52b5e546, - 0x618fa5f7, 0x52dc3b92, - 0x616f146c, 0x53028518, 0x614e73da, 0x5328c1d0, 0x612dc447, 0x534ef1b5, - 0x610d05b7, 0x537514c2, - 0x60ec3830, 0x539b2af0, 0x60cb5bb7, 0x53c13439, 0x60aa7050, 0x53e73097, - 0x60897601, 0x540d2005, - 0x60686ccf, 0x5433027d, 0x604754bf, 0x5458d7f9, 0x60262dd6, 0x547ea073, - 0x6004f819, 0x54a45be6, - 0x5fe3b38d, 0x54ca0a4b, 0x5fc26038, 0x54efab9c, 0x5fa0fe1f, 0x55153fd4, - 0x5f7f8d46, 0x553ac6ee, - 0x5f5e0db3, 0x556040e2, 0x5f3c7f6b, 0x5585adad, 0x5f1ae274, 0x55ab0d46, - 0x5ef936d1, 0x55d05faa, - 0x5ed77c8a, 0x55f5a4d2, 0x5eb5b3a2, 0x561adcb9, 0x5e93dc1f, 0x56400758, - 0x5e71f606, 0x566524aa, - 0x5e50015d, 0x568a34a9, 0x5e2dfe29, 0x56af3750, 0x5e0bec6e, 0x56d42c99, - 0x5de9cc33, 0x56f9147e, - 0x5dc79d7c, 0x571deefa, 0x5da5604f, 0x5742bc06, 0x5d8314b1, 0x57677b9d, - 0x5d60baa7, 0x578c2dba, - 0x5d3e5237, 0x57b0d256, 0x5d1bdb65, 0x57d5696d, 0x5cf95638, 0x57f9f2f8, - 0x5cd6c2b5, 0x581e6ef1, - 0x5cb420e0, 0x5842dd54, 0x5c9170bf, 0x58673e1b, 0x5c6eb258, 0x588b9140, - 0x5c4be5b0, 0x58afd6bd, - 0x5c290acc, 0x58d40e8c, 0x5c0621b2, 0x58f838a9, 0x5be32a67, 0x591c550e, - 0x5bc024f0, 0x594063b5, - 0x5b9d1154, 0x59646498, 0x5b79ef96, 0x598857b2, 0x5b56bfbd, 0x59ac3cfd, - 0x5b3381ce, 0x59d01475, - 0x5b1035cf, 0x59f3de12, 0x5aecdbc5, 0x5a1799d1, 0x5ac973b5, 0x5a3b47ab, - 0x5aa5fda5, 0x5a5ee79a, - 0x5a82799a, 0x5a82799a, 0x5a5ee79a, 0x5aa5fda5, 0x5a3b47ab, 0x5ac973b5, - 0x5a1799d1, 0x5aecdbc5, - 0x59f3de12, 0x5b1035cf, 0x59d01475, 0x5b3381ce, 0x59ac3cfd, 0x5b56bfbd, - 0x598857b2, 0x5b79ef96, - 0x59646498, 0x5b9d1154, 0x594063b5, 0x5bc024f0, 0x591c550e, 0x5be32a67, - 0x58f838a9, 0x5c0621b2, - 0x58d40e8c, 0x5c290acc, 0x58afd6bd, 0x5c4be5b0, 0x588b9140, 0x5c6eb258, - 0x58673e1b, 0x5c9170bf, - 0x5842dd54, 0x5cb420e0, 0x581e6ef1, 0x5cd6c2b5, 0x57f9f2f8, 0x5cf95638, - 0x57d5696d, 0x5d1bdb65, - 0x57b0d256, 0x5d3e5237, 0x578c2dba, 0x5d60baa7, 0x57677b9d, 0x5d8314b1, - 0x5742bc06, 0x5da5604f, - 0x571deefa, 0x5dc79d7c, 0x56f9147e, 0x5de9cc33, 0x56d42c99, 0x5e0bec6e, - 0x56af3750, 0x5e2dfe29, - 0x568a34a9, 0x5e50015d, 0x566524aa, 0x5e71f606, 0x56400758, 0x5e93dc1f, - 0x561adcb9, 0x5eb5b3a2, - 0x55f5a4d2, 0x5ed77c8a, 0x55d05faa, 0x5ef936d1, 0x55ab0d46, 0x5f1ae274, - 0x5585adad, 0x5f3c7f6b, - 0x556040e2, 0x5f5e0db3, 0x553ac6ee, 0x5f7f8d46, 0x55153fd4, 0x5fa0fe1f, - 0x54efab9c, 0x5fc26038, - 0x54ca0a4b, 0x5fe3b38d, 0x54a45be6, 0x6004f819, 0x547ea073, 0x60262dd6, - 0x5458d7f9, 0x604754bf, - 0x5433027d, 0x60686ccf, 0x540d2005, 0x60897601, 0x53e73097, 0x60aa7050, - 0x53c13439, 0x60cb5bb7, - 0x539b2af0, 0x60ec3830, 0x537514c2, 0x610d05b7, 0x534ef1b5, 0x612dc447, - 0x5328c1d0, 0x614e73da, - 0x53028518, 0x616f146c, 0x52dc3b92, 0x618fa5f7, 0x52b5e546, 0x61b02876, - 0x528f8238, 0x61d09be5, - 0x5269126e, 0x61f1003f, 0x524295f0, 0x6211557e, 0x521c0cc2, 0x62319b9d, - 0x51f576ea, 0x6251d298, - 0x51ced46e, 0x6271fa69, 0x51a82555, 0x6292130c, 0x518169a5, 0x62b21c7b, - 0x515aa162, 0x62d216b3, - 0x5133cc94, 0x62f201ac, 0x510ceb40, 0x6311dd64, 0x50e5fd6d, 0x6331a9d4, - 0x50bf031f, 0x635166f9, - 0x5097fc5e, 0x637114cc, 0x5070e92f, 0x6390b34a, 0x5049c999, 0x63b0426d, - 0x50229da1, 0x63cfc231, - 0x4ffb654d, 0x63ef3290, 0x4fd420a4, 0x640e9386, 0x4faccfab, 0x642de50d, - 0x4f857269, 0x644d2722, - 0x4f5e08e3, 0x646c59bf, 0x4f369320, 0x648b7ce0, 0x4f0f1126, 0x64aa907f, - 0x4ee782fb, 0x64c99498, - 0x4ebfe8a5, 0x64e88926, 0x4e984229, 0x65076e25, 0x4e708f8f, 0x6526438f, - 0x4e48d0dd, 0x6545095f, - 0x4e210617, 0x6563bf92, 0x4df92f46, 0x65826622, 0x4dd14c6e, 0x65a0fd0b, - 0x4da95d96, 0x65bf8447, - 0x4d8162c4, 0x65ddfbd3, 0x4d595bfe, 0x65fc63a9, 0x4d31494b, 0x661abbc5, - 0x4d092ab0, 0x66390422, - 0x4ce10034, 0x66573cbb, 0x4cb8c9dd, 0x6675658c, 0x4c9087b1, 0x66937e91, - 0x4c6839b7, 0x66b187c3, - 0x4c3fdff4, 0x66cf8120, 0x4c177a6e, 0x66ed6aa1, 0x4bef092d, 0x670b4444, - 0x4bc68c36, 0x67290e02, - 0x4b9e0390, 0x6746c7d8, 0x4b756f40, 0x676471c0, 0x4b4ccf4d, 0x67820bb7, - 0x4b2423be, 0x679f95b7, - 0x4afb6c98, 0x67bd0fbd, 0x4ad2a9e2, 0x67da79c3, 0x4aa9dba2, 0x67f7d3c5, - 0x4a8101de, 0x68151dbe, - 0x4a581c9e, 0x683257ab, 0x4a2f2be6, 0x684f8186, 0x4a062fbd, 0x686c9b4b, - 0x49dd282a, 0x6889a4f6, - 0x49b41533, 0x68a69e81, 0x498af6df, 0x68c387e9, 0x4961cd33, 0x68e06129, - 0x49389836, 0x68fd2a3d, - 0x490f57ee, 0x6919e320, 0x48e60c62, 0x69368bce, 0x48bcb599, 0x69532442, - 0x48935397, 0x696fac78, - 0x4869e665, 0x698c246c, 0x48406e08, 0x69a88c19, 0x4816ea86, 0x69c4e37a, - 0x47ed5be6, 0x69e12a8c, - 0x47c3c22f, 0x69fd614a, 0x479a1d67, 0x6a1987b0, 0x47706d93, 0x6a359db9, - 0x4746b2bc, 0x6a51a361, - 0x471cece7, 0x6a6d98a4, 0x46f31c1a, 0x6a897d7d, 0x46c9405c, 0x6aa551e9, - 0x469f59b4, 0x6ac115e2, - 0x46756828, 0x6adcc964, 0x464b6bbe, 0x6af86c6c, 0x4621647d, 0x6b13fef5, - 0x45f7526b, 0x6b2f80fb, - 0x45cd358f, 0x6b4af279, 0x45a30df0, 0x6b66536b, 0x4578db93, 0x6b81a3cd, - 0x454e9e80, 0x6b9ce39b, - 0x452456bd, 0x6bb812d1, 0x44fa0450, 0x6bd3316a, 0x44cfa740, 0x6bee3f62, - 0x44a53f93, 0x6c093cb6, - 0x447acd50, 0x6c242960, 0x4450507e, 0x6c3f055d, 0x4425c923, 0x6c59d0a9, - 0x43fb3746, 0x6c748b3f, - 0x43d09aed, 0x6c8f351c, 0x43a5f41e, 0x6ca9ce3b, 0x437b42e1, 0x6cc45698, - 0x4350873c, 0x6cdece2f, - 0x4325c135, 0x6cf934fc, 0x42faf0d4, 0x6d138afb, 0x42d0161e, 0x6d2dd027, - 0x42a5311b, 0x6d48047e, - 0x427a41d0, 0x6d6227fa, 0x424f4845, 0x6d7c3a98, 0x42244481, 0x6d963c54, - 0x41f93689, 0x6db02d29, - 0x41ce1e65, 0x6dca0d14, 0x41a2fc1a, 0x6de3dc11, 0x4177cfb1, 0x6dfd9a1c, - 0x414c992f, 0x6e174730, - 0x4121589b, 0x6e30e34a, 0x40f60dfb, 0x6e4a6e66, 0x40cab958, 0x6e63e87f, - 0x409f5ab6, 0x6e7d5193, - 0x4073f21d, 0x6e96a99d, 0x40487f94, 0x6eaff099, 0x401d0321, 0x6ec92683, - 0x3ff17cca, 0x6ee24b57, - 0x3fc5ec98, 0x6efb5f12, 0x3f9a5290, 0x6f1461b0, 0x3f6eaeb8, 0x6f2d532c, - 0x3f430119, 0x6f463383, - 0x3f1749b8, 0x6f5f02b2, 0x3eeb889c, 0x6f77c0b3, 0x3ebfbdcd, 0x6f906d84, - 0x3e93e950, 0x6fa90921, - 0x3e680b2c, 0x6fc19385, 0x3e3c2369, 0x6fda0cae, 0x3e10320d, 0x6ff27497, - 0x3de4371f, 0x700acb3c, - 0x3db832a6, 0x7023109a, 0x3d8c24a8, 0x703b44ad, 0x3d600d2c, 0x70536771, - 0x3d33ec39, 0x706b78e3, - 0x3d07c1d6, 0x708378ff, 0x3cdb8e09, 0x709b67c0, 0x3caf50da, 0x70b34525, - 0x3c830a50, 0x70cb1128, - 0x3c56ba70, 0x70e2cbc6, 0x3c2a6142, 0x70fa74fc, 0x3bfdfecd, 0x71120cc5, - 0x3bd19318, 0x7129931f, - 0x3ba51e29, 0x71410805, 0x3b78a007, 0x71586b74, 0x3b4c18ba, 0x716fbd68, - 0x3b1f8848, 0x7186fdde, - 0x3af2eeb7, 0x719e2cd2, 0x3ac64c0f, 0x71b54a41, 0x3a99a057, 0x71cc5626, - 0x3a6ceb96, 0x71e35080, - 0x3a402dd2, 0x71fa3949, 0x3a136712, 0x7211107e, 0x39e6975e, 0x7227d61c, - 0x39b9bebc, 0x723e8a20, - 0x398cdd32, 0x72552c85, 0x395ff2c9, 0x726bbd48, 0x3932ff87, 0x72823c67, - 0x39060373, 0x7298a9dd, - 0x38d8fe93, 0x72af05a7, 0x38abf0ef, 0x72c54fc1, 0x387eda8e, 0x72db8828, - 0x3851bb77, 0x72f1aed9, - 0x382493b0, 0x7307c3d0, 0x37f76341, 0x731dc70a, 0x37ca2a30, 0x7333b883, - 0x379ce885, 0x73499838, - 0x376f9e46, 0x735f6626, 0x37424b7b, 0x73752249, 0x3714f02a, 0x738acc9e, - 0x36e78c5b, 0x73a06522, - 0x36ba2014, 0x73b5ebd1, 0x368cab5c, 0x73cb60a8, 0x365f2e3b, 0x73e0c3a3, - 0x3631a8b8, 0x73f614c0, - 0x36041ad9, 0x740b53fb, 0x35d684a6, 0x74208150, 0x35a8e625, 0x74359cbd, - 0x357b3f5d, 0x744aa63f, - 0x354d9057, 0x745f9dd1, 0x351fd918, 0x74748371, 0x34f219a8, 0x7489571c, - 0x34c4520d, 0x749e18cd, - 0x34968250, 0x74b2c884, 0x3468aa76, 0x74c7663a, 0x343aca87, 0x74dbf1ef, - 0x340ce28b, 0x74f06b9e, - 0x33def287, 0x7504d345, 0x33b0fa84, 0x751928e0, 0x3382fa88, 0x752d6c6c, - 0x3354f29b, 0x75419de7, - 0x3326e2c3, 0x7555bd4c, 0x32f8cb07, 0x7569ca99, 0x32caab6f, 0x757dc5ca, - 0x329c8402, 0x7591aedd, - 0x326e54c7, 0x75a585cf, 0x32401dc6, 0x75b94a9c, 0x3211df04, 0x75ccfd42, - 0x31e39889, 0x75e09dbd, - 0x31b54a5e, 0x75f42c0b, 0x3186f487, 0x7607a828, 0x3158970e, 0x761b1211, - 0x312a31f8, 0x762e69c4, - 0x30fbc54d, 0x7641af3d, 0x30cd5115, 0x7654e279, 0x309ed556, 0x76680376, - 0x30705217, 0x767b1231, - 0x3041c761, 0x768e0ea6, 0x30133539, 0x76a0f8d2, 0x2fe49ba7, 0x76b3d0b4, - 0x2fb5fab2, 0x76c69647, - 0x2f875262, 0x76d94989, 0x2f58a2be, 0x76ebea77, 0x2f29ebcc, 0x76fe790e, - 0x2efb2d95, 0x7710f54c, - 0x2ecc681e, 0x77235f2d, 0x2e9d9b70, 0x7735b6af, 0x2e6ec792, 0x7747fbce, - 0x2e3fec8b, 0x775a2e89, - 0x2e110a62, 0x776c4edb, 0x2de2211e, 0x777e5cc3, 0x2db330c7, 0x7790583e, - 0x2d843964, 0x77a24148, - 0x2d553afc, 0x77b417df, 0x2d263596, 0x77c5dc01, 0x2cf72939, 0x77d78daa, - 0x2cc815ee, 0x77e92cd9, - 0x2c98fbba, 0x77fab989, 0x2c69daa6, 0x780c33b8, 0x2c3ab2b9, 0x781d9b65, - 0x2c0b83fa, 0x782ef08b, - 0x2bdc4e6f, 0x78403329, 0x2bad1221, 0x7851633b, 0x2b7dcf17, 0x786280bf, - 0x2b4e8558, 0x78738bb3, - 0x2b1f34eb, 0x78848414, 0x2aefddd8, 0x789569df, 0x2ac08026, 0x78a63d11, - 0x2a911bdc, 0x78b6fda8, - 0x2a61b101, 0x78c7aba2, 0x2a323f9e, 0x78d846fb, 0x2a02c7b8, 0x78e8cfb2, - 0x29d34958, 0x78f945c3, - 0x29a3c485, 0x7909a92d, 0x29743946, 0x7919f9ec, 0x2944a7a2, 0x792a37fe, - 0x29150fa1, 0x793a6361, - 0x28e5714b, 0x794a7c12, 0x28b5cca5, 0x795a820e, 0x288621b9, 0x796a7554, - 0x2856708d, 0x797a55e0, - 0x2826b928, 0x798a23b1, 0x27f6fb92, 0x7999dec4, 0x27c737d3, 0x79a98715, - 0x27976df1, 0x79b91ca4, - 0x27679df4, 0x79c89f6e, 0x2737c7e3, 0x79d80f6f, 0x2707ebc7, 0x79e76ca7, - 0x26d809a5, 0x79f6b711, - 0x26a82186, 0x7a05eead, 0x26783370, 0x7a151378, 0x26483f6c, 0x7a24256f, - 0x26184581, 0x7a332490, - 0x25e845b6, 0x7a4210d8, 0x25b84012, 0x7a50ea47, 0x2588349d, 0x7a5fb0d8, - 0x2558235f, 0x7a6e648a, - 0x25280c5e, 0x7a7d055b, 0x24f7efa2, 0x7a8b9348, 0x24c7cd33, 0x7a9a0e50, - 0x2497a517, 0x7aa8766f, - 0x24677758, 0x7ab6cba4, 0x243743fa, 0x7ac50dec, 0x24070b08, 0x7ad33d45, - 0x23d6cc87, 0x7ae159ae, - 0x23a6887f, 0x7aef6323, 0x23763ef7, 0x7afd59a4, 0x2345eff8, 0x7b0b3d2c, - 0x23159b88, 0x7b190dbc, - 0x22e541af, 0x7b26cb4f, 0x22b4e274, 0x7b3475e5, 0x22847de0, 0x7b420d7a, - 0x225413f8, 0x7b4f920e, - 0x2223a4c5, 0x7b5d039e, 0x21f3304f, 0x7b6a6227, 0x21c2b69c, 0x7b77ada8, - 0x219237b5, 0x7b84e61f, - 0x2161b3a0, 0x7b920b89, 0x21312a65, 0x7b9f1de6, 0x21009c0c, 0x7bac1d31, - 0x20d0089c, 0x7bb9096b, - 0x209f701c, 0x7bc5e290, 0x206ed295, 0x7bd2a89e, 0x203e300d, 0x7bdf5b94, - 0x200d888d, 0x7bebfb70, - 0x1fdcdc1b, 0x7bf88830, 0x1fac2abf, 0x7c0501d2, 0x1f7b7481, 0x7c116853, - 0x1f4ab968, 0x7c1dbbb3, - 0x1f19f97b, 0x7c29fbee, 0x1ee934c3, 0x7c362904, 0x1eb86b46, 0x7c4242f2, - 0x1e879d0d, 0x7c4e49b7, - 0x1e56ca1e, 0x7c5a3d50, 0x1e25f282, 0x7c661dbc, 0x1df5163f, 0x7c71eaf9, - 0x1dc4355e, 0x7c7da505, - 0x1d934fe5, 0x7c894bde, 0x1d6265dd, 0x7c94df83, 0x1d31774d, 0x7ca05ff1, - 0x1d00843d, 0x7cabcd28, - 0x1ccf8cb3, 0x7cb72724, 0x1c9e90b8, 0x7cc26de5, 0x1c6d9053, 0x7ccda169, - 0x1c3c8b8c, 0x7cd8c1ae, - 0x1c0b826a, 0x7ce3ceb2, 0x1bda74f6, 0x7ceec873, 0x1ba96335, 0x7cf9aef0, - 0x1b784d30, 0x7d048228, - 0x1b4732ef, 0x7d0f4218, 0x1b161479, 0x7d19eebf, 0x1ae4f1d6, 0x7d24881b, - 0x1ab3cb0d, 0x7d2f0e2b, - 0x1a82a026, 0x7d3980ec, 0x1a517128, 0x7d43e05e, 0x1a203e1b, 0x7d4e2c7f, - 0x19ef0707, 0x7d58654d, - 0x19bdcbf3, 0x7d628ac6, 0x198c8ce7, 0x7d6c9ce9, 0x195b49ea, 0x7d769bb5, - 0x192a0304, 0x7d808728, - 0x18f8b83c, 0x7d8a5f40, 0x18c7699b, 0x7d9423fc, 0x18961728, 0x7d9dd55a, - 0x1864c0ea, 0x7da77359, - 0x183366e9, 0x7db0fdf8, 0x1802092c, 0x7dba7534, 0x17d0a7bc, 0x7dc3d90d, - 0x179f429f, 0x7dcd2981, - 0x176dd9de, 0x7dd6668f, 0x173c6d80, 0x7ddf9034, 0x170afd8d, 0x7de8a670, - 0x16d98a0c, 0x7df1a942, - 0x16a81305, 0x7dfa98a8, 0x1676987f, 0x7e0374a0, 0x16451a83, 0x7e0c3d29, - 0x16139918, 0x7e14f242, - 0x15e21445, 0x7e1d93ea, 0x15b08c12, 0x7e26221f, 0x157f0086, 0x7e2e9cdf, - 0x154d71aa, 0x7e37042a, - 0x151bdf86, 0x7e3f57ff, 0x14ea4a1f, 0x7e47985b, 0x14b8b17f, 0x7e4fc53e, - 0x148715ae, 0x7e57dea7, - 0x145576b1, 0x7e5fe493, 0x1423d492, 0x7e67d703, 0x13f22f58, 0x7e6fb5f4, - 0x13c0870a, 0x7e778166, - 0x138edbb1, 0x7e7f3957, 0x135d2d53, 0x7e86ddc6, 0x132b7bf9, 0x7e8e6eb2, - 0x12f9c7aa, 0x7e95ec1a, - 0x12c8106f, 0x7e9d55fc, 0x1296564d, 0x7ea4ac58, 0x1264994e, 0x7eabef2c, - 0x1232d979, 0x7eb31e78, - 0x120116d5, 0x7eba3a39, 0x11cf516a, 0x7ec14270, 0x119d8941, 0x7ec8371a, - 0x116bbe60, 0x7ecf1837, - 0x1139f0cf, 0x7ed5e5c6, 0x11082096, 0x7edc9fc6, 0x10d64dbd, 0x7ee34636, - 0x10a4784b, 0x7ee9d914, - 0x1072a048, 0x7ef05860, 0x1040c5bb, 0x7ef6c418, 0x100ee8ad, 0x7efd1c3c, - 0xfdd0926, 0x7f0360cb, - 0xfab272b, 0x7f0991c4, 0xf7942c7, 0x7f0faf25, 0xf475bff, 0x7f15b8ee, - 0xf1572dc, 0x7f1baf1e, - 0xee38766, 0x7f2191b4, 0xeb199a4, 0x7f2760af, 0xe7fa99e, 0x7f2d1c0e, - 0xe4db75b, 0x7f32c3d1, - 0xe1bc2e4, 0x7f3857f6, 0xde9cc40, 0x7f3dd87c, 0xdb7d376, 0x7f434563, - 0xd85d88f, 0x7f489eaa, - 0xd53db92, 0x7f4de451, 0xd21dc87, 0x7f531655, 0xcefdb76, 0x7f5834b7, - 0xcbdd865, 0x7f5d3f75, - 0xc8bd35e, 0x7f62368f, 0xc59cc68, 0x7f671a05, 0xc27c389, 0x7f6be9d4, - 0xbf5b8cb, 0x7f70a5fe, - 0xbc3ac35, 0x7f754e80, 0xb919dcf, 0x7f79e35a, 0xb5f8d9f, 0x7f7e648c, - 0xb2d7baf, 0x7f82d214, - 0xafb6805, 0x7f872bf3, 0xac952aa, 0x7f8b7227, 0xa973ba5, 0x7f8fa4b0, - 0xa6522fe, 0x7f93c38c, - 0xa3308bd, 0x7f97cebd, 0xa00ece8, 0x7f9bc640, 0x9cecf89, 0x7f9faa15, - 0x99cb0a7, 0x7fa37a3c, - 0x96a9049, 0x7fa736b4, 0x9386e78, 0x7faadf7c, 0x9064b3a, 0x7fae7495, - 0x8d42699, 0x7fb1f5fc, - 0x8a2009a, 0x7fb563b3, 0x86fd947, 0x7fb8bdb8, 0x83db0a7, 0x7fbc040a, - 0x80b86c2, 0x7fbf36aa, - 0x7d95b9e, 0x7fc25596, 0x7a72f45, 0x7fc560cf, 0x77501be, 0x7fc85854, - 0x742d311, 0x7fcb3c23, - 0x710a345, 0x7fce0c3e, 0x6de7262, 0x7fd0c8a3, 0x6ac406f, 0x7fd37153, - 0x67a0d76, 0x7fd6064c, - 0x647d97c, 0x7fd8878e, 0x615a48b, 0x7fdaf519, 0x5e36ea9, 0x7fdd4eec, - 0x5b137df, 0x7fdf9508, - 0x57f0035, 0x7fe1c76b, 0x54cc7b1, 0x7fe3e616, 0x51a8e5c, 0x7fe5f108, - 0x4e8543e, 0x7fe7e841, - 0x4b6195d, 0x7fe9cbc0, 0x483ddc3, 0x7feb9b85, 0x451a177, 0x7fed5791, - 0x41f6480, 0x7feeffe1, - 0x3ed26e6, 0x7ff09478, 0x3bae8b2, 0x7ff21553, 0x388a9ea, 0x7ff38274, - 0x3566a96, 0x7ff4dbd9, - 0x3242abf, 0x7ff62182, 0x2f1ea6c, 0x7ff75370, 0x2bfa9a4, 0x7ff871a2, - 0x28d6870, 0x7ff97c18, - 0x25b26d7, 0x7ffa72d1, 0x228e4e2, 0x7ffb55ce, 0x1f6a297, 0x7ffc250f, - 0x1c45ffe, 0x7ffce093, - 0x1921d20, 0x7ffd885a, 0x15fda03, 0x7ffe1c65, 0x12d96b1, 0x7ffe9cb2, - 0xfb5330, 0x7fff0943, - 0xc90f88, 0x7fff6216, 0x96cbc1, 0x7fffa72c, 0x6487e3, 0x7fffd886, 0x3243f5, - 0x7ffff621, - 0x0, 0x7fffffff, 0xffcdbc0b, 0x7ffff621, 0xff9b781d, 0x7fffd886, 0xff69343f, - 0x7fffa72c, - 0xff36f078, 0x7fff6216, 0xff04acd0, 0x7fff0943, 0xfed2694f, 0x7ffe9cb2, - 0xfea025fd, 0x7ffe1c65, - 0xfe6de2e0, 0x7ffd885a, 0xfe3ba002, 0x7ffce093, 0xfe095d69, 0x7ffc250f, - 0xfdd71b1e, 0x7ffb55ce, - 0xfda4d929, 0x7ffa72d1, 0xfd729790, 0x7ff97c18, 0xfd40565c, 0x7ff871a2, - 0xfd0e1594, 0x7ff75370, - 0xfcdbd541, 0x7ff62182, 0xfca9956a, 0x7ff4dbd9, 0xfc775616, 0x7ff38274, - 0xfc45174e, 0x7ff21553, - 0xfc12d91a, 0x7ff09478, 0xfbe09b80, 0x7feeffe1, 0xfbae5e89, 0x7fed5791, - 0xfb7c223d, 0x7feb9b85, - 0xfb49e6a3, 0x7fe9cbc0, 0xfb17abc2, 0x7fe7e841, 0xfae571a4, 0x7fe5f108, - 0xfab3384f, 0x7fe3e616, - 0xfa80ffcb, 0x7fe1c76b, 0xfa4ec821, 0x7fdf9508, 0xfa1c9157, 0x7fdd4eec, - 0xf9ea5b75, 0x7fdaf519, - 0xf9b82684, 0x7fd8878e, 0xf985f28a, 0x7fd6064c, 0xf953bf91, 0x7fd37153, - 0xf9218d9e, 0x7fd0c8a3, - 0xf8ef5cbb, 0x7fce0c3e, 0xf8bd2cef, 0x7fcb3c23, 0xf88afe42, 0x7fc85854, - 0xf858d0bb, 0x7fc560cf, - 0xf826a462, 0x7fc25596, 0xf7f4793e, 0x7fbf36aa, 0xf7c24f59, 0x7fbc040a, - 0xf79026b9, 0x7fb8bdb8, - 0xf75dff66, 0x7fb563b3, 0xf72bd967, 0x7fb1f5fc, 0xf6f9b4c6, 0x7fae7495, - 0xf6c79188, 0x7faadf7c, - 0xf6956fb7, 0x7fa736b4, 0xf6634f59, 0x7fa37a3c, 0xf6313077, 0x7f9faa15, - 0xf5ff1318, 0x7f9bc640, - 0xf5ccf743, 0x7f97cebd, 0xf59add02, 0x7f93c38c, 0xf568c45b, 0x7f8fa4b0, - 0xf536ad56, 0x7f8b7227, - 0xf50497fb, 0x7f872bf3, 0xf4d28451, 0x7f82d214, 0xf4a07261, 0x7f7e648c, - 0xf46e6231, 0x7f79e35a, - 0xf43c53cb, 0x7f754e80, 0xf40a4735, 0x7f70a5fe, 0xf3d83c77, 0x7f6be9d4, - 0xf3a63398, 0x7f671a05, - 0xf3742ca2, 0x7f62368f, 0xf342279b, 0x7f5d3f75, 0xf310248a, 0x7f5834b7, - 0xf2de2379, 0x7f531655, - 0xf2ac246e, 0x7f4de451, 0xf27a2771, 0x7f489eaa, 0xf2482c8a, 0x7f434563, - 0xf21633c0, 0x7f3dd87c, - 0xf1e43d1c, 0x7f3857f6, 0xf1b248a5, 0x7f32c3d1, 0xf1805662, 0x7f2d1c0e, - 0xf14e665c, 0x7f2760af, - 0xf11c789a, 0x7f2191b4, 0xf0ea8d24, 0x7f1baf1e, 0xf0b8a401, 0x7f15b8ee, - 0xf086bd39, 0x7f0faf25, - 0xf054d8d5, 0x7f0991c4, 0xf022f6da, 0x7f0360cb, 0xeff11753, 0x7efd1c3c, - 0xefbf3a45, 0x7ef6c418, - 0xef8d5fb8, 0x7ef05860, 0xef5b87b5, 0x7ee9d914, 0xef29b243, 0x7ee34636, - 0xeef7df6a, 0x7edc9fc6, - 0xeec60f31, 0x7ed5e5c6, 0xee9441a0, 0x7ecf1837, 0xee6276bf, 0x7ec8371a, - 0xee30ae96, 0x7ec14270, - 0xedfee92b, 0x7eba3a39, 0xedcd2687, 0x7eb31e78, 0xed9b66b2, 0x7eabef2c, - 0xed69a9b3, 0x7ea4ac58, - 0xed37ef91, 0x7e9d55fc, 0xed063856, 0x7e95ec1a, 0xecd48407, 0x7e8e6eb2, - 0xeca2d2ad, 0x7e86ddc6, - 0xec71244f, 0x7e7f3957, 0xec3f78f6, 0x7e778166, 0xec0dd0a8, 0x7e6fb5f4, - 0xebdc2b6e, 0x7e67d703, - 0xebaa894f, 0x7e5fe493, 0xeb78ea52, 0x7e57dea7, 0xeb474e81, 0x7e4fc53e, - 0xeb15b5e1, 0x7e47985b, - 0xeae4207a, 0x7e3f57ff, 0xeab28e56, 0x7e37042a, 0xea80ff7a, 0x7e2e9cdf, - 0xea4f73ee, 0x7e26221f, - 0xea1debbb, 0x7e1d93ea, 0xe9ec66e8, 0x7e14f242, 0xe9bae57d, 0x7e0c3d29, - 0xe9896781, 0x7e0374a0, - 0xe957ecfb, 0x7dfa98a8, 0xe92675f4, 0x7df1a942, 0xe8f50273, 0x7de8a670, - 0xe8c39280, 0x7ddf9034, - 0xe8922622, 0x7dd6668f, 0xe860bd61, 0x7dcd2981, 0xe82f5844, 0x7dc3d90d, - 0xe7fdf6d4, 0x7dba7534, - 0xe7cc9917, 0x7db0fdf8, 0xe79b3f16, 0x7da77359, 0xe769e8d8, 0x7d9dd55a, - 0xe7389665, 0x7d9423fc, - 0xe70747c4, 0x7d8a5f40, 0xe6d5fcfc, 0x7d808728, 0xe6a4b616, 0x7d769bb5, - 0xe6737319, 0x7d6c9ce9, - 0xe642340d, 0x7d628ac6, 0xe610f8f9, 0x7d58654d, 0xe5dfc1e5, 0x7d4e2c7f, - 0xe5ae8ed8, 0x7d43e05e, - 0xe57d5fda, 0x7d3980ec, 0xe54c34f3, 0x7d2f0e2b, 0xe51b0e2a, 0x7d24881b, - 0xe4e9eb87, 0x7d19eebf, - 0xe4b8cd11, 0x7d0f4218, 0xe487b2d0, 0x7d048228, 0xe4569ccb, 0x7cf9aef0, - 0xe4258b0a, 0x7ceec873, - 0xe3f47d96, 0x7ce3ceb2, 0xe3c37474, 0x7cd8c1ae, 0xe3926fad, 0x7ccda169, - 0xe3616f48, 0x7cc26de5, - 0xe330734d, 0x7cb72724, 0xe2ff7bc3, 0x7cabcd28, 0xe2ce88b3, 0x7ca05ff1, - 0xe29d9a23, 0x7c94df83, - 0xe26cb01b, 0x7c894bde, 0xe23bcaa2, 0x7c7da505, 0xe20ae9c1, 0x7c71eaf9, - 0xe1da0d7e, 0x7c661dbc, - 0xe1a935e2, 0x7c5a3d50, 0xe17862f3, 0x7c4e49b7, 0xe14794ba, 0x7c4242f2, - 0xe116cb3d, 0x7c362904, - 0xe0e60685, 0x7c29fbee, 0xe0b54698, 0x7c1dbbb3, 0xe0848b7f, 0x7c116853, - 0xe053d541, 0x7c0501d2, - 0xe02323e5, 0x7bf88830, 0xdff27773, 0x7bebfb70, 0xdfc1cff3, 0x7bdf5b94, - 0xdf912d6b, 0x7bd2a89e, - 0xdf608fe4, 0x7bc5e290, 0xdf2ff764, 0x7bb9096b, 0xdeff63f4, 0x7bac1d31, - 0xdeced59b, 0x7b9f1de6, - 0xde9e4c60, 0x7b920b89, 0xde6dc84b, 0x7b84e61f, 0xde3d4964, 0x7b77ada8, - 0xde0ccfb1, 0x7b6a6227, - 0xdddc5b3b, 0x7b5d039e, 0xddabec08, 0x7b4f920e, 0xdd7b8220, 0x7b420d7a, - 0xdd4b1d8c, 0x7b3475e5, - 0xdd1abe51, 0x7b26cb4f, 0xdcea6478, 0x7b190dbc, 0xdcba1008, 0x7b0b3d2c, - 0xdc89c109, 0x7afd59a4, - 0xdc597781, 0x7aef6323, 0xdc293379, 0x7ae159ae, 0xdbf8f4f8, 0x7ad33d45, - 0xdbc8bc06, 0x7ac50dec, - 0xdb9888a8, 0x7ab6cba4, 0xdb685ae9, 0x7aa8766f, 0xdb3832cd, 0x7a9a0e50, - 0xdb08105e, 0x7a8b9348, - 0xdad7f3a2, 0x7a7d055b, 0xdaa7dca1, 0x7a6e648a, 0xda77cb63, 0x7a5fb0d8, - 0xda47bfee, 0x7a50ea47, - 0xda17ba4a, 0x7a4210d8, 0xd9e7ba7f, 0x7a332490, 0xd9b7c094, 0x7a24256f, - 0xd987cc90, 0x7a151378, - 0xd957de7a, 0x7a05eead, 0xd927f65b, 0x79f6b711, 0xd8f81439, 0x79e76ca7, - 0xd8c8381d, 0x79d80f6f, - 0xd898620c, 0x79c89f6e, 0xd868920f, 0x79b91ca4, 0xd838c82d, 0x79a98715, - 0xd809046e, 0x7999dec4, - 0xd7d946d8, 0x798a23b1, 0xd7a98f73, 0x797a55e0, 0xd779de47, 0x796a7554, - 0xd74a335b, 0x795a820e, - 0xd71a8eb5, 0x794a7c12, 0xd6eaf05f, 0x793a6361, 0xd6bb585e, 0x792a37fe, - 0xd68bc6ba, 0x7919f9ec, - 0xd65c3b7b, 0x7909a92d, 0xd62cb6a8, 0x78f945c3, 0xd5fd3848, 0x78e8cfb2, - 0xd5cdc062, 0x78d846fb, - 0xd59e4eff, 0x78c7aba2, 0xd56ee424, 0x78b6fda8, 0xd53f7fda, 0x78a63d11, - 0xd5102228, 0x789569df, - 0xd4e0cb15, 0x78848414, 0xd4b17aa8, 0x78738bb3, 0xd48230e9, 0x786280bf, - 0xd452eddf, 0x7851633b, - 0xd423b191, 0x78403329, 0xd3f47c06, 0x782ef08b, 0xd3c54d47, 0x781d9b65, - 0xd396255a, 0x780c33b8, - 0xd3670446, 0x77fab989, 0xd337ea12, 0x77e92cd9, 0xd308d6c7, 0x77d78daa, - 0xd2d9ca6a, 0x77c5dc01, - 0xd2aac504, 0x77b417df, 0xd27bc69c, 0x77a24148, 0xd24ccf39, 0x7790583e, - 0xd21ddee2, 0x777e5cc3, - 0xd1eef59e, 0x776c4edb, 0xd1c01375, 0x775a2e89, 0xd191386e, 0x7747fbce, - 0xd1626490, 0x7735b6af, - 0xd13397e2, 0x77235f2d, 0xd104d26b, 0x7710f54c, 0xd0d61434, 0x76fe790e, - 0xd0a75d42, 0x76ebea77, - 0xd078ad9e, 0x76d94989, 0xd04a054e, 0x76c69647, 0xd01b6459, 0x76b3d0b4, - 0xcfeccac7, 0x76a0f8d2, - 0xcfbe389f, 0x768e0ea6, 0xcf8fade9, 0x767b1231, 0xcf612aaa, 0x76680376, - 0xcf32aeeb, 0x7654e279, - 0xcf043ab3, 0x7641af3d, 0xced5ce08, 0x762e69c4, 0xcea768f2, 0x761b1211, - 0xce790b79, 0x7607a828, - 0xce4ab5a2, 0x75f42c0b, 0xce1c6777, 0x75e09dbd, 0xcdee20fc, 0x75ccfd42, - 0xcdbfe23a, 0x75b94a9c, - 0xcd91ab39, 0x75a585cf, 0xcd637bfe, 0x7591aedd, 0xcd355491, 0x757dc5ca, - 0xcd0734f9, 0x7569ca99, - 0xccd91d3d, 0x7555bd4c, 0xccab0d65, 0x75419de7, 0xcc7d0578, 0x752d6c6c, - 0xcc4f057c, 0x751928e0, - 0xcc210d79, 0x7504d345, 0xcbf31d75, 0x74f06b9e, 0xcbc53579, 0x74dbf1ef, - 0xcb97558a, 0x74c7663a, - 0xcb697db0, 0x74b2c884, 0xcb3badf3, 0x749e18cd, 0xcb0de658, 0x7489571c, - 0xcae026e8, 0x74748371, - 0xcab26fa9, 0x745f9dd1, 0xca84c0a3, 0x744aa63f, 0xca5719db, 0x74359cbd, - 0xca297b5a, 0x74208150, - 0xc9fbe527, 0x740b53fb, 0xc9ce5748, 0x73f614c0, 0xc9a0d1c5, 0x73e0c3a3, - 0xc97354a4, 0x73cb60a8, - 0xc945dfec, 0x73b5ebd1, 0xc91873a5, 0x73a06522, 0xc8eb0fd6, 0x738acc9e, - 0xc8bdb485, 0x73752249, - 0xc89061ba, 0x735f6626, 0xc863177b, 0x73499838, 0xc835d5d0, 0x7333b883, - 0xc8089cbf, 0x731dc70a, - 0xc7db6c50, 0x7307c3d0, 0xc7ae4489, 0x72f1aed9, 0xc7812572, 0x72db8828, - 0xc7540f11, 0x72c54fc1, - 0xc727016d, 0x72af05a7, 0xc6f9fc8d, 0x7298a9dd, 0xc6cd0079, 0x72823c67, - 0xc6a00d37, 0x726bbd48, - 0xc67322ce, 0x72552c85, 0xc6464144, 0x723e8a20, 0xc61968a2, 0x7227d61c, - 0xc5ec98ee, 0x7211107e, - 0xc5bfd22e, 0x71fa3949, 0xc593146a, 0x71e35080, 0xc5665fa9, 0x71cc5626, - 0xc539b3f1, 0x71b54a41, - 0xc50d1149, 0x719e2cd2, 0xc4e077b8, 0x7186fdde, 0xc4b3e746, 0x716fbd68, - 0xc4875ff9, 0x71586b74, - 0xc45ae1d7, 0x71410805, 0xc42e6ce8, 0x7129931f, 0xc4020133, 0x71120cc5, - 0xc3d59ebe, 0x70fa74fc, - 0xc3a94590, 0x70e2cbc6, 0xc37cf5b0, 0x70cb1128, 0xc350af26, 0x70b34525, - 0xc32471f7, 0x709b67c0, - 0xc2f83e2a, 0x708378ff, 0xc2cc13c7, 0x706b78e3, 0xc29ff2d4, 0x70536771, - 0xc273db58, 0x703b44ad, - 0xc247cd5a, 0x7023109a, 0xc21bc8e1, 0x700acb3c, 0xc1efcdf3, 0x6ff27497, - 0xc1c3dc97, 0x6fda0cae, - 0xc197f4d4, 0x6fc19385, 0xc16c16b0, 0x6fa90921, 0xc1404233, 0x6f906d84, - 0xc1147764, 0x6f77c0b3, - 0xc0e8b648, 0x6f5f02b2, 0xc0bcfee7, 0x6f463383, 0xc0915148, 0x6f2d532c, - 0xc065ad70, 0x6f1461b0, - 0xc03a1368, 0x6efb5f12, 0xc00e8336, 0x6ee24b57, 0xbfe2fcdf, 0x6ec92683, - 0xbfb7806c, 0x6eaff099, - 0xbf8c0de3, 0x6e96a99d, 0xbf60a54a, 0x6e7d5193, 0xbf3546a8, 0x6e63e87f, - 0xbf09f205, 0x6e4a6e66, - 0xbedea765, 0x6e30e34a, 0xbeb366d1, 0x6e174730, 0xbe88304f, 0x6dfd9a1c, - 0xbe5d03e6, 0x6de3dc11, - 0xbe31e19b, 0x6dca0d14, 0xbe06c977, 0x6db02d29, 0xbddbbb7f, 0x6d963c54, - 0xbdb0b7bb, 0x6d7c3a98, - 0xbd85be30, 0x6d6227fa, 0xbd5acee5, 0x6d48047e, 0xbd2fe9e2, 0x6d2dd027, - 0xbd050f2c, 0x6d138afb, - 0xbcda3ecb, 0x6cf934fc, 0xbcaf78c4, 0x6cdece2f, 0xbc84bd1f, 0x6cc45698, - 0xbc5a0be2, 0x6ca9ce3b, - 0xbc2f6513, 0x6c8f351c, 0xbc04c8ba, 0x6c748b3f, 0xbbda36dd, 0x6c59d0a9, - 0xbbafaf82, 0x6c3f055d, - 0xbb8532b0, 0x6c242960, 0xbb5ac06d, 0x6c093cb6, 0xbb3058c0, 0x6bee3f62, - 0xbb05fbb0, 0x6bd3316a, - 0xbadba943, 0x6bb812d1, 0xbab16180, 0x6b9ce39b, 0xba87246d, 0x6b81a3cd, - 0xba5cf210, 0x6b66536b, - 0xba32ca71, 0x6b4af279, 0xba08ad95, 0x6b2f80fb, 0xb9de9b83, 0x6b13fef5, - 0xb9b49442, 0x6af86c6c, - 0xb98a97d8, 0x6adcc964, 0xb960a64c, 0x6ac115e2, 0xb936bfa4, 0x6aa551e9, - 0xb90ce3e6, 0x6a897d7d, - 0xb8e31319, 0x6a6d98a4, 0xb8b94d44, 0x6a51a361, 0xb88f926d, 0x6a359db9, - 0xb865e299, 0x6a1987b0, - 0xb83c3dd1, 0x69fd614a, 0xb812a41a, 0x69e12a8c, 0xb7e9157a, 0x69c4e37a, - 0xb7bf91f8, 0x69a88c19, - 0xb796199b, 0x698c246c, 0xb76cac69, 0x696fac78, 0xb7434a67, 0x69532442, - 0xb719f39e, 0x69368bce, - 0xb6f0a812, 0x6919e320, 0xb6c767ca, 0x68fd2a3d, 0xb69e32cd, 0x68e06129, - 0xb6750921, 0x68c387e9, - 0xb64beacd, 0x68a69e81, 0xb622d7d6, 0x6889a4f6, 0xb5f9d043, 0x686c9b4b, - 0xb5d0d41a, 0x684f8186, - 0xb5a7e362, 0x683257ab, 0xb57efe22, 0x68151dbe, 0xb556245e, 0x67f7d3c5, - 0xb52d561e, 0x67da79c3, - 0xb5049368, 0x67bd0fbd, 0xb4dbdc42, 0x679f95b7, 0xb4b330b3, 0x67820bb7, - 0xb48a90c0, 0x676471c0, - 0xb461fc70, 0x6746c7d8, 0xb43973ca, 0x67290e02, 0xb410f6d3, 0x670b4444, - 0xb3e88592, 0x66ed6aa1, - 0xb3c0200c, 0x66cf8120, 0xb397c649, 0x66b187c3, 0xb36f784f, 0x66937e91, - 0xb3473623, 0x6675658c, - 0xb31effcc, 0x66573cbb, 0xb2f6d550, 0x66390422, 0xb2ceb6b5, 0x661abbc5, - 0xb2a6a402, 0x65fc63a9, - 0xb27e9d3c, 0x65ddfbd3, 0xb256a26a, 0x65bf8447, 0xb22eb392, 0x65a0fd0b, - 0xb206d0ba, 0x65826622, - 0xb1def9e9, 0x6563bf92, 0xb1b72f23, 0x6545095f, 0xb18f7071, 0x6526438f, - 0xb167bdd7, 0x65076e25, - 0xb140175b, 0x64e88926, 0xb1187d05, 0x64c99498, 0xb0f0eeda, 0x64aa907f, - 0xb0c96ce0, 0x648b7ce0, - 0xb0a1f71d, 0x646c59bf, 0xb07a8d97, 0x644d2722, 0xb0533055, 0x642de50d, - 0xb02bdf5c, 0x640e9386, - 0xb0049ab3, 0x63ef3290, 0xafdd625f, 0x63cfc231, 0xafb63667, 0x63b0426d, - 0xaf8f16d1, 0x6390b34a, - 0xaf6803a2, 0x637114cc, 0xaf40fce1, 0x635166f9, 0xaf1a0293, 0x6331a9d4, - 0xaef314c0, 0x6311dd64, - 0xaecc336c, 0x62f201ac, 0xaea55e9e, 0x62d216b3, 0xae7e965b, 0x62b21c7b, - 0xae57daab, 0x6292130c, - 0xae312b92, 0x6271fa69, 0xae0a8916, 0x6251d298, 0xade3f33e, 0x62319b9d, - 0xadbd6a10, 0x6211557e, - 0xad96ed92, 0x61f1003f, 0xad707dc8, 0x61d09be5, 0xad4a1aba, 0x61b02876, - 0xad23c46e, 0x618fa5f7, - 0xacfd7ae8, 0x616f146c, 0xacd73e30, 0x614e73da, 0xacb10e4b, 0x612dc447, - 0xac8aeb3e, 0x610d05b7, - 0xac64d510, 0x60ec3830, 0xac3ecbc7, 0x60cb5bb7, 0xac18cf69, 0x60aa7050, - 0xabf2dffb, 0x60897601, - 0xabccfd83, 0x60686ccf, 0xaba72807, 0x604754bf, 0xab815f8d, 0x60262dd6, - 0xab5ba41a, 0x6004f819, - 0xab35f5b5, 0x5fe3b38d, 0xab105464, 0x5fc26038, 0xaaeac02c, 0x5fa0fe1f, - 0xaac53912, 0x5f7f8d46, - 0xaa9fbf1e, 0x5f5e0db3, 0xaa7a5253, 0x5f3c7f6b, 0xaa54f2ba, 0x5f1ae274, - 0xaa2fa056, 0x5ef936d1, - 0xaa0a5b2e, 0x5ed77c8a, 0xa9e52347, 0x5eb5b3a2, 0xa9bff8a8, 0x5e93dc1f, - 0xa99adb56, 0x5e71f606, - 0xa975cb57, 0x5e50015d, 0xa950c8b0, 0x5e2dfe29, 0xa92bd367, 0x5e0bec6e, - 0xa906eb82, 0x5de9cc33, - 0xa8e21106, 0x5dc79d7c, 0xa8bd43fa, 0x5da5604f, 0xa8988463, 0x5d8314b1, - 0xa873d246, 0x5d60baa7, - 0xa84f2daa, 0x5d3e5237, 0xa82a9693, 0x5d1bdb65, 0xa8060d08, 0x5cf95638, - 0xa7e1910f, 0x5cd6c2b5, - 0xa7bd22ac, 0x5cb420e0, 0xa798c1e5, 0x5c9170bf, 0xa7746ec0, 0x5c6eb258, - 0xa7502943, 0x5c4be5b0, - 0xa72bf174, 0x5c290acc, 0xa707c757, 0x5c0621b2, 0xa6e3aaf2, 0x5be32a67, - 0xa6bf9c4b, 0x5bc024f0, - 0xa69b9b68, 0x5b9d1154, 0xa677a84e, 0x5b79ef96, 0xa653c303, 0x5b56bfbd, - 0xa62feb8b, 0x5b3381ce, - 0xa60c21ee, 0x5b1035cf, 0xa5e8662f, 0x5aecdbc5, 0xa5c4b855, 0x5ac973b5, - 0xa5a11866, 0x5aa5fda5, - 0xa57d8666, 0x5a82799a, 0xa55a025b, 0x5a5ee79a, 0xa5368c4b, 0x5a3b47ab, - 0xa513243b, 0x5a1799d1, - 0xa4efca31, 0x59f3de12, 0xa4cc7e32, 0x59d01475, 0xa4a94043, 0x59ac3cfd, - 0xa486106a, 0x598857b2, - 0xa462eeac, 0x59646498, 0xa43fdb10, 0x594063b5, 0xa41cd599, 0x591c550e, - 0xa3f9de4e, 0x58f838a9, - 0xa3d6f534, 0x58d40e8c, 0xa3b41a50, 0x58afd6bd, 0xa3914da8, 0x588b9140, - 0xa36e8f41, 0x58673e1b, - 0xa34bdf20, 0x5842dd54, 0xa3293d4b, 0x581e6ef1, 0xa306a9c8, 0x57f9f2f8, - 0xa2e4249b, 0x57d5696d, - 0xa2c1adc9, 0x57b0d256, 0xa29f4559, 0x578c2dba, 0xa27ceb4f, 0x57677b9d, - 0xa25a9fb1, 0x5742bc06, - 0xa2386284, 0x571deefa, 0xa21633cd, 0x56f9147e, 0xa1f41392, 0x56d42c99, - 0xa1d201d7, 0x56af3750, - 0xa1affea3, 0x568a34a9, 0xa18e09fa, 0x566524aa, 0xa16c23e1, 0x56400758, - 0xa14a4c5e, 0x561adcb9, - 0xa1288376, 0x55f5a4d2, 0xa106c92f, 0x55d05faa, 0xa0e51d8c, 0x55ab0d46, - 0xa0c38095, 0x5585adad, - 0xa0a1f24d, 0x556040e2, 0xa08072ba, 0x553ac6ee, 0xa05f01e1, 0x55153fd4, - 0xa03d9fc8, 0x54efab9c, - 0xa01c4c73, 0x54ca0a4b, 0x9ffb07e7, 0x54a45be6, 0x9fd9d22a, 0x547ea073, - 0x9fb8ab41, 0x5458d7f9, - 0x9f979331, 0x5433027d, 0x9f7689ff, 0x540d2005, 0x9f558fb0, 0x53e73097, - 0x9f34a449, 0x53c13439, - 0x9f13c7d0, 0x539b2af0, 0x9ef2fa49, 0x537514c2, 0x9ed23bb9, 0x534ef1b5, - 0x9eb18c26, 0x5328c1d0, - 0x9e90eb94, 0x53028518, 0x9e705a09, 0x52dc3b92, 0x9e4fd78a, 0x52b5e546, - 0x9e2f641b, 0x528f8238, - 0x9e0effc1, 0x5269126e, 0x9deeaa82, 0x524295f0, 0x9dce6463, 0x521c0cc2, - 0x9dae2d68, 0x51f576ea, - 0x9d8e0597, 0x51ced46e, 0x9d6decf4, 0x51a82555, 0x9d4de385, 0x518169a5, - 0x9d2de94d, 0x515aa162, - 0x9d0dfe54, 0x5133cc94, 0x9cee229c, 0x510ceb40, 0x9cce562c, 0x50e5fd6d, - 0x9cae9907, 0x50bf031f, - 0x9c8eeb34, 0x5097fc5e, 0x9c6f4cb6, 0x5070e92f, 0x9c4fbd93, 0x5049c999, - 0x9c303dcf, 0x50229da1, - 0x9c10cd70, 0x4ffb654d, 0x9bf16c7a, 0x4fd420a4, 0x9bd21af3, 0x4faccfab, - 0x9bb2d8de, 0x4f857269, - 0x9b93a641, 0x4f5e08e3, 0x9b748320, 0x4f369320, 0x9b556f81, 0x4f0f1126, - 0x9b366b68, 0x4ee782fb, - 0x9b1776da, 0x4ebfe8a5, 0x9af891db, 0x4e984229, 0x9ad9bc71, 0x4e708f8f, - 0x9abaf6a1, 0x4e48d0dd, - 0x9a9c406e, 0x4e210617, 0x9a7d99de, 0x4df92f46, 0x9a5f02f5, 0x4dd14c6e, - 0x9a407bb9, 0x4da95d96, - 0x9a22042d, 0x4d8162c4, 0x9a039c57, 0x4d595bfe, 0x99e5443b, 0x4d31494b, - 0x99c6fbde, 0x4d092ab0, - 0x99a8c345, 0x4ce10034, 0x998a9a74, 0x4cb8c9dd, 0x996c816f, 0x4c9087b1, - 0x994e783d, 0x4c6839b7, - 0x99307ee0, 0x4c3fdff4, 0x9912955f, 0x4c177a6e, 0x98f4bbbc, 0x4bef092d, - 0x98d6f1fe, 0x4bc68c36, - 0x98b93828, 0x4b9e0390, 0x989b8e40, 0x4b756f40, 0x987df449, 0x4b4ccf4d, - 0x98606a49, 0x4b2423be, - 0x9842f043, 0x4afb6c98, 0x9825863d, 0x4ad2a9e2, 0x98082c3b, 0x4aa9dba2, - 0x97eae242, 0x4a8101de, - 0x97cda855, 0x4a581c9e, 0x97b07e7a, 0x4a2f2be6, 0x979364b5, 0x4a062fbd, - 0x97765b0a, 0x49dd282a, - 0x9759617f, 0x49b41533, 0x973c7817, 0x498af6df, 0x971f9ed7, 0x4961cd33, - 0x9702d5c3, 0x49389836, - 0x96e61ce0, 0x490f57ee, 0x96c97432, 0x48e60c62, 0x96acdbbe, 0x48bcb599, - 0x96905388, 0x48935397, - 0x9673db94, 0x4869e665, 0x965773e7, 0x48406e08, 0x963b1c86, 0x4816ea86, - 0x961ed574, 0x47ed5be6, - 0x96029eb6, 0x47c3c22f, 0x95e67850, 0x479a1d67, 0x95ca6247, 0x47706d93, - 0x95ae5c9f, 0x4746b2bc, - 0x9592675c, 0x471cece7, 0x95768283, 0x46f31c1a, 0x955aae17, 0x46c9405c, - 0x953eea1e, 0x469f59b4, - 0x9523369c, 0x46756828, 0x95079394, 0x464b6bbe, 0x94ec010b, 0x4621647d, - 0x94d07f05, 0x45f7526b, - 0x94b50d87, 0x45cd358f, 0x9499ac95, 0x45a30df0, 0x947e5c33, 0x4578db93, - 0x94631c65, 0x454e9e80, - 0x9447ed2f, 0x452456bd, 0x942cce96, 0x44fa0450, 0x9411c09e, 0x44cfa740, - 0x93f6c34a, 0x44a53f93, - 0x93dbd6a0, 0x447acd50, 0x93c0faa3, 0x4450507e, 0x93a62f57, 0x4425c923, - 0x938b74c1, 0x43fb3746, - 0x9370cae4, 0x43d09aed, 0x935631c5, 0x43a5f41e, 0x933ba968, 0x437b42e1, - 0x932131d1, 0x4350873c, - 0x9306cb04, 0x4325c135, 0x92ec7505, 0x42faf0d4, 0x92d22fd9, 0x42d0161e, - 0x92b7fb82, 0x42a5311b, - 0x929dd806, 0x427a41d0, 0x9283c568, 0x424f4845, 0x9269c3ac, 0x42244481, - 0x924fd2d7, 0x41f93689, - 0x9235f2ec, 0x41ce1e65, 0x921c23ef, 0x41a2fc1a, 0x920265e4, 0x4177cfb1, - 0x91e8b8d0, 0x414c992f, - 0x91cf1cb6, 0x4121589b, 0x91b5919a, 0x40f60dfb, 0x919c1781, 0x40cab958, - 0x9182ae6d, 0x409f5ab6, - 0x91695663, 0x4073f21d, 0x91500f67, 0x40487f94, 0x9136d97d, 0x401d0321, - 0x911db4a9, 0x3ff17cca, - 0x9104a0ee, 0x3fc5ec98, 0x90eb9e50, 0x3f9a5290, 0x90d2acd4, 0x3f6eaeb8, - 0x90b9cc7d, 0x3f430119, - 0x90a0fd4e, 0x3f1749b8, 0x90883f4d, 0x3eeb889c, 0x906f927c, 0x3ebfbdcd, - 0x9056f6df, 0x3e93e950, - 0x903e6c7b, 0x3e680b2c, 0x9025f352, 0x3e3c2369, 0x900d8b69, 0x3e10320d, - 0x8ff534c4, 0x3de4371f, - 0x8fdcef66, 0x3db832a6, 0x8fc4bb53, 0x3d8c24a8, 0x8fac988f, 0x3d600d2c, - 0x8f94871d, 0x3d33ec39, - 0x8f7c8701, 0x3d07c1d6, 0x8f649840, 0x3cdb8e09, 0x8f4cbadb, 0x3caf50da, - 0x8f34eed8, 0x3c830a50, - 0x8f1d343a, 0x3c56ba70, 0x8f058b04, 0x3c2a6142, 0x8eedf33b, 0x3bfdfecd, - 0x8ed66ce1, 0x3bd19318, - 0x8ebef7fb, 0x3ba51e29, 0x8ea7948c, 0x3b78a007, 0x8e904298, 0x3b4c18ba, - 0x8e790222, 0x3b1f8848, - 0x8e61d32e, 0x3af2eeb7, 0x8e4ab5bf, 0x3ac64c0f, 0x8e33a9da, 0x3a99a057, - 0x8e1caf80, 0x3a6ceb96, - 0x8e05c6b7, 0x3a402dd2, 0x8deeef82, 0x3a136712, 0x8dd829e4, 0x39e6975e, - 0x8dc175e0, 0x39b9bebc, - 0x8daad37b, 0x398cdd32, 0x8d9442b8, 0x395ff2c9, 0x8d7dc399, 0x3932ff87, - 0x8d675623, 0x39060373, - 0x8d50fa59, 0x38d8fe93, 0x8d3ab03f, 0x38abf0ef, 0x8d2477d8, 0x387eda8e, - 0x8d0e5127, 0x3851bb77, - 0x8cf83c30, 0x382493b0, 0x8ce238f6, 0x37f76341, 0x8ccc477d, 0x37ca2a30, - 0x8cb667c8, 0x379ce885, - 0x8ca099da, 0x376f9e46, 0x8c8addb7, 0x37424b7b, 0x8c753362, 0x3714f02a, - 0x8c5f9ade, 0x36e78c5b, - 0x8c4a142f, 0x36ba2014, 0x8c349f58, 0x368cab5c, 0x8c1f3c5d, 0x365f2e3b, - 0x8c09eb40, 0x3631a8b8, - 0x8bf4ac05, 0x36041ad9, 0x8bdf7eb0, 0x35d684a6, 0x8bca6343, 0x35a8e625, - 0x8bb559c1, 0x357b3f5d, - 0x8ba0622f, 0x354d9057, 0x8b8b7c8f, 0x351fd918, 0x8b76a8e4, 0x34f219a8, - 0x8b61e733, 0x34c4520d, - 0x8b4d377c, 0x34968250, 0x8b3899c6, 0x3468aa76, 0x8b240e11, 0x343aca87, - 0x8b0f9462, 0x340ce28b, - 0x8afb2cbb, 0x33def287, 0x8ae6d720, 0x33b0fa84, 0x8ad29394, 0x3382fa88, - 0x8abe6219, 0x3354f29b, - 0x8aaa42b4, 0x3326e2c3, 0x8a963567, 0x32f8cb07, 0x8a823a36, 0x32caab6f, - 0x8a6e5123, 0x329c8402, - 0x8a5a7a31, 0x326e54c7, 0x8a46b564, 0x32401dc6, 0x8a3302be, 0x3211df04, - 0x8a1f6243, 0x31e39889, - 0x8a0bd3f5, 0x31b54a5e, 0x89f857d8, 0x3186f487, 0x89e4edef, 0x3158970e, - 0x89d1963c, 0x312a31f8, - 0x89be50c3, 0x30fbc54d, 0x89ab1d87, 0x30cd5115, 0x8997fc8a, 0x309ed556, - 0x8984edcf, 0x30705217, - 0x8971f15a, 0x3041c761, 0x895f072e, 0x30133539, 0x894c2f4c, 0x2fe49ba7, - 0x893969b9, 0x2fb5fab2, - 0x8926b677, 0x2f875262, 0x89141589, 0x2f58a2be, 0x890186f2, 0x2f29ebcc, - 0x88ef0ab4, 0x2efb2d95, - 0x88dca0d3, 0x2ecc681e, 0x88ca4951, 0x2e9d9b70, 0x88b80432, 0x2e6ec792, - 0x88a5d177, 0x2e3fec8b, - 0x8893b125, 0x2e110a62, 0x8881a33d, 0x2de2211e, 0x886fa7c2, 0x2db330c7, - 0x885dbeb8, 0x2d843964, - 0x884be821, 0x2d553afc, 0x883a23ff, 0x2d263596, 0x88287256, 0x2cf72939, - 0x8816d327, 0x2cc815ee, - 0x88054677, 0x2c98fbba, 0x87f3cc48, 0x2c69daa6, 0x87e2649b, 0x2c3ab2b9, - 0x87d10f75, 0x2c0b83fa, - 0x87bfccd7, 0x2bdc4e6f, 0x87ae9cc5, 0x2bad1221, 0x879d7f41, 0x2b7dcf17, - 0x878c744d, 0x2b4e8558, - 0x877b7bec, 0x2b1f34eb, 0x876a9621, 0x2aefddd8, 0x8759c2ef, 0x2ac08026, - 0x87490258, 0x2a911bdc, - 0x8738545e, 0x2a61b101, 0x8727b905, 0x2a323f9e, 0x8717304e, 0x2a02c7b8, - 0x8706ba3d, 0x29d34958, - 0x86f656d3, 0x29a3c485, 0x86e60614, 0x29743946, 0x86d5c802, 0x2944a7a2, - 0x86c59c9f, 0x29150fa1, - 0x86b583ee, 0x28e5714b, 0x86a57df2, 0x28b5cca5, 0x86958aac, 0x288621b9, - 0x8685aa20, 0x2856708d, - 0x8675dc4f, 0x2826b928, 0x8666213c, 0x27f6fb92, 0x865678eb, 0x27c737d3, - 0x8646e35c, 0x27976df1, - 0x86376092, 0x27679df4, 0x8627f091, 0x2737c7e3, 0x86189359, 0x2707ebc7, - 0x860948ef, 0x26d809a5, - 0x85fa1153, 0x26a82186, 0x85eaec88, 0x26783370, 0x85dbda91, 0x26483f6c, - 0x85ccdb70, 0x26184581, - 0x85bdef28, 0x25e845b6, 0x85af15b9, 0x25b84012, 0x85a04f28, 0x2588349d, - 0x85919b76, 0x2558235f, - 0x8582faa5, 0x25280c5e, 0x85746cb8, 0x24f7efa2, 0x8565f1b0, 0x24c7cd33, - 0x85578991, 0x2497a517, - 0x8549345c, 0x24677758, 0x853af214, 0x243743fa, 0x852cc2bb, 0x24070b08, - 0x851ea652, 0x23d6cc87, - 0x85109cdd, 0x23a6887f, 0x8502a65c, 0x23763ef7, 0x84f4c2d4, 0x2345eff8, - 0x84e6f244, 0x23159b88, - 0x84d934b1, 0x22e541af, 0x84cb8a1b, 0x22b4e274, 0x84bdf286, 0x22847de0, - 0x84b06df2, 0x225413f8, - 0x84a2fc62, 0x2223a4c5, 0x84959dd9, 0x21f3304f, 0x84885258, 0x21c2b69c, - 0x847b19e1, 0x219237b5, - 0x846df477, 0x2161b3a0, 0x8460e21a, 0x21312a65, 0x8453e2cf, 0x21009c0c, - 0x8446f695, 0x20d0089c, - 0x843a1d70, 0x209f701c, 0x842d5762, 0x206ed295, 0x8420a46c, 0x203e300d, - 0x84140490, 0x200d888d, - 0x840777d0, 0x1fdcdc1b, 0x83fafe2e, 0x1fac2abf, 0x83ee97ad, 0x1f7b7481, - 0x83e2444d, 0x1f4ab968, - 0x83d60412, 0x1f19f97b, 0x83c9d6fc, 0x1ee934c3, 0x83bdbd0e, 0x1eb86b46, - 0x83b1b649, 0x1e879d0d, - 0x83a5c2b0, 0x1e56ca1e, 0x8399e244, 0x1e25f282, 0x838e1507, 0x1df5163f, - 0x83825afb, 0x1dc4355e, - 0x8376b422, 0x1d934fe5, 0x836b207d, 0x1d6265dd, 0x835fa00f, 0x1d31774d, - 0x835432d8, 0x1d00843d, - 0x8348d8dc, 0x1ccf8cb3, 0x833d921b, 0x1c9e90b8, 0x83325e97, 0x1c6d9053, - 0x83273e52, 0x1c3c8b8c, - 0x831c314e, 0x1c0b826a, 0x8311378d, 0x1bda74f6, 0x83065110, 0x1ba96335, - 0x82fb7dd8, 0x1b784d30, - 0x82f0bde8, 0x1b4732ef, 0x82e61141, 0x1b161479, 0x82db77e5, 0x1ae4f1d6, - 0x82d0f1d5, 0x1ab3cb0d, - 0x82c67f14, 0x1a82a026, 0x82bc1fa2, 0x1a517128, 0x82b1d381, 0x1a203e1b, - 0x82a79ab3, 0x19ef0707, - 0x829d753a, 0x19bdcbf3, 0x82936317, 0x198c8ce7, 0x8289644b, 0x195b49ea, - 0x827f78d8, 0x192a0304, - 0x8275a0c0, 0x18f8b83c, 0x826bdc04, 0x18c7699b, 0x82622aa6, 0x18961728, - 0x82588ca7, 0x1864c0ea, - 0x824f0208, 0x183366e9, 0x82458acc, 0x1802092c, 0x823c26f3, 0x17d0a7bc, - 0x8232d67f, 0x179f429f, - 0x82299971, 0x176dd9de, 0x82206fcc, 0x173c6d80, 0x82175990, 0x170afd8d, - 0x820e56be, 0x16d98a0c, - 0x82056758, 0x16a81305, 0x81fc8b60, 0x1676987f, 0x81f3c2d7, 0x16451a83, - 0x81eb0dbe, 0x16139918, - 0x81e26c16, 0x15e21445, 0x81d9dde1, 0x15b08c12, 0x81d16321, 0x157f0086, - 0x81c8fbd6, 0x154d71aa, - 0x81c0a801, 0x151bdf86, 0x81b867a5, 0x14ea4a1f, 0x81b03ac2, 0x14b8b17f, - 0x81a82159, 0x148715ae, - 0x81a01b6d, 0x145576b1, 0x819828fd, 0x1423d492, 0x81904a0c, 0x13f22f58, - 0x81887e9a, 0x13c0870a, - 0x8180c6a9, 0x138edbb1, 0x8179223a, 0x135d2d53, 0x8171914e, 0x132b7bf9, - 0x816a13e6, 0x12f9c7aa, - 0x8162aa04, 0x12c8106f, 0x815b53a8, 0x1296564d, 0x815410d4, 0x1264994e, - 0x814ce188, 0x1232d979, - 0x8145c5c7, 0x120116d5, 0x813ebd90, 0x11cf516a, 0x8137c8e6, 0x119d8941, - 0x8130e7c9, 0x116bbe60, - 0x812a1a3a, 0x1139f0cf, 0x8123603a, 0x11082096, 0x811cb9ca, 0x10d64dbd, - 0x811626ec, 0x10a4784b, - 0x810fa7a0, 0x1072a048, 0x81093be8, 0x1040c5bb, 0x8102e3c4, 0x100ee8ad, - 0x80fc9f35, 0xfdd0926, - 0x80f66e3c, 0xfab272b, 0x80f050db, 0xf7942c7, 0x80ea4712, 0xf475bff, - 0x80e450e2, 0xf1572dc, - 0x80de6e4c, 0xee38766, 0x80d89f51, 0xeb199a4, 0x80d2e3f2, 0xe7fa99e, - 0x80cd3c2f, 0xe4db75b, - 0x80c7a80a, 0xe1bc2e4, 0x80c22784, 0xde9cc40, 0x80bcba9d, 0xdb7d376, - 0x80b76156, 0xd85d88f, - 0x80b21baf, 0xd53db92, 0x80ace9ab, 0xd21dc87, 0x80a7cb49, 0xcefdb76, - 0x80a2c08b, 0xcbdd865, - 0x809dc971, 0xc8bd35e, 0x8098e5fb, 0xc59cc68, 0x8094162c, 0xc27c389, - 0x808f5a02, 0xbf5b8cb, - 0x808ab180, 0xbc3ac35, 0x80861ca6, 0xb919dcf, 0x80819b74, 0xb5f8d9f, - 0x807d2dec, 0xb2d7baf, - 0x8078d40d, 0xafb6805, 0x80748dd9, 0xac952aa, 0x80705b50, 0xa973ba5, - 0x806c3c74, 0xa6522fe, - 0x80683143, 0xa3308bd, 0x806439c0, 0xa00ece8, 0x806055eb, 0x9cecf89, - 0x805c85c4, 0x99cb0a7, - 0x8058c94c, 0x96a9049, 0x80552084, 0x9386e78, 0x80518b6b, 0x9064b3a, - 0x804e0a04, 0x8d42699, - 0x804a9c4d, 0x8a2009a, 0x80474248, 0x86fd947, 0x8043fbf6, 0x83db0a7, - 0x8040c956, 0x80b86c2, - 0x803daa6a, 0x7d95b9e, 0x803a9f31, 0x7a72f45, 0x8037a7ac, 0x77501be, - 0x8034c3dd, 0x742d311, - 0x8031f3c2, 0x710a345, 0x802f375d, 0x6de7262, 0x802c8ead, 0x6ac406f, - 0x8029f9b4, 0x67a0d76, - 0x80277872, 0x647d97c, 0x80250ae7, 0x615a48b, 0x8022b114, 0x5e36ea9, - 0x80206af8, 0x5b137df, - 0x801e3895, 0x57f0035, 0x801c19ea, 0x54cc7b1, 0x801a0ef8, 0x51a8e5c, - 0x801817bf, 0x4e8543e, - 0x80163440, 0x4b6195d, 0x8014647b, 0x483ddc3, 0x8012a86f, 0x451a177, - 0x8011001f, 0x41f6480, - 0x800f6b88, 0x3ed26e6, 0x800deaad, 0x3bae8b2, 0x800c7d8c, 0x388a9ea, - 0x800b2427, 0x3566a96, - 0x8009de7e, 0x3242abf, 0x8008ac90, 0x2f1ea6c, 0x80078e5e, 0x2bfa9a4, - 0x800683e8, 0x28d6870, - 0x80058d2f, 0x25b26d7, 0x8004aa32, 0x228e4e2, 0x8003daf1, 0x1f6a297, - 0x80031f6d, 0x1c45ffe, - 0x800277a6, 0x1921d20, 0x8001e39b, 0x15fda03, 0x8001634e, 0x12d96b1, - 0x8000f6bd, 0xfb5330, - 0x80009dea, 0xc90f88, 0x800058d4, 0x96cbc1, 0x8000277a, 0x6487e3, - 0x800009df, 0x3243f5, - 0x80000000, 0x0, 0x800009df, 0xffcdbc0b, 0x8000277a, 0xff9b781d, 0x800058d4, - 0xff69343f, - 0x80009dea, 0xff36f078, 0x8000f6bd, 0xff04acd0, 0x8001634e, 0xfed2694f, - 0x8001e39b, 0xfea025fd, - 0x800277a6, 0xfe6de2e0, 0x80031f6d, 0xfe3ba002, 0x8003daf1, 0xfe095d69, - 0x8004aa32, 0xfdd71b1e, - 0x80058d2f, 0xfda4d929, 0x800683e8, 0xfd729790, 0x80078e5e, 0xfd40565c, - 0x8008ac90, 0xfd0e1594, - 0x8009de7e, 0xfcdbd541, 0x800b2427, 0xfca9956a, 0x800c7d8c, 0xfc775616, - 0x800deaad, 0xfc45174e, - 0x800f6b88, 0xfc12d91a, 0x8011001f, 0xfbe09b80, 0x8012a86f, 0xfbae5e89, - 0x8014647b, 0xfb7c223d, - 0x80163440, 0xfb49e6a3, 0x801817bf, 0xfb17abc2, 0x801a0ef8, 0xfae571a4, - 0x801c19ea, 0xfab3384f, - 0x801e3895, 0xfa80ffcb, 0x80206af8, 0xfa4ec821, 0x8022b114, 0xfa1c9157, - 0x80250ae7, 0xf9ea5b75, - 0x80277872, 0xf9b82684, 0x8029f9b4, 0xf985f28a, 0x802c8ead, 0xf953bf91, - 0x802f375d, 0xf9218d9e, - 0x8031f3c2, 0xf8ef5cbb, 0x8034c3dd, 0xf8bd2cef, 0x8037a7ac, 0xf88afe42, - 0x803a9f31, 0xf858d0bb, - 0x803daa6a, 0xf826a462, 0x8040c956, 0xf7f4793e, 0x8043fbf6, 0xf7c24f59, - 0x80474248, 0xf79026b9, - 0x804a9c4d, 0xf75dff66, 0x804e0a04, 0xf72bd967, 0x80518b6b, 0xf6f9b4c6, - 0x80552084, 0xf6c79188, - 0x8058c94c, 0xf6956fb7, 0x805c85c4, 0xf6634f59, 0x806055eb, 0xf6313077, - 0x806439c0, 0xf5ff1318, - 0x80683143, 0xf5ccf743, 0x806c3c74, 0xf59add02, 0x80705b50, 0xf568c45b, - 0x80748dd9, 0xf536ad56, - 0x8078d40d, 0xf50497fb, 0x807d2dec, 0xf4d28451, 0x80819b74, 0xf4a07261, - 0x80861ca6, 0xf46e6231, - 0x808ab180, 0xf43c53cb, 0x808f5a02, 0xf40a4735, 0x8094162c, 0xf3d83c77, - 0x8098e5fb, 0xf3a63398, - 0x809dc971, 0xf3742ca2, 0x80a2c08b, 0xf342279b, 0x80a7cb49, 0xf310248a, - 0x80ace9ab, 0xf2de2379, - 0x80b21baf, 0xf2ac246e, 0x80b76156, 0xf27a2771, 0x80bcba9d, 0xf2482c8a, - 0x80c22784, 0xf21633c0, - 0x80c7a80a, 0xf1e43d1c, 0x80cd3c2f, 0xf1b248a5, 0x80d2e3f2, 0xf1805662, - 0x80d89f51, 0xf14e665c, - 0x80de6e4c, 0xf11c789a, 0x80e450e2, 0xf0ea8d24, 0x80ea4712, 0xf0b8a401, - 0x80f050db, 0xf086bd39, - 0x80f66e3c, 0xf054d8d5, 0x80fc9f35, 0xf022f6da, 0x8102e3c4, 0xeff11753, - 0x81093be8, 0xefbf3a45, - 0x810fa7a0, 0xef8d5fb8, 0x811626ec, 0xef5b87b5, 0x811cb9ca, 0xef29b243, - 0x8123603a, 0xeef7df6a, - 0x812a1a3a, 0xeec60f31, 0x8130e7c9, 0xee9441a0, 0x8137c8e6, 0xee6276bf, - 0x813ebd90, 0xee30ae96, - 0x8145c5c7, 0xedfee92b, 0x814ce188, 0xedcd2687, 0x815410d4, 0xed9b66b2, - 0x815b53a8, 0xed69a9b3, - 0x8162aa04, 0xed37ef91, 0x816a13e6, 0xed063856, 0x8171914e, 0xecd48407, - 0x8179223a, 0xeca2d2ad, - 0x8180c6a9, 0xec71244f, 0x81887e9a, 0xec3f78f6, 0x81904a0c, 0xec0dd0a8, - 0x819828fd, 0xebdc2b6e, - 0x81a01b6d, 0xebaa894f, 0x81a82159, 0xeb78ea52, 0x81b03ac2, 0xeb474e81, - 0x81b867a5, 0xeb15b5e1, - 0x81c0a801, 0xeae4207a, 0x81c8fbd6, 0xeab28e56, 0x81d16321, 0xea80ff7a, - 0x81d9dde1, 0xea4f73ee, - 0x81e26c16, 0xea1debbb, 0x81eb0dbe, 0xe9ec66e8, 0x81f3c2d7, 0xe9bae57d, - 0x81fc8b60, 0xe9896781, - 0x82056758, 0xe957ecfb, 0x820e56be, 0xe92675f4, 0x82175990, 0xe8f50273, - 0x82206fcc, 0xe8c39280, - 0x82299971, 0xe8922622, 0x8232d67f, 0xe860bd61, 0x823c26f3, 0xe82f5844, - 0x82458acc, 0xe7fdf6d4, - 0x824f0208, 0xe7cc9917, 0x82588ca7, 0xe79b3f16, 0x82622aa6, 0xe769e8d8, - 0x826bdc04, 0xe7389665, - 0x8275a0c0, 0xe70747c4, 0x827f78d8, 0xe6d5fcfc, 0x8289644b, 0xe6a4b616, - 0x82936317, 0xe6737319, - 0x829d753a, 0xe642340d, 0x82a79ab3, 0xe610f8f9, 0x82b1d381, 0xe5dfc1e5, - 0x82bc1fa2, 0xe5ae8ed8, - 0x82c67f14, 0xe57d5fda, 0x82d0f1d5, 0xe54c34f3, 0x82db77e5, 0xe51b0e2a, - 0x82e61141, 0xe4e9eb87, - 0x82f0bde8, 0xe4b8cd11, 0x82fb7dd8, 0xe487b2d0, 0x83065110, 0xe4569ccb, - 0x8311378d, 0xe4258b0a, - 0x831c314e, 0xe3f47d96, 0x83273e52, 0xe3c37474, 0x83325e97, 0xe3926fad, - 0x833d921b, 0xe3616f48, - 0x8348d8dc, 0xe330734d, 0x835432d8, 0xe2ff7bc3, 0x835fa00f, 0xe2ce88b3, - 0x836b207d, 0xe29d9a23, - 0x8376b422, 0xe26cb01b, 0x83825afb, 0xe23bcaa2, 0x838e1507, 0xe20ae9c1, - 0x8399e244, 0xe1da0d7e, - 0x83a5c2b0, 0xe1a935e2, 0x83b1b649, 0xe17862f3, 0x83bdbd0e, 0xe14794ba, - 0x83c9d6fc, 0xe116cb3d, - 0x83d60412, 0xe0e60685, 0x83e2444d, 0xe0b54698, 0x83ee97ad, 0xe0848b7f, - 0x83fafe2e, 0xe053d541, - 0x840777d0, 0xe02323e5, 0x84140490, 0xdff27773, 0x8420a46c, 0xdfc1cff3, - 0x842d5762, 0xdf912d6b, - 0x843a1d70, 0xdf608fe4, 0x8446f695, 0xdf2ff764, 0x8453e2cf, 0xdeff63f4, - 0x8460e21a, 0xdeced59b, - 0x846df477, 0xde9e4c60, 0x847b19e1, 0xde6dc84b, 0x84885258, 0xde3d4964, - 0x84959dd9, 0xde0ccfb1, - 0x84a2fc62, 0xdddc5b3b, 0x84b06df2, 0xddabec08, 0x84bdf286, 0xdd7b8220, - 0x84cb8a1b, 0xdd4b1d8c, - 0x84d934b1, 0xdd1abe51, 0x84e6f244, 0xdcea6478, 0x84f4c2d4, 0xdcba1008, - 0x8502a65c, 0xdc89c109, - 0x85109cdd, 0xdc597781, 0x851ea652, 0xdc293379, 0x852cc2bb, 0xdbf8f4f8, - 0x853af214, 0xdbc8bc06, - 0x8549345c, 0xdb9888a8, 0x85578991, 0xdb685ae9, 0x8565f1b0, 0xdb3832cd, - 0x85746cb8, 0xdb08105e, - 0x8582faa5, 0xdad7f3a2, 0x85919b76, 0xdaa7dca1, 0x85a04f28, 0xda77cb63, - 0x85af15b9, 0xda47bfee, - 0x85bdef28, 0xda17ba4a, 0x85ccdb70, 0xd9e7ba7f, 0x85dbda91, 0xd9b7c094, - 0x85eaec88, 0xd987cc90, - 0x85fa1153, 0xd957de7a, 0x860948ef, 0xd927f65b, 0x86189359, 0xd8f81439, - 0x8627f091, 0xd8c8381d, - 0x86376092, 0xd898620c, 0x8646e35c, 0xd868920f, 0x865678eb, 0xd838c82d, - 0x8666213c, 0xd809046e, - 0x8675dc4f, 0xd7d946d8, 0x8685aa20, 0xd7a98f73, 0x86958aac, 0xd779de47, - 0x86a57df2, 0xd74a335b, - 0x86b583ee, 0xd71a8eb5, 0x86c59c9f, 0xd6eaf05f, 0x86d5c802, 0xd6bb585e, - 0x86e60614, 0xd68bc6ba, - 0x86f656d3, 0xd65c3b7b, 0x8706ba3d, 0xd62cb6a8, 0x8717304e, 0xd5fd3848, - 0x8727b905, 0xd5cdc062, - 0x8738545e, 0xd59e4eff, 0x87490258, 0xd56ee424, 0x8759c2ef, 0xd53f7fda, - 0x876a9621, 0xd5102228, - 0x877b7bec, 0xd4e0cb15, 0x878c744d, 0xd4b17aa8, 0x879d7f41, 0xd48230e9, - 0x87ae9cc5, 0xd452eddf, - 0x87bfccd7, 0xd423b191, 0x87d10f75, 0xd3f47c06, 0x87e2649b, 0xd3c54d47, - 0x87f3cc48, 0xd396255a, - 0x88054677, 0xd3670446, 0x8816d327, 0xd337ea12, 0x88287256, 0xd308d6c7, - 0x883a23ff, 0xd2d9ca6a, - 0x884be821, 0xd2aac504, 0x885dbeb8, 0xd27bc69c, 0x886fa7c2, 0xd24ccf39, - 0x8881a33d, 0xd21ddee2, - 0x8893b125, 0xd1eef59e, 0x88a5d177, 0xd1c01375, 0x88b80432, 0xd191386e, - 0x88ca4951, 0xd1626490, - 0x88dca0d3, 0xd13397e2, 0x88ef0ab4, 0xd104d26b, 0x890186f2, 0xd0d61434, - 0x89141589, 0xd0a75d42, - 0x8926b677, 0xd078ad9e, 0x893969b9, 0xd04a054e, 0x894c2f4c, 0xd01b6459, - 0x895f072e, 0xcfeccac7, - 0x8971f15a, 0xcfbe389f, 0x8984edcf, 0xcf8fade9, 0x8997fc8a, 0xcf612aaa, - 0x89ab1d87, 0xcf32aeeb, - 0x89be50c3, 0xcf043ab3, 0x89d1963c, 0xced5ce08, 0x89e4edef, 0xcea768f2, - 0x89f857d8, 0xce790b79, - 0x8a0bd3f5, 0xce4ab5a2, 0x8a1f6243, 0xce1c6777, 0x8a3302be, 0xcdee20fc, - 0x8a46b564, 0xcdbfe23a, - 0x8a5a7a31, 0xcd91ab39, 0x8a6e5123, 0xcd637bfe, 0x8a823a36, 0xcd355491, - 0x8a963567, 0xcd0734f9, - 0x8aaa42b4, 0xccd91d3d, 0x8abe6219, 0xccab0d65, 0x8ad29394, 0xcc7d0578, - 0x8ae6d720, 0xcc4f057c, - 0x8afb2cbb, 0xcc210d79, 0x8b0f9462, 0xcbf31d75, 0x8b240e11, 0xcbc53579, - 0x8b3899c6, 0xcb97558a, - 0x8b4d377c, 0xcb697db0, 0x8b61e733, 0xcb3badf3, 0x8b76a8e4, 0xcb0de658, - 0x8b8b7c8f, 0xcae026e8, - 0x8ba0622f, 0xcab26fa9, 0x8bb559c1, 0xca84c0a3, 0x8bca6343, 0xca5719db, - 0x8bdf7eb0, 0xca297b5a, - 0x8bf4ac05, 0xc9fbe527, 0x8c09eb40, 0xc9ce5748, 0x8c1f3c5d, 0xc9a0d1c5, - 0x8c349f58, 0xc97354a4, - 0x8c4a142f, 0xc945dfec, 0x8c5f9ade, 0xc91873a5, 0x8c753362, 0xc8eb0fd6, - 0x8c8addb7, 0xc8bdb485, - 0x8ca099da, 0xc89061ba, 0x8cb667c8, 0xc863177b, 0x8ccc477d, 0xc835d5d0, - 0x8ce238f6, 0xc8089cbf, - 0x8cf83c30, 0xc7db6c50, 0x8d0e5127, 0xc7ae4489, 0x8d2477d8, 0xc7812572, - 0x8d3ab03f, 0xc7540f11, - 0x8d50fa59, 0xc727016d, 0x8d675623, 0xc6f9fc8d, 0x8d7dc399, 0xc6cd0079, - 0x8d9442b8, 0xc6a00d37, - 0x8daad37b, 0xc67322ce, 0x8dc175e0, 0xc6464144, 0x8dd829e4, 0xc61968a2, - 0x8deeef82, 0xc5ec98ee, - 0x8e05c6b7, 0xc5bfd22e, 0x8e1caf80, 0xc593146a, 0x8e33a9da, 0xc5665fa9, - 0x8e4ab5bf, 0xc539b3f1, - 0x8e61d32e, 0xc50d1149, 0x8e790222, 0xc4e077b8, 0x8e904298, 0xc4b3e746, - 0x8ea7948c, 0xc4875ff9, - 0x8ebef7fb, 0xc45ae1d7, 0x8ed66ce1, 0xc42e6ce8, 0x8eedf33b, 0xc4020133, - 0x8f058b04, 0xc3d59ebe, - 0x8f1d343a, 0xc3a94590, 0x8f34eed8, 0xc37cf5b0, 0x8f4cbadb, 0xc350af26, - 0x8f649840, 0xc32471f7, - 0x8f7c8701, 0xc2f83e2a, 0x8f94871d, 0xc2cc13c7, 0x8fac988f, 0xc29ff2d4, - 0x8fc4bb53, 0xc273db58, - 0x8fdcef66, 0xc247cd5a, 0x8ff534c4, 0xc21bc8e1, 0x900d8b69, 0xc1efcdf3, - 0x9025f352, 0xc1c3dc97, - 0x903e6c7b, 0xc197f4d4, 0x9056f6df, 0xc16c16b0, 0x906f927c, 0xc1404233, - 0x90883f4d, 0xc1147764, - 0x90a0fd4e, 0xc0e8b648, 0x90b9cc7d, 0xc0bcfee7, 0x90d2acd4, 0xc0915148, - 0x90eb9e50, 0xc065ad70, - 0x9104a0ee, 0xc03a1368, 0x911db4a9, 0xc00e8336, 0x9136d97d, 0xbfe2fcdf, - 0x91500f67, 0xbfb7806c, - 0x91695663, 0xbf8c0de3, 0x9182ae6d, 0xbf60a54a, 0x919c1781, 0xbf3546a8, - 0x91b5919a, 0xbf09f205, - 0x91cf1cb6, 0xbedea765, 0x91e8b8d0, 0xbeb366d1, 0x920265e4, 0xbe88304f, - 0x921c23ef, 0xbe5d03e6, - 0x9235f2ec, 0xbe31e19b, 0x924fd2d7, 0xbe06c977, 0x9269c3ac, 0xbddbbb7f, - 0x9283c568, 0xbdb0b7bb, - 0x929dd806, 0xbd85be30, 0x92b7fb82, 0xbd5acee5, 0x92d22fd9, 0xbd2fe9e2, - 0x92ec7505, 0xbd050f2c, - 0x9306cb04, 0xbcda3ecb, 0x932131d1, 0xbcaf78c4, 0x933ba968, 0xbc84bd1f, - 0x935631c5, 0xbc5a0be2, - 0x9370cae4, 0xbc2f6513, 0x938b74c1, 0xbc04c8ba, 0x93a62f57, 0xbbda36dd, - 0x93c0faa3, 0xbbafaf82, - 0x93dbd6a0, 0xbb8532b0, 0x93f6c34a, 0xbb5ac06d, 0x9411c09e, 0xbb3058c0, - 0x942cce96, 0xbb05fbb0, - 0x9447ed2f, 0xbadba943, 0x94631c65, 0xbab16180, 0x947e5c33, 0xba87246d, - 0x9499ac95, 0xba5cf210, - 0x94b50d87, 0xba32ca71, 0x94d07f05, 0xba08ad95, 0x94ec010b, 0xb9de9b83, - 0x95079394, 0xb9b49442, - 0x9523369c, 0xb98a97d8, 0x953eea1e, 0xb960a64c, 0x955aae17, 0xb936bfa4, - 0x95768283, 0xb90ce3e6, - 0x9592675c, 0xb8e31319, 0x95ae5c9f, 0xb8b94d44, 0x95ca6247, 0xb88f926d, - 0x95e67850, 0xb865e299, - 0x96029eb6, 0xb83c3dd1, 0x961ed574, 0xb812a41a, 0x963b1c86, 0xb7e9157a, - 0x965773e7, 0xb7bf91f8, - 0x9673db94, 0xb796199b, 0x96905388, 0xb76cac69, 0x96acdbbe, 0xb7434a67, - 0x96c97432, 0xb719f39e, - 0x96e61ce0, 0xb6f0a812, 0x9702d5c3, 0xb6c767ca, 0x971f9ed7, 0xb69e32cd, - 0x973c7817, 0xb6750921, - 0x9759617f, 0xb64beacd, 0x97765b0a, 0xb622d7d6, 0x979364b5, 0xb5f9d043, - 0x97b07e7a, 0xb5d0d41a, - 0x97cda855, 0xb5a7e362, 0x97eae242, 0xb57efe22, 0x98082c3b, 0xb556245e, - 0x9825863d, 0xb52d561e, - 0x9842f043, 0xb5049368, 0x98606a49, 0xb4dbdc42, 0x987df449, 0xb4b330b3, - 0x989b8e40, 0xb48a90c0, - 0x98b93828, 0xb461fc70, 0x98d6f1fe, 0xb43973ca, 0x98f4bbbc, 0xb410f6d3, - 0x9912955f, 0xb3e88592, - 0x99307ee0, 0xb3c0200c, 0x994e783d, 0xb397c649, 0x996c816f, 0xb36f784f, - 0x998a9a74, 0xb3473623, - 0x99a8c345, 0xb31effcc, 0x99c6fbde, 0xb2f6d550, 0x99e5443b, 0xb2ceb6b5, - 0x9a039c57, 0xb2a6a402, - 0x9a22042d, 0xb27e9d3c, 0x9a407bb9, 0xb256a26a, 0x9a5f02f5, 0xb22eb392, - 0x9a7d99de, 0xb206d0ba, - 0x9a9c406e, 0xb1def9e9, 0x9abaf6a1, 0xb1b72f23, 0x9ad9bc71, 0xb18f7071, - 0x9af891db, 0xb167bdd7, - 0x9b1776da, 0xb140175b, 0x9b366b68, 0xb1187d05, 0x9b556f81, 0xb0f0eeda, - 0x9b748320, 0xb0c96ce0, - 0x9b93a641, 0xb0a1f71d, 0x9bb2d8de, 0xb07a8d97, 0x9bd21af3, 0xb0533055, - 0x9bf16c7a, 0xb02bdf5c, - 0x9c10cd70, 0xb0049ab3, 0x9c303dcf, 0xafdd625f, 0x9c4fbd93, 0xafb63667, - 0x9c6f4cb6, 0xaf8f16d1, - 0x9c8eeb34, 0xaf6803a2, 0x9cae9907, 0xaf40fce1, 0x9cce562c, 0xaf1a0293, - 0x9cee229c, 0xaef314c0, - 0x9d0dfe54, 0xaecc336c, 0x9d2de94d, 0xaea55e9e, 0x9d4de385, 0xae7e965b, - 0x9d6decf4, 0xae57daab, - 0x9d8e0597, 0xae312b92, 0x9dae2d68, 0xae0a8916, 0x9dce6463, 0xade3f33e, - 0x9deeaa82, 0xadbd6a10, - 0x9e0effc1, 0xad96ed92, 0x9e2f641b, 0xad707dc8, 0x9e4fd78a, 0xad4a1aba, - 0x9e705a09, 0xad23c46e, - 0x9e90eb94, 0xacfd7ae8, 0x9eb18c26, 0xacd73e30, 0x9ed23bb9, 0xacb10e4b, - 0x9ef2fa49, 0xac8aeb3e, - 0x9f13c7d0, 0xac64d510, 0x9f34a449, 0xac3ecbc7, 0x9f558fb0, 0xac18cf69, - 0x9f7689ff, 0xabf2dffb, - 0x9f979331, 0xabccfd83, 0x9fb8ab41, 0xaba72807, 0x9fd9d22a, 0xab815f8d, - 0x9ffb07e7, 0xab5ba41a, - 0xa01c4c73, 0xab35f5b5, 0xa03d9fc8, 0xab105464, 0xa05f01e1, 0xaaeac02c, - 0xa08072ba, 0xaac53912, - 0xa0a1f24d, 0xaa9fbf1e, 0xa0c38095, 0xaa7a5253, 0xa0e51d8c, 0xaa54f2ba, - 0xa106c92f, 0xaa2fa056, - 0xa1288376, 0xaa0a5b2e, 0xa14a4c5e, 0xa9e52347, 0xa16c23e1, 0xa9bff8a8, - 0xa18e09fa, 0xa99adb56, - 0xa1affea3, 0xa975cb57, 0xa1d201d7, 0xa950c8b0, 0xa1f41392, 0xa92bd367, - 0xa21633cd, 0xa906eb82, - 0xa2386284, 0xa8e21106, 0xa25a9fb1, 0xa8bd43fa, 0xa27ceb4f, 0xa8988463, - 0xa29f4559, 0xa873d246, - 0xa2c1adc9, 0xa84f2daa, 0xa2e4249b, 0xa82a9693, 0xa306a9c8, 0xa8060d08, - 0xa3293d4b, 0xa7e1910f, - 0xa34bdf20, 0xa7bd22ac, 0xa36e8f41, 0xa798c1e5, 0xa3914da8, 0xa7746ec0, - 0xa3b41a50, 0xa7502943, - 0xa3d6f534, 0xa72bf174, 0xa3f9de4e, 0xa707c757, 0xa41cd599, 0xa6e3aaf2, - 0xa43fdb10, 0xa6bf9c4b, - 0xa462eeac, 0xa69b9b68, 0xa486106a, 0xa677a84e, 0xa4a94043, 0xa653c303, - 0xa4cc7e32, 0xa62feb8b, - 0xa4efca31, 0xa60c21ee, 0xa513243b, 0xa5e8662f, 0xa5368c4b, 0xa5c4b855, - 0xa55a025b, 0xa5a11866, - 0xa57d8666, 0xa57d8666, 0xa5a11866, 0xa55a025b, 0xa5c4b855, 0xa5368c4b, - 0xa5e8662f, 0xa513243b, - 0xa60c21ee, 0xa4efca31, 0xa62feb8b, 0xa4cc7e32, 0xa653c303, 0xa4a94043, - 0xa677a84e, 0xa486106a, - 0xa69b9b68, 0xa462eeac, 0xa6bf9c4b, 0xa43fdb10, 0xa6e3aaf2, 0xa41cd599, - 0xa707c757, 0xa3f9de4e, - 0xa72bf174, 0xa3d6f534, 0xa7502943, 0xa3b41a50, 0xa7746ec0, 0xa3914da8, - 0xa798c1e5, 0xa36e8f41, - 0xa7bd22ac, 0xa34bdf20, 0xa7e1910f, 0xa3293d4b, 0xa8060d08, 0xa306a9c8, - 0xa82a9693, 0xa2e4249b, - 0xa84f2daa, 0xa2c1adc9, 0xa873d246, 0xa29f4559, 0xa8988463, 0xa27ceb4f, - 0xa8bd43fa, 0xa25a9fb1, - 0xa8e21106, 0xa2386284, 0xa906eb82, 0xa21633cd, 0xa92bd367, 0xa1f41392, - 0xa950c8b0, 0xa1d201d7, - 0xa975cb57, 0xa1affea3, 0xa99adb56, 0xa18e09fa, 0xa9bff8a8, 0xa16c23e1, - 0xa9e52347, 0xa14a4c5e, - 0xaa0a5b2e, 0xa1288376, 0xaa2fa056, 0xa106c92f, 0xaa54f2ba, 0xa0e51d8c, - 0xaa7a5253, 0xa0c38095, - 0xaa9fbf1e, 0xa0a1f24d, 0xaac53912, 0xa08072ba, 0xaaeac02c, 0xa05f01e1, - 0xab105464, 0xa03d9fc8, - 0xab35f5b5, 0xa01c4c73, 0xab5ba41a, 0x9ffb07e7, 0xab815f8d, 0x9fd9d22a, - 0xaba72807, 0x9fb8ab41, - 0xabccfd83, 0x9f979331, 0xabf2dffb, 0x9f7689ff, 0xac18cf69, 0x9f558fb0, - 0xac3ecbc7, 0x9f34a449, - 0xac64d510, 0x9f13c7d0, 0xac8aeb3e, 0x9ef2fa49, 0xacb10e4b, 0x9ed23bb9, - 0xacd73e30, 0x9eb18c26, - 0xacfd7ae8, 0x9e90eb94, 0xad23c46e, 0x9e705a09, 0xad4a1aba, 0x9e4fd78a, - 0xad707dc8, 0x9e2f641b, - 0xad96ed92, 0x9e0effc1, 0xadbd6a10, 0x9deeaa82, 0xade3f33e, 0x9dce6463, - 0xae0a8916, 0x9dae2d68, - 0xae312b92, 0x9d8e0597, 0xae57daab, 0x9d6decf4, 0xae7e965b, 0x9d4de385, - 0xaea55e9e, 0x9d2de94d, - 0xaecc336c, 0x9d0dfe54, 0xaef314c0, 0x9cee229c, 0xaf1a0293, 0x9cce562c, - 0xaf40fce1, 0x9cae9907, - 0xaf6803a2, 0x9c8eeb34, 0xaf8f16d1, 0x9c6f4cb6, 0xafb63667, 0x9c4fbd93, - 0xafdd625f, 0x9c303dcf, - 0xb0049ab3, 0x9c10cd70, 0xb02bdf5c, 0x9bf16c7a, 0xb0533055, 0x9bd21af3, - 0xb07a8d97, 0x9bb2d8de, - 0xb0a1f71d, 0x9b93a641, 0xb0c96ce0, 0x9b748320, 0xb0f0eeda, 0x9b556f81, - 0xb1187d05, 0x9b366b68, - 0xb140175b, 0x9b1776da, 0xb167bdd7, 0x9af891db, 0xb18f7071, 0x9ad9bc71, - 0xb1b72f23, 0x9abaf6a1, - 0xb1def9e9, 0x9a9c406e, 0xb206d0ba, 0x9a7d99de, 0xb22eb392, 0x9a5f02f5, - 0xb256a26a, 0x9a407bb9, - 0xb27e9d3c, 0x9a22042d, 0xb2a6a402, 0x9a039c57, 0xb2ceb6b5, 0x99e5443b, - 0xb2f6d550, 0x99c6fbde, - 0xb31effcc, 0x99a8c345, 0xb3473623, 0x998a9a74, 0xb36f784f, 0x996c816f, - 0xb397c649, 0x994e783d, - 0xb3c0200c, 0x99307ee0, 0xb3e88592, 0x9912955f, 0xb410f6d3, 0x98f4bbbc, - 0xb43973ca, 0x98d6f1fe, - 0xb461fc70, 0x98b93828, 0xb48a90c0, 0x989b8e40, 0xb4b330b3, 0x987df449, - 0xb4dbdc42, 0x98606a49, - 0xb5049368, 0x9842f043, 0xb52d561e, 0x9825863d, 0xb556245e, 0x98082c3b, - 0xb57efe22, 0x97eae242, - 0xb5a7e362, 0x97cda855, 0xb5d0d41a, 0x97b07e7a, 0xb5f9d043, 0x979364b5, - 0xb622d7d6, 0x97765b0a, - 0xb64beacd, 0x9759617f, 0xb6750921, 0x973c7817, 0xb69e32cd, 0x971f9ed7, - 0xb6c767ca, 0x9702d5c3, - 0xb6f0a812, 0x96e61ce0, 0xb719f39e, 0x96c97432, 0xb7434a67, 0x96acdbbe, - 0xb76cac69, 0x96905388, - 0xb796199b, 0x9673db94, 0xb7bf91f8, 0x965773e7, 0xb7e9157a, 0x963b1c86, - 0xb812a41a, 0x961ed574, - 0xb83c3dd1, 0x96029eb6, 0xb865e299, 0x95e67850, 0xb88f926d, 0x95ca6247, - 0xb8b94d44, 0x95ae5c9f, - 0xb8e31319, 0x9592675c, 0xb90ce3e6, 0x95768283, 0xb936bfa4, 0x955aae17, - 0xb960a64c, 0x953eea1e, - 0xb98a97d8, 0x9523369c, 0xb9b49442, 0x95079394, 0xb9de9b83, 0x94ec010b, - 0xba08ad95, 0x94d07f05, - 0xba32ca71, 0x94b50d87, 0xba5cf210, 0x9499ac95, 0xba87246d, 0x947e5c33, - 0xbab16180, 0x94631c65, - 0xbadba943, 0x9447ed2f, 0xbb05fbb0, 0x942cce96, 0xbb3058c0, 0x9411c09e, - 0xbb5ac06d, 0x93f6c34a, - 0xbb8532b0, 0x93dbd6a0, 0xbbafaf82, 0x93c0faa3, 0xbbda36dd, 0x93a62f57, - 0xbc04c8ba, 0x938b74c1, - 0xbc2f6513, 0x9370cae4, 0xbc5a0be2, 0x935631c5, 0xbc84bd1f, 0x933ba968, - 0xbcaf78c4, 0x932131d1, - 0xbcda3ecb, 0x9306cb04, 0xbd050f2c, 0x92ec7505, 0xbd2fe9e2, 0x92d22fd9, - 0xbd5acee5, 0x92b7fb82, - 0xbd85be30, 0x929dd806, 0xbdb0b7bb, 0x9283c568, 0xbddbbb7f, 0x9269c3ac, - 0xbe06c977, 0x924fd2d7, - 0xbe31e19b, 0x9235f2ec, 0xbe5d03e6, 0x921c23ef, 0xbe88304f, 0x920265e4, - 0xbeb366d1, 0x91e8b8d0, - 0xbedea765, 0x91cf1cb6, 0xbf09f205, 0x91b5919a, 0xbf3546a8, 0x919c1781, - 0xbf60a54a, 0x9182ae6d, - 0xbf8c0de3, 0x91695663, 0xbfb7806c, 0x91500f67, 0xbfe2fcdf, 0x9136d97d, - 0xc00e8336, 0x911db4a9, - 0xc03a1368, 0x9104a0ee, 0xc065ad70, 0x90eb9e50, 0xc0915148, 0x90d2acd4, - 0xc0bcfee7, 0x90b9cc7d, - 0xc0e8b648, 0x90a0fd4e, 0xc1147764, 0x90883f4d, 0xc1404233, 0x906f927c, - 0xc16c16b0, 0x9056f6df, - 0xc197f4d4, 0x903e6c7b, 0xc1c3dc97, 0x9025f352, 0xc1efcdf3, 0x900d8b69, - 0xc21bc8e1, 0x8ff534c4, - 0xc247cd5a, 0x8fdcef66, 0xc273db58, 0x8fc4bb53, 0xc29ff2d4, 0x8fac988f, - 0xc2cc13c7, 0x8f94871d, - 0xc2f83e2a, 0x8f7c8701, 0xc32471f7, 0x8f649840, 0xc350af26, 0x8f4cbadb, - 0xc37cf5b0, 0x8f34eed8, - 0xc3a94590, 0x8f1d343a, 0xc3d59ebe, 0x8f058b04, 0xc4020133, 0x8eedf33b, - 0xc42e6ce8, 0x8ed66ce1, - 0xc45ae1d7, 0x8ebef7fb, 0xc4875ff9, 0x8ea7948c, 0xc4b3e746, 0x8e904298, - 0xc4e077b8, 0x8e790222, - 0xc50d1149, 0x8e61d32e, 0xc539b3f1, 0x8e4ab5bf, 0xc5665fa9, 0x8e33a9da, - 0xc593146a, 0x8e1caf80, - 0xc5bfd22e, 0x8e05c6b7, 0xc5ec98ee, 0x8deeef82, 0xc61968a2, 0x8dd829e4, - 0xc6464144, 0x8dc175e0, - 0xc67322ce, 0x8daad37b, 0xc6a00d37, 0x8d9442b8, 0xc6cd0079, 0x8d7dc399, - 0xc6f9fc8d, 0x8d675623, - 0xc727016d, 0x8d50fa59, 0xc7540f11, 0x8d3ab03f, 0xc7812572, 0x8d2477d8, - 0xc7ae4489, 0x8d0e5127, - 0xc7db6c50, 0x8cf83c30, 0xc8089cbf, 0x8ce238f6, 0xc835d5d0, 0x8ccc477d, - 0xc863177b, 0x8cb667c8, - 0xc89061ba, 0x8ca099da, 0xc8bdb485, 0x8c8addb7, 0xc8eb0fd6, 0x8c753362, - 0xc91873a5, 0x8c5f9ade, - 0xc945dfec, 0x8c4a142f, 0xc97354a4, 0x8c349f58, 0xc9a0d1c5, 0x8c1f3c5d, - 0xc9ce5748, 0x8c09eb40, - 0xc9fbe527, 0x8bf4ac05, 0xca297b5a, 0x8bdf7eb0, 0xca5719db, 0x8bca6343, - 0xca84c0a3, 0x8bb559c1, - 0xcab26fa9, 0x8ba0622f, 0xcae026e8, 0x8b8b7c8f, 0xcb0de658, 0x8b76a8e4, - 0xcb3badf3, 0x8b61e733, - 0xcb697db0, 0x8b4d377c, 0xcb97558a, 0x8b3899c6, 0xcbc53579, 0x8b240e11, - 0xcbf31d75, 0x8b0f9462, - 0xcc210d79, 0x8afb2cbb, 0xcc4f057c, 0x8ae6d720, 0xcc7d0578, 0x8ad29394, - 0xccab0d65, 0x8abe6219, - 0xccd91d3d, 0x8aaa42b4, 0xcd0734f9, 0x8a963567, 0xcd355491, 0x8a823a36, - 0xcd637bfe, 0x8a6e5123, - 0xcd91ab39, 0x8a5a7a31, 0xcdbfe23a, 0x8a46b564, 0xcdee20fc, 0x8a3302be, - 0xce1c6777, 0x8a1f6243, - 0xce4ab5a2, 0x8a0bd3f5, 0xce790b79, 0x89f857d8, 0xcea768f2, 0x89e4edef, - 0xced5ce08, 0x89d1963c, - 0xcf043ab3, 0x89be50c3, 0xcf32aeeb, 0x89ab1d87, 0xcf612aaa, 0x8997fc8a, - 0xcf8fade9, 0x8984edcf, - 0xcfbe389f, 0x8971f15a, 0xcfeccac7, 0x895f072e, 0xd01b6459, 0x894c2f4c, - 0xd04a054e, 0x893969b9, - 0xd078ad9e, 0x8926b677, 0xd0a75d42, 0x89141589, 0xd0d61434, 0x890186f2, - 0xd104d26b, 0x88ef0ab4, - 0xd13397e2, 0x88dca0d3, 0xd1626490, 0x88ca4951, 0xd191386e, 0x88b80432, - 0xd1c01375, 0x88a5d177, - 0xd1eef59e, 0x8893b125, 0xd21ddee2, 0x8881a33d, 0xd24ccf39, 0x886fa7c2, - 0xd27bc69c, 0x885dbeb8, - 0xd2aac504, 0x884be821, 0xd2d9ca6a, 0x883a23ff, 0xd308d6c7, 0x88287256, - 0xd337ea12, 0x8816d327, - 0xd3670446, 0x88054677, 0xd396255a, 0x87f3cc48, 0xd3c54d47, 0x87e2649b, - 0xd3f47c06, 0x87d10f75, - 0xd423b191, 0x87bfccd7, 0xd452eddf, 0x87ae9cc5, 0xd48230e9, 0x879d7f41, - 0xd4b17aa8, 0x878c744d, - 0xd4e0cb15, 0x877b7bec, 0xd5102228, 0x876a9621, 0xd53f7fda, 0x8759c2ef, - 0xd56ee424, 0x87490258, - 0xd59e4eff, 0x8738545e, 0xd5cdc062, 0x8727b905, 0xd5fd3848, 0x8717304e, - 0xd62cb6a8, 0x8706ba3d, - 0xd65c3b7b, 0x86f656d3, 0xd68bc6ba, 0x86e60614, 0xd6bb585e, 0x86d5c802, - 0xd6eaf05f, 0x86c59c9f, - 0xd71a8eb5, 0x86b583ee, 0xd74a335b, 0x86a57df2, 0xd779de47, 0x86958aac, - 0xd7a98f73, 0x8685aa20, - 0xd7d946d8, 0x8675dc4f, 0xd809046e, 0x8666213c, 0xd838c82d, 0x865678eb, - 0xd868920f, 0x8646e35c, - 0xd898620c, 0x86376092, 0xd8c8381d, 0x8627f091, 0xd8f81439, 0x86189359, - 0xd927f65b, 0x860948ef, - 0xd957de7a, 0x85fa1153, 0xd987cc90, 0x85eaec88, 0xd9b7c094, 0x85dbda91, - 0xd9e7ba7f, 0x85ccdb70, - 0xda17ba4a, 0x85bdef28, 0xda47bfee, 0x85af15b9, 0xda77cb63, 0x85a04f28, - 0xdaa7dca1, 0x85919b76, - 0xdad7f3a2, 0x8582faa5, 0xdb08105e, 0x85746cb8, 0xdb3832cd, 0x8565f1b0, - 0xdb685ae9, 0x85578991, - 0xdb9888a8, 0x8549345c, 0xdbc8bc06, 0x853af214, 0xdbf8f4f8, 0x852cc2bb, - 0xdc293379, 0x851ea652, - 0xdc597781, 0x85109cdd, 0xdc89c109, 0x8502a65c, 0xdcba1008, 0x84f4c2d4, - 0xdcea6478, 0x84e6f244, - 0xdd1abe51, 0x84d934b1, 0xdd4b1d8c, 0x84cb8a1b, 0xdd7b8220, 0x84bdf286, - 0xddabec08, 0x84b06df2, - 0xdddc5b3b, 0x84a2fc62, 0xde0ccfb1, 0x84959dd9, 0xde3d4964, 0x84885258, - 0xde6dc84b, 0x847b19e1, - 0xde9e4c60, 0x846df477, 0xdeced59b, 0x8460e21a, 0xdeff63f4, 0x8453e2cf, - 0xdf2ff764, 0x8446f695, - 0xdf608fe4, 0x843a1d70, 0xdf912d6b, 0x842d5762, 0xdfc1cff3, 0x8420a46c, - 0xdff27773, 0x84140490, - 0xe02323e5, 0x840777d0, 0xe053d541, 0x83fafe2e, 0xe0848b7f, 0x83ee97ad, - 0xe0b54698, 0x83e2444d, - 0xe0e60685, 0x83d60412, 0xe116cb3d, 0x83c9d6fc, 0xe14794ba, 0x83bdbd0e, - 0xe17862f3, 0x83b1b649, - 0xe1a935e2, 0x83a5c2b0, 0xe1da0d7e, 0x8399e244, 0xe20ae9c1, 0x838e1507, - 0xe23bcaa2, 0x83825afb, - 0xe26cb01b, 0x8376b422, 0xe29d9a23, 0x836b207d, 0xe2ce88b3, 0x835fa00f, - 0xe2ff7bc3, 0x835432d8, - 0xe330734d, 0x8348d8dc, 0xe3616f48, 0x833d921b, 0xe3926fad, 0x83325e97, - 0xe3c37474, 0x83273e52, - 0xe3f47d96, 0x831c314e, 0xe4258b0a, 0x8311378d, 0xe4569ccb, 0x83065110, - 0xe487b2d0, 0x82fb7dd8, - 0xe4b8cd11, 0x82f0bde8, 0xe4e9eb87, 0x82e61141, 0xe51b0e2a, 0x82db77e5, - 0xe54c34f3, 0x82d0f1d5, - 0xe57d5fda, 0x82c67f14, 0xe5ae8ed8, 0x82bc1fa2, 0xe5dfc1e5, 0x82b1d381, - 0xe610f8f9, 0x82a79ab3, - 0xe642340d, 0x829d753a, 0xe6737319, 0x82936317, 0xe6a4b616, 0x8289644b, - 0xe6d5fcfc, 0x827f78d8, - 0xe70747c4, 0x8275a0c0, 0xe7389665, 0x826bdc04, 0xe769e8d8, 0x82622aa6, - 0xe79b3f16, 0x82588ca7, - 0xe7cc9917, 0x824f0208, 0xe7fdf6d4, 0x82458acc, 0xe82f5844, 0x823c26f3, - 0xe860bd61, 0x8232d67f, - 0xe8922622, 0x82299971, 0xe8c39280, 0x82206fcc, 0xe8f50273, 0x82175990, - 0xe92675f4, 0x820e56be, - 0xe957ecfb, 0x82056758, 0xe9896781, 0x81fc8b60, 0xe9bae57d, 0x81f3c2d7, - 0xe9ec66e8, 0x81eb0dbe, - 0xea1debbb, 0x81e26c16, 0xea4f73ee, 0x81d9dde1, 0xea80ff7a, 0x81d16321, - 0xeab28e56, 0x81c8fbd6, - 0xeae4207a, 0x81c0a801, 0xeb15b5e1, 0x81b867a5, 0xeb474e81, 0x81b03ac2, - 0xeb78ea52, 0x81a82159, - 0xebaa894f, 0x81a01b6d, 0xebdc2b6e, 0x819828fd, 0xec0dd0a8, 0x81904a0c, - 0xec3f78f6, 0x81887e9a, - 0xec71244f, 0x8180c6a9, 0xeca2d2ad, 0x8179223a, 0xecd48407, 0x8171914e, - 0xed063856, 0x816a13e6, - 0xed37ef91, 0x8162aa04, 0xed69a9b3, 0x815b53a8, 0xed9b66b2, 0x815410d4, - 0xedcd2687, 0x814ce188, - 0xedfee92b, 0x8145c5c7, 0xee30ae96, 0x813ebd90, 0xee6276bf, 0x8137c8e6, - 0xee9441a0, 0x8130e7c9, - 0xeec60f31, 0x812a1a3a, 0xeef7df6a, 0x8123603a, 0xef29b243, 0x811cb9ca, - 0xef5b87b5, 0x811626ec, - 0xef8d5fb8, 0x810fa7a0, 0xefbf3a45, 0x81093be8, 0xeff11753, 0x8102e3c4, - 0xf022f6da, 0x80fc9f35, - 0xf054d8d5, 0x80f66e3c, 0xf086bd39, 0x80f050db, 0xf0b8a401, 0x80ea4712, - 0xf0ea8d24, 0x80e450e2, - 0xf11c789a, 0x80de6e4c, 0xf14e665c, 0x80d89f51, 0xf1805662, 0x80d2e3f2, - 0xf1b248a5, 0x80cd3c2f, - 0xf1e43d1c, 0x80c7a80a, 0xf21633c0, 0x80c22784, 0xf2482c8a, 0x80bcba9d, - 0xf27a2771, 0x80b76156, - 0xf2ac246e, 0x80b21baf, 0xf2de2379, 0x80ace9ab, 0xf310248a, 0x80a7cb49, - 0xf342279b, 0x80a2c08b, - 0xf3742ca2, 0x809dc971, 0xf3a63398, 0x8098e5fb, 0xf3d83c77, 0x8094162c, - 0xf40a4735, 0x808f5a02, - 0xf43c53cb, 0x808ab180, 0xf46e6231, 0x80861ca6, 0xf4a07261, 0x80819b74, - 0xf4d28451, 0x807d2dec, - 0xf50497fb, 0x8078d40d, 0xf536ad56, 0x80748dd9, 0xf568c45b, 0x80705b50, - 0xf59add02, 0x806c3c74, - 0xf5ccf743, 0x80683143, 0xf5ff1318, 0x806439c0, 0xf6313077, 0x806055eb, - 0xf6634f59, 0x805c85c4, - 0xf6956fb7, 0x8058c94c, 0xf6c79188, 0x80552084, 0xf6f9b4c6, 0x80518b6b, - 0xf72bd967, 0x804e0a04, - 0xf75dff66, 0x804a9c4d, 0xf79026b9, 0x80474248, 0xf7c24f59, 0x8043fbf6, - 0xf7f4793e, 0x8040c956, - 0xf826a462, 0x803daa6a, 0xf858d0bb, 0x803a9f31, 0xf88afe42, 0x8037a7ac, - 0xf8bd2cef, 0x8034c3dd, - 0xf8ef5cbb, 0x8031f3c2, 0xf9218d9e, 0x802f375d, 0xf953bf91, 0x802c8ead, - 0xf985f28a, 0x8029f9b4, - 0xf9b82684, 0x80277872, 0xf9ea5b75, 0x80250ae7, 0xfa1c9157, 0x8022b114, - 0xfa4ec821, 0x80206af8, - 0xfa80ffcb, 0x801e3895, 0xfab3384f, 0x801c19ea, 0xfae571a4, 0x801a0ef8, - 0xfb17abc2, 0x801817bf, - 0xfb49e6a3, 0x80163440, 0xfb7c223d, 0x8014647b, 0xfbae5e89, 0x8012a86f, - 0xfbe09b80, 0x8011001f, - 0xfc12d91a, 0x800f6b88, 0xfc45174e, 0x800deaad, 0xfc775616, 0x800c7d8c, - 0xfca9956a, 0x800b2427, - 0xfcdbd541, 0x8009de7e, 0xfd0e1594, 0x8008ac90, 0xfd40565c, 0x80078e5e, - 0xfd729790, 0x800683e8, - 0xfda4d929, 0x80058d2f, 0xfdd71b1e, 0x8004aa32, 0xfe095d69, 0x8003daf1, - 0xfe3ba002, 0x80031f6d, - 0xfe6de2e0, 0x800277a6, 0xfea025fd, 0x8001e39b, 0xfed2694f, 0x8001634e, - 0xff04acd0, 0x8000f6bd, - 0xff36f078, 0x80009dea, 0xff69343f, 0x800058d4, 0xff9b781d, 0x8000277a, - 0xffcdbc0b, 0x800009df, - -}; - - -/* -* @brief Q15 Twiddle factors Table -*/ - -/** -* \par -* Example code for Q15 Twiddle factors Generation:: -* \par -*
for(i = 0; i< 3N/4; i++)    
-* {    
-*	twiddleCoefQ15[2*i]= cos(i * 2*PI/(float)N);    
-*	twiddleCoefQ15[2*i+1]= sin(i * 2*PI/(float)N);    
-* } 
-* \par -* where N = 4096 and PI = 3.14159265358979 -* \par -* Cos and Sin values are interleaved fashion -* \par -* Convert Floating point to Q15(Fixed point 1.15): -* round(twiddleCoefQ15(i) * pow(2, 15)) -* -*/ - -const q15_t ALIGN4 twiddleCoefQ15[6144] = { - - 0x7fff, 0x0, 0x7fff, 0x32, 0x7fff, 0x65, 0x7fff, 0x97, - 0x7fff, 0xc9, 0x7fff, 0xfb, 0x7fff, 0x12e, 0x7ffe, 0x160, - 0x7ffe, 0x192, 0x7ffd, 0x1c4, 0x7ffc, 0x1f7, 0x7ffb, 0x229, - 0x7ffa, 0x25b, 0x7ff9, 0x28d, 0x7ff8, 0x2c0, 0x7ff7, 0x2f2, - 0x7ff6, 0x324, 0x7ff5, 0x356, 0x7ff4, 0x389, 0x7ff2, 0x3bb, - 0x7ff1, 0x3ed, 0x7fef, 0x41f, 0x7fed, 0x452, 0x7fec, 0x484, - 0x7fea, 0x4b6, 0x7fe8, 0x4e8, 0x7fe6, 0x51b, 0x7fe4, 0x54d, - 0x7fe2, 0x57f, 0x7fe0, 0x5b1, 0x7fdd, 0x5e3, 0x7fdb, 0x616, - 0x7fd9, 0x648, 0x7fd6, 0x67a, 0x7fd3, 0x6ac, 0x7fd1, 0x6de, - 0x7fce, 0x711, 0x7fcb, 0x743, 0x7fc8, 0x775, 0x7fc5, 0x7a7, - 0x7fc2, 0x7d9, 0x7fbf, 0x80c, 0x7fbc, 0x83e, 0x7fb9, 0x870, - 0x7fb5, 0x8a2, 0x7fb2, 0x8d4, 0x7fae, 0x906, 0x7fab, 0x938, - 0x7fa7, 0x96b, 0x7fa3, 0x99d, 0x7fa0, 0x9cf, 0x7f9c, 0xa01, - 0x7f98, 0xa33, 0x7f94, 0xa65, 0x7f90, 0xa97, 0x7f8b, 0xac9, - 0x7f87, 0xafb, 0x7f83, 0xb2d, 0x7f7e, 0xb60, 0x7f7a, 0xb92, - 0x7f75, 0xbc4, 0x7f71, 0xbf6, 0x7f6c, 0xc28, 0x7f67, 0xc5a, - 0x7f62, 0xc8c, 0x7f5d, 0xcbe, 0x7f58, 0xcf0, 0x7f53, 0xd22, - 0x7f4e, 0xd54, 0x7f49, 0xd86, 0x7f43, 0xdb8, 0x7f3e, 0xdea, - 0x7f38, 0xe1c, 0x7f33, 0xe4e, 0x7f2d, 0xe80, 0x7f27, 0xeb2, - 0x7f22, 0xee4, 0x7f1c, 0xf15, 0x7f16, 0xf47, 0x7f10, 0xf79, - 0x7f0a, 0xfab, 0x7f03, 0xfdd, 0x7efd, 0x100f, 0x7ef7, 0x1041, - 0x7ef0, 0x1073, 0x7eea, 0x10a4, 0x7ee3, 0x10d6, 0x7edd, 0x1108, - 0x7ed6, 0x113a, 0x7ecf, 0x116c, 0x7ec8, 0x119e, 0x7ec1, 0x11cf, - 0x7eba, 0x1201, 0x7eb3, 0x1233, 0x7eac, 0x1265, 0x7ea5, 0x1296, - 0x7e9d, 0x12c8, 0x7e96, 0x12fa, 0x7e8e, 0x132b, 0x7e87, 0x135d, - 0x7e7f, 0x138f, 0x7e78, 0x13c1, 0x7e70, 0x13f2, 0x7e68, 0x1424, - 0x7e60, 0x1455, 0x7e58, 0x1487, 0x7e50, 0x14b9, 0x7e48, 0x14ea, - 0x7e3f, 0x151c, 0x7e37, 0x154d, 0x7e2f, 0x157f, 0x7e26, 0x15b1, - 0x7e1e, 0x15e2, 0x7e15, 0x1614, 0x7e0c, 0x1645, 0x7e03, 0x1677, - 0x7dfb, 0x16a8, 0x7df2, 0x16da, 0x7de9, 0x170b, 0x7de0, 0x173c, - 0x7dd6, 0x176e, 0x7dcd, 0x179f, 0x7dc4, 0x17d1, 0x7dba, 0x1802, - 0x7db1, 0x1833, 0x7da7, 0x1865, 0x7d9e, 0x1896, 0x7d94, 0x18c7, - 0x7d8a, 0x18f9, 0x7d81, 0x192a, 0x7d77, 0x195b, 0x7d6d, 0x198d, - 0x7d63, 0x19be, 0x7d58, 0x19ef, 0x7d4e, 0x1a20, 0x7d44, 0x1a51, - 0x7d3a, 0x1a83, 0x7d2f, 0x1ab4, 0x7d25, 0x1ae5, 0x7d1a, 0x1b16, - 0x7d0f, 0x1b47, 0x7d05, 0x1b78, 0x7cfa, 0x1ba9, 0x7cef, 0x1bda, - 0x7ce4, 0x1c0c, 0x7cd9, 0x1c3d, 0x7cce, 0x1c6e, 0x7cc2, 0x1c9f, - 0x7cb7, 0x1cd0, 0x7cac, 0x1d01, 0x7ca0, 0x1d31, 0x7c95, 0x1d62, - 0x7c89, 0x1d93, 0x7c7e, 0x1dc4, 0x7c72, 0x1df5, 0x7c66, 0x1e26, - 0x7c5a, 0x1e57, 0x7c4e, 0x1e88, 0x7c42, 0x1eb8, 0x7c36, 0x1ee9, - 0x7c2a, 0x1f1a, 0x7c1e, 0x1f4b, 0x7c11, 0x1f7b, 0x7c05, 0x1fac, - 0x7bf9, 0x1fdd, 0x7bec, 0x200e, 0x7bdf, 0x203e, 0x7bd3, 0x206f, - 0x7bc6, 0x209f, 0x7bb9, 0x20d0, 0x7bac, 0x2101, 0x7b9f, 0x2131, - 0x7b92, 0x2162, 0x7b85, 0x2192, 0x7b78, 0x21c3, 0x7b6a, 0x21f3, - 0x7b5d, 0x2224, 0x7b50, 0x2254, 0x7b42, 0x2284, 0x7b34, 0x22b5, - 0x7b27, 0x22e5, 0x7b19, 0x2316, 0x7b0b, 0x2346, 0x7afd, 0x2376, - 0x7aef, 0x23a7, 0x7ae1, 0x23d7, 0x7ad3, 0x2407, 0x7ac5, 0x2437, - 0x7ab7, 0x2467, 0x7aa8, 0x2498, 0x7a9a, 0x24c8, 0x7a8c, 0x24f8, - 0x7a7d, 0x2528, 0x7a6e, 0x2558, 0x7a60, 0x2588, 0x7a51, 0x25b8, - 0x7a42, 0x25e8, 0x7a33, 0x2618, 0x7a24, 0x2648, 0x7a15, 0x2678, - 0x7a06, 0x26a8, 0x79f7, 0x26d8, 0x79e7, 0x2708, 0x79d8, 0x2738, - 0x79c9, 0x2768, 0x79b9, 0x2797, 0x79aa, 0x27c7, 0x799a, 0x27f7, - 0x798a, 0x2827, 0x797a, 0x2856, 0x796a, 0x2886, 0x795b, 0x28b6, - 0x794a, 0x28e5, 0x793a, 0x2915, 0x792a, 0x2945, 0x791a, 0x2974, - 0x790a, 0x29a4, 0x78f9, 0x29d3, 0x78e9, 0x2a03, 0x78d8, 0x2a32, - 0x78c8, 0x2a62, 0x78b7, 0x2a91, 0x78a6, 0x2ac1, 0x7895, 0x2af0, - 0x7885, 0x2b1f, 0x7874, 0x2b4f, 0x7863, 0x2b7e, 0x7851, 0x2bad, - 0x7840, 0x2bdc, 0x782f, 0x2c0c, 0x781e, 0x2c3b, 0x780c, 0x2c6a, - 0x77fb, 0x2c99, 0x77e9, 0x2cc8, 0x77d8, 0x2cf7, 0x77c6, 0x2d26, - 0x77b4, 0x2d55, 0x77a2, 0x2d84, 0x7790, 0x2db3, 0x777e, 0x2de2, - 0x776c, 0x2e11, 0x775a, 0x2e40, 0x7748, 0x2e6f, 0x7736, 0x2e9e, - 0x7723, 0x2ecc, 0x7711, 0x2efb, 0x76fe, 0x2f2a, 0x76ec, 0x2f59, - 0x76d9, 0x2f87, 0x76c7, 0x2fb6, 0x76b4, 0x2fe5, 0x76a1, 0x3013, - 0x768e, 0x3042, 0x767b, 0x3070, 0x7668, 0x309f, 0x7655, 0x30cd, - 0x7642, 0x30fc, 0x762e, 0x312a, 0x761b, 0x3159, 0x7608, 0x3187, - 0x75f4, 0x31b5, 0x75e1, 0x31e4, 0x75cd, 0x3212, 0x75b9, 0x3240, - 0x75a6, 0x326e, 0x7592, 0x329d, 0x757e, 0x32cb, 0x756a, 0x32f9, - 0x7556, 0x3327, 0x7542, 0x3355, 0x752d, 0x3383, 0x7519, 0x33b1, - 0x7505, 0x33df, 0x74f0, 0x340d, 0x74dc, 0x343b, 0x74c7, 0x3469, - 0x74b3, 0x3497, 0x749e, 0x34c4, 0x7489, 0x34f2, 0x7475, 0x3520, - 0x7460, 0x354e, 0x744b, 0x357b, 0x7436, 0x35a9, 0x7421, 0x35d7, - 0x740b, 0x3604, 0x73f6, 0x3632, 0x73e1, 0x365f, 0x73cb, 0x368d, - 0x73b6, 0x36ba, 0x73a0, 0x36e8, 0x738b, 0x3715, 0x7375, 0x3742, - 0x735f, 0x3770, 0x734a, 0x379d, 0x7334, 0x37ca, 0x731e, 0x37f7, - 0x7308, 0x3825, 0x72f2, 0x3852, 0x72dc, 0x387f, 0x72c5, 0x38ac, - 0x72af, 0x38d9, 0x7299, 0x3906, 0x7282, 0x3933, 0x726c, 0x3960, - 0x7255, 0x398d, 0x723f, 0x39ba, 0x7228, 0x39e7, 0x7211, 0x3a13, - 0x71fa, 0x3a40, 0x71e3, 0x3a6d, 0x71cc, 0x3a9a, 0x71b5, 0x3ac6, - 0x719e, 0x3af3, 0x7187, 0x3b20, 0x7170, 0x3b4c, 0x7158, 0x3b79, - 0x7141, 0x3ba5, 0x712a, 0x3bd2, 0x7112, 0x3bfe, 0x70fa, 0x3c2a, - 0x70e3, 0x3c57, 0x70cb, 0x3c83, 0x70b3, 0x3caf, 0x709b, 0x3cdc, - 0x7083, 0x3d08, 0x706b, 0x3d34, 0x7053, 0x3d60, 0x703b, 0x3d8c, - 0x7023, 0x3db8, 0x700b, 0x3de4, 0x6ff2, 0x3e10, 0x6fda, 0x3e3c, - 0x6fc2, 0x3e68, 0x6fa9, 0x3e94, 0x6f90, 0x3ec0, 0x6f78, 0x3eec, - 0x6f5f, 0x3f17, 0x6f46, 0x3f43, 0x6f2d, 0x3f6f, 0x6f14, 0x3f9a, - 0x6efb, 0x3fc6, 0x6ee2, 0x3ff1, 0x6ec9, 0x401d, 0x6eb0, 0x4048, - 0x6e97, 0x4074, 0x6e7d, 0x409f, 0x6e64, 0x40cb, 0x6e4a, 0x40f6, - 0x6e31, 0x4121, 0x6e17, 0x414d, 0x6dfe, 0x4178, 0x6de4, 0x41a3, - 0x6dca, 0x41ce, 0x6db0, 0x41f9, 0x6d96, 0x4224, 0x6d7c, 0x424f, - 0x6d62, 0x427a, 0x6d48, 0x42a5, 0x6d2e, 0x42d0, 0x6d14, 0x42fb, - 0x6cf9, 0x4326, 0x6cdf, 0x4351, 0x6cc4, 0x437b, 0x6caa, 0x43a6, - 0x6c8f, 0x43d1, 0x6c75, 0x43fb, 0x6c5a, 0x4426, 0x6c3f, 0x4450, - 0x6c24, 0x447b, 0x6c09, 0x44a5, 0x6bee, 0x44d0, 0x6bd3, 0x44fa, - 0x6bb8, 0x4524, 0x6b9d, 0x454f, 0x6b82, 0x4579, 0x6b66, 0x45a3, - 0x6b4b, 0x45cd, 0x6b30, 0x45f7, 0x6b14, 0x4621, 0x6af8, 0x464b, - 0x6add, 0x4675, 0x6ac1, 0x469f, 0x6aa5, 0x46c9, 0x6a89, 0x46f3, - 0x6a6e, 0x471d, 0x6a52, 0x4747, 0x6a36, 0x4770, 0x6a1a, 0x479a, - 0x69fd, 0x47c4, 0x69e1, 0x47ed, 0x69c5, 0x4817, 0x69a9, 0x4840, - 0x698c, 0x486a, 0x6970, 0x4893, 0x6953, 0x48bd, 0x6937, 0x48e6, - 0x691a, 0x490f, 0x68fd, 0x4939, 0x68e0, 0x4962, 0x68c4, 0x498b, - 0x68a7, 0x49b4, 0x688a, 0x49dd, 0x686d, 0x4a06, 0x6850, 0x4a2f, - 0x6832, 0x4a58, 0x6815, 0x4a81, 0x67f8, 0x4aaa, 0x67da, 0x4ad3, - 0x67bd, 0x4afb, 0x67a0, 0x4b24, 0x6782, 0x4b4d, 0x6764, 0x4b75, - 0x6747, 0x4b9e, 0x6729, 0x4bc7, 0x670b, 0x4bef, 0x66ed, 0x4c17, - 0x66d0, 0x4c40, 0x66b2, 0x4c68, 0x6693, 0x4c91, 0x6675, 0x4cb9, - 0x6657, 0x4ce1, 0x6639, 0x4d09, 0x661b, 0x4d31, 0x65fc, 0x4d59, - 0x65de, 0x4d81, 0x65c0, 0x4da9, 0x65a1, 0x4dd1, 0x6582, 0x4df9, - 0x6564, 0x4e21, 0x6545, 0x4e49, 0x6526, 0x4e71, 0x6507, 0x4e98, - 0x64e9, 0x4ec0, 0x64ca, 0x4ee8, 0x64ab, 0x4f0f, 0x648b, 0x4f37, - 0x646c, 0x4f5e, 0x644d, 0x4f85, 0x642e, 0x4fad, 0x640f, 0x4fd4, - 0x63ef, 0x4ffb, 0x63d0, 0x5023, 0x63b0, 0x504a, 0x6391, 0x5071, - 0x6371, 0x5098, 0x6351, 0x50bf, 0x6332, 0x50e6, 0x6312, 0x510d, - 0x62f2, 0x5134, 0x62d2, 0x515b, 0x62b2, 0x5181, 0x6292, 0x51a8, - 0x6272, 0x51cf, 0x6252, 0x51f5, 0x6232, 0x521c, 0x6211, 0x5243, - 0x61f1, 0x5269, 0x61d1, 0x5290, 0x61b0, 0x52b6, 0x6190, 0x52dc, - 0x616f, 0x5303, 0x614e, 0x5329, 0x612e, 0x534f, 0x610d, 0x5375, - 0x60ec, 0x539b, 0x60cb, 0x53c1, 0x60aa, 0x53e7, 0x6089, 0x540d, - 0x6068, 0x5433, 0x6047, 0x5459, 0x6026, 0x547f, 0x6005, 0x54a4, - 0x5fe4, 0x54ca, 0x5fc2, 0x54f0, 0x5fa1, 0x5515, 0x5f80, 0x553b, - 0x5f5e, 0x5560, 0x5f3c, 0x5586, 0x5f1b, 0x55ab, 0x5ef9, 0x55d0, - 0x5ed7, 0x55f6, 0x5eb6, 0x561b, 0x5e94, 0x5640, 0x5e72, 0x5665, - 0x5e50, 0x568a, 0x5e2e, 0x56af, 0x5e0c, 0x56d4, 0x5dea, 0x56f9, - 0x5dc8, 0x571e, 0x5da5, 0x5743, 0x5d83, 0x5767, 0x5d61, 0x578c, - 0x5d3e, 0x57b1, 0x5d1c, 0x57d5, 0x5cf9, 0x57fa, 0x5cd7, 0x581e, - 0x5cb4, 0x5843, 0x5c91, 0x5867, 0x5c6f, 0x588c, 0x5c4c, 0x58b0, - 0x5c29, 0x58d4, 0x5c06, 0x58f8, 0x5be3, 0x591c, 0x5bc0, 0x5940, - 0x5b9d, 0x5964, 0x5b7a, 0x5988, 0x5b57, 0x59ac, 0x5b34, 0x59d0, - 0x5b10, 0x59f4, 0x5aed, 0x5a18, 0x5ac9, 0x5a3b, 0x5aa6, 0x5a5f, - 0x5a82, 0x5a82, 0x5a5f, 0x5aa6, 0x5a3b, 0x5ac9, 0x5a18, 0x5aed, - 0x59f4, 0x5b10, 0x59d0, 0x5b34, 0x59ac, 0x5b57, 0x5988, 0x5b7a, - 0x5964, 0x5b9d, 0x5940, 0x5bc0, 0x591c, 0x5be3, 0x58f8, 0x5c06, - 0x58d4, 0x5c29, 0x58b0, 0x5c4c, 0x588c, 0x5c6f, 0x5867, 0x5c91, - 0x5843, 0x5cb4, 0x581e, 0x5cd7, 0x57fa, 0x5cf9, 0x57d5, 0x5d1c, - 0x57b1, 0x5d3e, 0x578c, 0x5d61, 0x5767, 0x5d83, 0x5743, 0x5da5, - 0x571e, 0x5dc8, 0x56f9, 0x5dea, 0x56d4, 0x5e0c, 0x56af, 0x5e2e, - 0x568a, 0x5e50, 0x5665, 0x5e72, 0x5640, 0x5e94, 0x561b, 0x5eb6, - 0x55f6, 0x5ed7, 0x55d0, 0x5ef9, 0x55ab, 0x5f1b, 0x5586, 0x5f3c, - 0x5560, 0x5f5e, 0x553b, 0x5f80, 0x5515, 0x5fa1, 0x54f0, 0x5fc2, - 0x54ca, 0x5fe4, 0x54a4, 0x6005, 0x547f, 0x6026, 0x5459, 0x6047, - 0x5433, 0x6068, 0x540d, 0x6089, 0x53e7, 0x60aa, 0x53c1, 0x60cb, - 0x539b, 0x60ec, 0x5375, 0x610d, 0x534f, 0x612e, 0x5329, 0x614e, - 0x5303, 0x616f, 0x52dc, 0x6190, 0x52b6, 0x61b0, 0x5290, 0x61d1, - 0x5269, 0x61f1, 0x5243, 0x6211, 0x521c, 0x6232, 0x51f5, 0x6252, - 0x51cf, 0x6272, 0x51a8, 0x6292, 0x5181, 0x62b2, 0x515b, 0x62d2, - 0x5134, 0x62f2, 0x510d, 0x6312, 0x50e6, 0x6332, 0x50bf, 0x6351, - 0x5098, 0x6371, 0x5071, 0x6391, 0x504a, 0x63b0, 0x5023, 0x63d0, - 0x4ffb, 0x63ef, 0x4fd4, 0x640f, 0x4fad, 0x642e, 0x4f85, 0x644d, - 0x4f5e, 0x646c, 0x4f37, 0x648b, 0x4f0f, 0x64ab, 0x4ee8, 0x64ca, - 0x4ec0, 0x64e9, 0x4e98, 0x6507, 0x4e71, 0x6526, 0x4e49, 0x6545, - 0x4e21, 0x6564, 0x4df9, 0x6582, 0x4dd1, 0x65a1, 0x4da9, 0x65c0, - 0x4d81, 0x65de, 0x4d59, 0x65fc, 0x4d31, 0x661b, 0x4d09, 0x6639, - 0x4ce1, 0x6657, 0x4cb9, 0x6675, 0x4c91, 0x6693, 0x4c68, 0x66b2, - 0x4c40, 0x66d0, 0x4c17, 0x66ed, 0x4bef, 0x670b, 0x4bc7, 0x6729, - 0x4b9e, 0x6747, 0x4b75, 0x6764, 0x4b4d, 0x6782, 0x4b24, 0x67a0, - 0x4afb, 0x67bd, 0x4ad3, 0x67da, 0x4aaa, 0x67f8, 0x4a81, 0x6815, - 0x4a58, 0x6832, 0x4a2f, 0x6850, 0x4a06, 0x686d, 0x49dd, 0x688a, - 0x49b4, 0x68a7, 0x498b, 0x68c4, 0x4962, 0x68e0, 0x4939, 0x68fd, - 0x490f, 0x691a, 0x48e6, 0x6937, 0x48bd, 0x6953, 0x4893, 0x6970, - 0x486a, 0x698c, 0x4840, 0x69a9, 0x4817, 0x69c5, 0x47ed, 0x69e1, - 0x47c4, 0x69fd, 0x479a, 0x6a1a, 0x4770, 0x6a36, 0x4747, 0x6a52, - 0x471d, 0x6a6e, 0x46f3, 0x6a89, 0x46c9, 0x6aa5, 0x469f, 0x6ac1, - 0x4675, 0x6add, 0x464b, 0x6af8, 0x4621, 0x6b14, 0x45f7, 0x6b30, - 0x45cd, 0x6b4b, 0x45a3, 0x6b66, 0x4579, 0x6b82, 0x454f, 0x6b9d, - 0x4524, 0x6bb8, 0x44fa, 0x6bd3, 0x44d0, 0x6bee, 0x44a5, 0x6c09, - 0x447b, 0x6c24, 0x4450, 0x6c3f, 0x4426, 0x6c5a, 0x43fb, 0x6c75, - 0x43d1, 0x6c8f, 0x43a6, 0x6caa, 0x437b, 0x6cc4, 0x4351, 0x6cdf, - 0x4326, 0x6cf9, 0x42fb, 0x6d14, 0x42d0, 0x6d2e, 0x42a5, 0x6d48, - 0x427a, 0x6d62, 0x424f, 0x6d7c, 0x4224, 0x6d96, 0x41f9, 0x6db0, - 0x41ce, 0x6dca, 0x41a3, 0x6de4, 0x4178, 0x6dfe, 0x414d, 0x6e17, - 0x4121, 0x6e31, 0x40f6, 0x6e4a, 0x40cb, 0x6e64, 0x409f, 0x6e7d, - 0x4074, 0x6e97, 0x4048, 0x6eb0, 0x401d, 0x6ec9, 0x3ff1, 0x6ee2, - 0x3fc6, 0x6efb, 0x3f9a, 0x6f14, 0x3f6f, 0x6f2d, 0x3f43, 0x6f46, - 0x3f17, 0x6f5f, 0x3eec, 0x6f78, 0x3ec0, 0x6f90, 0x3e94, 0x6fa9, - 0x3e68, 0x6fc2, 0x3e3c, 0x6fda, 0x3e10, 0x6ff2, 0x3de4, 0x700b, - 0x3db8, 0x7023, 0x3d8c, 0x703b, 0x3d60, 0x7053, 0x3d34, 0x706b, - 0x3d08, 0x7083, 0x3cdc, 0x709b, 0x3caf, 0x70b3, 0x3c83, 0x70cb, - 0x3c57, 0x70e3, 0x3c2a, 0x70fa, 0x3bfe, 0x7112, 0x3bd2, 0x712a, - 0x3ba5, 0x7141, 0x3b79, 0x7158, 0x3b4c, 0x7170, 0x3b20, 0x7187, - 0x3af3, 0x719e, 0x3ac6, 0x71b5, 0x3a9a, 0x71cc, 0x3a6d, 0x71e3, - 0x3a40, 0x71fa, 0x3a13, 0x7211, 0x39e7, 0x7228, 0x39ba, 0x723f, - 0x398d, 0x7255, 0x3960, 0x726c, 0x3933, 0x7282, 0x3906, 0x7299, - 0x38d9, 0x72af, 0x38ac, 0x72c5, 0x387f, 0x72dc, 0x3852, 0x72f2, - 0x3825, 0x7308, 0x37f7, 0x731e, 0x37ca, 0x7334, 0x379d, 0x734a, - 0x3770, 0x735f, 0x3742, 0x7375, 0x3715, 0x738b, 0x36e8, 0x73a0, - 0x36ba, 0x73b6, 0x368d, 0x73cb, 0x365f, 0x73e1, 0x3632, 0x73f6, - 0x3604, 0x740b, 0x35d7, 0x7421, 0x35a9, 0x7436, 0x357b, 0x744b, - 0x354e, 0x7460, 0x3520, 0x7475, 0x34f2, 0x7489, 0x34c4, 0x749e, - 0x3497, 0x74b3, 0x3469, 0x74c7, 0x343b, 0x74dc, 0x340d, 0x74f0, - 0x33df, 0x7505, 0x33b1, 0x7519, 0x3383, 0x752d, 0x3355, 0x7542, - 0x3327, 0x7556, 0x32f9, 0x756a, 0x32cb, 0x757e, 0x329d, 0x7592, - 0x326e, 0x75a6, 0x3240, 0x75b9, 0x3212, 0x75cd, 0x31e4, 0x75e1, - 0x31b5, 0x75f4, 0x3187, 0x7608, 0x3159, 0x761b, 0x312a, 0x762e, - 0x30fc, 0x7642, 0x30cd, 0x7655, 0x309f, 0x7668, 0x3070, 0x767b, - 0x3042, 0x768e, 0x3013, 0x76a1, 0x2fe5, 0x76b4, 0x2fb6, 0x76c7, - 0x2f87, 0x76d9, 0x2f59, 0x76ec, 0x2f2a, 0x76fe, 0x2efb, 0x7711, - 0x2ecc, 0x7723, 0x2e9e, 0x7736, 0x2e6f, 0x7748, 0x2e40, 0x775a, - 0x2e11, 0x776c, 0x2de2, 0x777e, 0x2db3, 0x7790, 0x2d84, 0x77a2, - 0x2d55, 0x77b4, 0x2d26, 0x77c6, 0x2cf7, 0x77d8, 0x2cc8, 0x77e9, - 0x2c99, 0x77fb, 0x2c6a, 0x780c, 0x2c3b, 0x781e, 0x2c0c, 0x782f, - 0x2bdc, 0x7840, 0x2bad, 0x7851, 0x2b7e, 0x7863, 0x2b4f, 0x7874, - 0x2b1f, 0x7885, 0x2af0, 0x7895, 0x2ac1, 0x78a6, 0x2a91, 0x78b7, - 0x2a62, 0x78c8, 0x2a32, 0x78d8, 0x2a03, 0x78e9, 0x29d3, 0x78f9, - 0x29a4, 0x790a, 0x2974, 0x791a, 0x2945, 0x792a, 0x2915, 0x793a, - 0x28e5, 0x794a, 0x28b6, 0x795b, 0x2886, 0x796a, 0x2856, 0x797a, - 0x2827, 0x798a, 0x27f7, 0x799a, 0x27c7, 0x79aa, 0x2797, 0x79b9, - 0x2768, 0x79c9, 0x2738, 0x79d8, 0x2708, 0x79e7, 0x26d8, 0x79f7, - 0x26a8, 0x7a06, 0x2678, 0x7a15, 0x2648, 0x7a24, 0x2618, 0x7a33, - 0x25e8, 0x7a42, 0x25b8, 0x7a51, 0x2588, 0x7a60, 0x2558, 0x7a6e, - 0x2528, 0x7a7d, 0x24f8, 0x7a8c, 0x24c8, 0x7a9a, 0x2498, 0x7aa8, - 0x2467, 0x7ab7, 0x2437, 0x7ac5, 0x2407, 0x7ad3, 0x23d7, 0x7ae1, - 0x23a7, 0x7aef, 0x2376, 0x7afd, 0x2346, 0x7b0b, 0x2316, 0x7b19, - 0x22e5, 0x7b27, 0x22b5, 0x7b34, 0x2284, 0x7b42, 0x2254, 0x7b50, - 0x2224, 0x7b5d, 0x21f3, 0x7b6a, 0x21c3, 0x7b78, 0x2192, 0x7b85, - 0x2162, 0x7b92, 0x2131, 0x7b9f, 0x2101, 0x7bac, 0x20d0, 0x7bb9, - 0x209f, 0x7bc6, 0x206f, 0x7bd3, 0x203e, 0x7bdf, 0x200e, 0x7bec, - 0x1fdd, 0x7bf9, 0x1fac, 0x7c05, 0x1f7b, 0x7c11, 0x1f4b, 0x7c1e, - 0x1f1a, 0x7c2a, 0x1ee9, 0x7c36, 0x1eb8, 0x7c42, 0x1e88, 0x7c4e, - 0x1e57, 0x7c5a, 0x1e26, 0x7c66, 0x1df5, 0x7c72, 0x1dc4, 0x7c7e, - 0x1d93, 0x7c89, 0x1d62, 0x7c95, 0x1d31, 0x7ca0, 0x1d01, 0x7cac, - 0x1cd0, 0x7cb7, 0x1c9f, 0x7cc2, 0x1c6e, 0x7cce, 0x1c3d, 0x7cd9, - 0x1c0c, 0x7ce4, 0x1bda, 0x7cef, 0x1ba9, 0x7cfa, 0x1b78, 0x7d05, - 0x1b47, 0x7d0f, 0x1b16, 0x7d1a, 0x1ae5, 0x7d25, 0x1ab4, 0x7d2f, - 0x1a83, 0x7d3a, 0x1a51, 0x7d44, 0x1a20, 0x7d4e, 0x19ef, 0x7d58, - 0x19be, 0x7d63, 0x198d, 0x7d6d, 0x195b, 0x7d77, 0x192a, 0x7d81, - 0x18f9, 0x7d8a, 0x18c7, 0x7d94, 0x1896, 0x7d9e, 0x1865, 0x7da7, - 0x1833, 0x7db1, 0x1802, 0x7dba, 0x17d1, 0x7dc4, 0x179f, 0x7dcd, - 0x176e, 0x7dd6, 0x173c, 0x7de0, 0x170b, 0x7de9, 0x16da, 0x7df2, - 0x16a8, 0x7dfb, 0x1677, 0x7e03, 0x1645, 0x7e0c, 0x1614, 0x7e15, - 0x15e2, 0x7e1e, 0x15b1, 0x7e26, 0x157f, 0x7e2f, 0x154d, 0x7e37, - 0x151c, 0x7e3f, 0x14ea, 0x7e48, 0x14b9, 0x7e50, 0x1487, 0x7e58, - 0x1455, 0x7e60, 0x1424, 0x7e68, 0x13f2, 0x7e70, 0x13c1, 0x7e78, - 0x138f, 0x7e7f, 0x135d, 0x7e87, 0x132b, 0x7e8e, 0x12fa, 0x7e96, - 0x12c8, 0x7e9d, 0x1296, 0x7ea5, 0x1265, 0x7eac, 0x1233, 0x7eb3, - 0x1201, 0x7eba, 0x11cf, 0x7ec1, 0x119e, 0x7ec8, 0x116c, 0x7ecf, - 0x113a, 0x7ed6, 0x1108, 0x7edd, 0x10d6, 0x7ee3, 0x10a4, 0x7eea, - 0x1073, 0x7ef0, 0x1041, 0x7ef7, 0x100f, 0x7efd, 0xfdd, 0x7f03, - 0xfab, 0x7f0a, 0xf79, 0x7f10, 0xf47, 0x7f16, 0xf15, 0x7f1c, - 0xee4, 0x7f22, 0xeb2, 0x7f27, 0xe80, 0x7f2d, 0xe4e, 0x7f33, - 0xe1c, 0x7f38, 0xdea, 0x7f3e, 0xdb8, 0x7f43, 0xd86, 0x7f49, - 0xd54, 0x7f4e, 0xd22, 0x7f53, 0xcf0, 0x7f58, 0xcbe, 0x7f5d, - 0xc8c, 0x7f62, 0xc5a, 0x7f67, 0xc28, 0x7f6c, 0xbf6, 0x7f71, - 0xbc4, 0x7f75, 0xb92, 0x7f7a, 0xb60, 0x7f7e, 0xb2d, 0x7f83, - 0xafb, 0x7f87, 0xac9, 0x7f8b, 0xa97, 0x7f90, 0xa65, 0x7f94, - 0xa33, 0x7f98, 0xa01, 0x7f9c, 0x9cf, 0x7fa0, 0x99d, 0x7fa3, - 0x96b, 0x7fa7, 0x938, 0x7fab, 0x906, 0x7fae, 0x8d4, 0x7fb2, - 0x8a2, 0x7fb5, 0x870, 0x7fb9, 0x83e, 0x7fbc, 0x80c, 0x7fbf, - 0x7d9, 0x7fc2, 0x7a7, 0x7fc5, 0x775, 0x7fc8, 0x743, 0x7fcb, - 0x711, 0x7fce, 0x6de, 0x7fd1, 0x6ac, 0x7fd3, 0x67a, 0x7fd6, - 0x648, 0x7fd9, 0x616, 0x7fdb, 0x5e3, 0x7fdd, 0x5b1, 0x7fe0, - 0x57f, 0x7fe2, 0x54d, 0x7fe4, 0x51b, 0x7fe6, 0x4e8, 0x7fe8, - 0x4b6, 0x7fea, 0x484, 0x7fec, 0x452, 0x7fed, 0x41f, 0x7fef, - 0x3ed, 0x7ff1, 0x3bb, 0x7ff2, 0x389, 0x7ff4, 0x356, 0x7ff5, - 0x324, 0x7ff6, 0x2f2, 0x7ff7, 0x2c0, 0x7ff8, 0x28d, 0x7ff9, - 0x25b, 0x7ffa, 0x229, 0x7ffb, 0x1f7, 0x7ffc, 0x1c4, 0x7ffd, - 0x192, 0x7ffe, 0x160, 0x7ffe, 0x12e, 0x7fff, 0xfb, 0x7fff, - 0xc9, 0x7fff, 0x97, 0x7fff, 0x65, 0x7fff, 0x32, 0x7fff, - 0x0, 0x7fff, 0xffce, 0x7fff, 0xff9b, 0x7fff, 0xff69, 0x7fff, - 0xff37, 0x7fff, 0xff05, 0x7fff, 0xfed2, 0x7fff, 0xfea0, 0x7ffe, - 0xfe6e, 0x7ffe, 0xfe3c, 0x7ffd, 0xfe09, 0x7ffc, 0xfdd7, 0x7ffb, - 0xfda5, 0x7ffa, 0xfd73, 0x7ff9, 0xfd40, 0x7ff8, 0xfd0e, 0x7ff7, - 0xfcdc, 0x7ff6, 0xfcaa, 0x7ff5, 0xfc77, 0x7ff4, 0xfc45, 0x7ff2, - 0xfc13, 0x7ff1, 0xfbe1, 0x7fef, 0xfbae, 0x7fed, 0xfb7c, 0x7fec, - 0xfb4a, 0x7fea, 0xfb18, 0x7fe8, 0xfae5, 0x7fe6, 0xfab3, 0x7fe4, - 0xfa81, 0x7fe2, 0xfa4f, 0x7fe0, 0xfa1d, 0x7fdd, 0xf9ea, 0x7fdb, - 0xf9b8, 0x7fd9, 0xf986, 0x7fd6, 0xf954, 0x7fd3, 0xf922, 0x7fd1, - 0xf8ef, 0x7fce, 0xf8bd, 0x7fcb, 0xf88b, 0x7fc8, 0xf859, 0x7fc5, - 0xf827, 0x7fc2, 0xf7f4, 0x7fbf, 0xf7c2, 0x7fbc, 0xf790, 0x7fb9, - 0xf75e, 0x7fb5, 0xf72c, 0x7fb2, 0xf6fa, 0x7fae, 0xf6c8, 0x7fab, - 0xf695, 0x7fa7, 0xf663, 0x7fa3, 0xf631, 0x7fa0, 0xf5ff, 0x7f9c, - 0xf5cd, 0x7f98, 0xf59b, 0x7f94, 0xf569, 0x7f90, 0xf537, 0x7f8b, - 0xf505, 0x7f87, 0xf4d3, 0x7f83, 0xf4a0, 0x7f7e, 0xf46e, 0x7f7a, - 0xf43c, 0x7f75, 0xf40a, 0x7f71, 0xf3d8, 0x7f6c, 0xf3a6, 0x7f67, - 0xf374, 0x7f62, 0xf342, 0x7f5d, 0xf310, 0x7f58, 0xf2de, 0x7f53, - 0xf2ac, 0x7f4e, 0xf27a, 0x7f49, 0xf248, 0x7f43, 0xf216, 0x7f3e, - 0xf1e4, 0x7f38, 0xf1b2, 0x7f33, 0xf180, 0x7f2d, 0xf14e, 0x7f27, - 0xf11c, 0x7f22, 0xf0eb, 0x7f1c, 0xf0b9, 0x7f16, 0xf087, 0x7f10, - 0xf055, 0x7f0a, 0xf023, 0x7f03, 0xeff1, 0x7efd, 0xefbf, 0x7ef7, - 0xef8d, 0x7ef0, 0xef5c, 0x7eea, 0xef2a, 0x7ee3, 0xeef8, 0x7edd, - 0xeec6, 0x7ed6, 0xee94, 0x7ecf, 0xee62, 0x7ec8, 0xee31, 0x7ec1, - 0xedff, 0x7eba, 0xedcd, 0x7eb3, 0xed9b, 0x7eac, 0xed6a, 0x7ea5, - 0xed38, 0x7e9d, 0xed06, 0x7e96, 0xecd5, 0x7e8e, 0xeca3, 0x7e87, - 0xec71, 0x7e7f, 0xec3f, 0x7e78, 0xec0e, 0x7e70, 0xebdc, 0x7e68, - 0xebab, 0x7e60, 0xeb79, 0x7e58, 0xeb47, 0x7e50, 0xeb16, 0x7e48, - 0xeae4, 0x7e3f, 0xeab3, 0x7e37, 0xea81, 0x7e2f, 0xea4f, 0x7e26, - 0xea1e, 0x7e1e, 0xe9ec, 0x7e15, 0xe9bb, 0x7e0c, 0xe989, 0x7e03, - 0xe958, 0x7dfb, 0xe926, 0x7df2, 0xe8f5, 0x7de9, 0xe8c4, 0x7de0, - 0xe892, 0x7dd6, 0xe861, 0x7dcd, 0xe82f, 0x7dc4, 0xe7fe, 0x7dba, - 0xe7cd, 0x7db1, 0xe79b, 0x7da7, 0xe76a, 0x7d9e, 0xe739, 0x7d94, - 0xe707, 0x7d8a, 0xe6d6, 0x7d81, 0xe6a5, 0x7d77, 0xe673, 0x7d6d, - 0xe642, 0x7d63, 0xe611, 0x7d58, 0xe5e0, 0x7d4e, 0xe5af, 0x7d44, - 0xe57d, 0x7d3a, 0xe54c, 0x7d2f, 0xe51b, 0x7d25, 0xe4ea, 0x7d1a, - 0xe4b9, 0x7d0f, 0xe488, 0x7d05, 0xe457, 0x7cfa, 0xe426, 0x7cef, - 0xe3f4, 0x7ce4, 0xe3c3, 0x7cd9, 0xe392, 0x7cce, 0xe361, 0x7cc2, - 0xe330, 0x7cb7, 0xe2ff, 0x7cac, 0xe2cf, 0x7ca0, 0xe29e, 0x7c95, - 0xe26d, 0x7c89, 0xe23c, 0x7c7e, 0xe20b, 0x7c72, 0xe1da, 0x7c66, - 0xe1a9, 0x7c5a, 0xe178, 0x7c4e, 0xe148, 0x7c42, 0xe117, 0x7c36, - 0xe0e6, 0x7c2a, 0xe0b5, 0x7c1e, 0xe085, 0x7c11, 0xe054, 0x7c05, - 0xe023, 0x7bf9, 0xdff2, 0x7bec, 0xdfc2, 0x7bdf, 0xdf91, 0x7bd3, - 0xdf61, 0x7bc6, 0xdf30, 0x7bb9, 0xdeff, 0x7bac, 0xdecf, 0x7b9f, - 0xde9e, 0x7b92, 0xde6e, 0x7b85, 0xde3d, 0x7b78, 0xde0d, 0x7b6a, - 0xdddc, 0x7b5d, 0xddac, 0x7b50, 0xdd7c, 0x7b42, 0xdd4b, 0x7b34, - 0xdd1b, 0x7b27, 0xdcea, 0x7b19, 0xdcba, 0x7b0b, 0xdc8a, 0x7afd, - 0xdc59, 0x7aef, 0xdc29, 0x7ae1, 0xdbf9, 0x7ad3, 0xdbc9, 0x7ac5, - 0xdb99, 0x7ab7, 0xdb68, 0x7aa8, 0xdb38, 0x7a9a, 0xdb08, 0x7a8c, - 0xdad8, 0x7a7d, 0xdaa8, 0x7a6e, 0xda78, 0x7a60, 0xda48, 0x7a51, - 0xda18, 0x7a42, 0xd9e8, 0x7a33, 0xd9b8, 0x7a24, 0xd988, 0x7a15, - 0xd958, 0x7a06, 0xd928, 0x79f7, 0xd8f8, 0x79e7, 0xd8c8, 0x79d8, - 0xd898, 0x79c9, 0xd869, 0x79b9, 0xd839, 0x79aa, 0xd809, 0x799a, - 0xd7d9, 0x798a, 0xd7aa, 0x797a, 0xd77a, 0x796a, 0xd74a, 0x795b, - 0xd71b, 0x794a, 0xd6eb, 0x793a, 0xd6bb, 0x792a, 0xd68c, 0x791a, - 0xd65c, 0x790a, 0xd62d, 0x78f9, 0xd5fd, 0x78e9, 0xd5ce, 0x78d8, - 0xd59e, 0x78c8, 0xd56f, 0x78b7, 0xd53f, 0x78a6, 0xd510, 0x7895, - 0xd4e1, 0x7885, 0xd4b1, 0x7874, 0xd482, 0x7863, 0xd453, 0x7851, - 0xd424, 0x7840, 0xd3f4, 0x782f, 0xd3c5, 0x781e, 0xd396, 0x780c, - 0xd367, 0x77fb, 0xd338, 0x77e9, 0xd309, 0x77d8, 0xd2da, 0x77c6, - 0xd2ab, 0x77b4, 0xd27c, 0x77a2, 0xd24d, 0x7790, 0xd21e, 0x777e, - 0xd1ef, 0x776c, 0xd1c0, 0x775a, 0xd191, 0x7748, 0xd162, 0x7736, - 0xd134, 0x7723, 0xd105, 0x7711, 0xd0d6, 0x76fe, 0xd0a7, 0x76ec, - 0xd079, 0x76d9, 0xd04a, 0x76c7, 0xd01b, 0x76b4, 0xcfed, 0x76a1, - 0xcfbe, 0x768e, 0xcf90, 0x767b, 0xcf61, 0x7668, 0xcf33, 0x7655, - 0xcf04, 0x7642, 0xced6, 0x762e, 0xcea7, 0x761b, 0xce79, 0x7608, - 0xce4b, 0x75f4, 0xce1c, 0x75e1, 0xcdee, 0x75cd, 0xcdc0, 0x75b9, - 0xcd92, 0x75a6, 0xcd63, 0x7592, 0xcd35, 0x757e, 0xcd07, 0x756a, - 0xccd9, 0x7556, 0xccab, 0x7542, 0xcc7d, 0x752d, 0xcc4f, 0x7519, - 0xcc21, 0x7505, 0xcbf3, 0x74f0, 0xcbc5, 0x74dc, 0xcb97, 0x74c7, - 0xcb69, 0x74b3, 0xcb3c, 0x749e, 0xcb0e, 0x7489, 0xcae0, 0x7475, - 0xcab2, 0x7460, 0xca85, 0x744b, 0xca57, 0x7436, 0xca29, 0x7421, - 0xc9fc, 0x740b, 0xc9ce, 0x73f6, 0xc9a1, 0x73e1, 0xc973, 0x73cb, - 0xc946, 0x73b6, 0xc918, 0x73a0, 0xc8eb, 0x738b, 0xc8be, 0x7375, - 0xc890, 0x735f, 0xc863, 0x734a, 0xc836, 0x7334, 0xc809, 0x731e, - 0xc7db, 0x7308, 0xc7ae, 0x72f2, 0xc781, 0x72dc, 0xc754, 0x72c5, - 0xc727, 0x72af, 0xc6fa, 0x7299, 0xc6cd, 0x7282, 0xc6a0, 0x726c, - 0xc673, 0x7255, 0xc646, 0x723f, 0xc619, 0x7228, 0xc5ed, 0x7211, - 0xc5c0, 0x71fa, 0xc593, 0x71e3, 0xc566, 0x71cc, 0xc53a, 0x71b5, - 0xc50d, 0x719e, 0xc4e0, 0x7187, 0xc4b4, 0x7170, 0xc487, 0x7158, - 0xc45b, 0x7141, 0xc42e, 0x712a, 0xc402, 0x7112, 0xc3d6, 0x70fa, - 0xc3a9, 0x70e3, 0xc37d, 0x70cb, 0xc351, 0x70b3, 0xc324, 0x709b, - 0xc2f8, 0x7083, 0xc2cc, 0x706b, 0xc2a0, 0x7053, 0xc274, 0x703b, - 0xc248, 0x7023, 0xc21c, 0x700b, 0xc1f0, 0x6ff2, 0xc1c4, 0x6fda, - 0xc198, 0x6fc2, 0xc16c, 0x6fa9, 0xc140, 0x6f90, 0xc114, 0x6f78, - 0xc0e9, 0x6f5f, 0xc0bd, 0x6f46, 0xc091, 0x6f2d, 0xc066, 0x6f14, - 0xc03a, 0x6efb, 0xc00f, 0x6ee2, 0xbfe3, 0x6ec9, 0xbfb8, 0x6eb0, - 0xbf8c, 0x6e97, 0xbf61, 0x6e7d, 0xbf35, 0x6e64, 0xbf0a, 0x6e4a, - 0xbedf, 0x6e31, 0xbeb3, 0x6e17, 0xbe88, 0x6dfe, 0xbe5d, 0x6de4, - 0xbe32, 0x6dca, 0xbe07, 0x6db0, 0xbddc, 0x6d96, 0xbdb1, 0x6d7c, - 0xbd86, 0x6d62, 0xbd5b, 0x6d48, 0xbd30, 0x6d2e, 0xbd05, 0x6d14, - 0xbcda, 0x6cf9, 0xbcaf, 0x6cdf, 0xbc85, 0x6cc4, 0xbc5a, 0x6caa, - 0xbc2f, 0x6c8f, 0xbc05, 0x6c75, 0xbbda, 0x6c5a, 0xbbb0, 0x6c3f, - 0xbb85, 0x6c24, 0xbb5b, 0x6c09, 0xbb30, 0x6bee, 0xbb06, 0x6bd3, - 0xbadc, 0x6bb8, 0xbab1, 0x6b9d, 0xba87, 0x6b82, 0xba5d, 0x6b66, - 0xba33, 0x6b4b, 0xba09, 0x6b30, 0xb9df, 0x6b14, 0xb9b5, 0x6af8, - 0xb98b, 0x6add, 0xb961, 0x6ac1, 0xb937, 0x6aa5, 0xb90d, 0x6a89, - 0xb8e3, 0x6a6e, 0xb8b9, 0x6a52, 0xb890, 0x6a36, 0xb866, 0x6a1a, - 0xb83c, 0x69fd, 0xb813, 0x69e1, 0xb7e9, 0x69c5, 0xb7c0, 0x69a9, - 0xb796, 0x698c, 0xb76d, 0x6970, 0xb743, 0x6953, 0xb71a, 0x6937, - 0xb6f1, 0x691a, 0xb6c7, 0x68fd, 0xb69e, 0x68e0, 0xb675, 0x68c4, - 0xb64c, 0x68a7, 0xb623, 0x688a, 0xb5fa, 0x686d, 0xb5d1, 0x6850, - 0xb5a8, 0x6832, 0xb57f, 0x6815, 0xb556, 0x67f8, 0xb52d, 0x67da, - 0xb505, 0x67bd, 0xb4dc, 0x67a0, 0xb4b3, 0x6782, 0xb48b, 0x6764, - 0xb462, 0x6747, 0xb439, 0x6729, 0xb411, 0x670b, 0xb3e9, 0x66ed, - 0xb3c0, 0x66d0, 0xb398, 0x66b2, 0xb36f, 0x6693, 0xb347, 0x6675, - 0xb31f, 0x6657, 0xb2f7, 0x6639, 0xb2cf, 0x661b, 0xb2a7, 0x65fc, - 0xb27f, 0x65de, 0xb257, 0x65c0, 0xb22f, 0x65a1, 0xb207, 0x6582, - 0xb1df, 0x6564, 0xb1b7, 0x6545, 0xb18f, 0x6526, 0xb168, 0x6507, - 0xb140, 0x64e9, 0xb118, 0x64ca, 0xb0f1, 0x64ab, 0xb0c9, 0x648b, - 0xb0a2, 0x646c, 0xb07b, 0x644d, 0xb053, 0x642e, 0xb02c, 0x640f, - 0xb005, 0x63ef, 0xafdd, 0x63d0, 0xafb6, 0x63b0, 0xaf8f, 0x6391, - 0xaf68, 0x6371, 0xaf41, 0x6351, 0xaf1a, 0x6332, 0xaef3, 0x6312, - 0xaecc, 0x62f2, 0xaea5, 0x62d2, 0xae7f, 0x62b2, 0xae58, 0x6292, - 0xae31, 0x6272, 0xae0b, 0x6252, 0xade4, 0x6232, 0xadbd, 0x6211, - 0xad97, 0x61f1, 0xad70, 0x61d1, 0xad4a, 0x61b0, 0xad24, 0x6190, - 0xacfd, 0x616f, 0xacd7, 0x614e, 0xacb1, 0x612e, 0xac8b, 0x610d, - 0xac65, 0x60ec, 0xac3f, 0x60cb, 0xac19, 0x60aa, 0xabf3, 0x6089, - 0xabcd, 0x6068, 0xaba7, 0x6047, 0xab81, 0x6026, 0xab5c, 0x6005, - 0xab36, 0x5fe4, 0xab10, 0x5fc2, 0xaaeb, 0x5fa1, 0xaac5, 0x5f80, - 0xaaa0, 0x5f5e, 0xaa7a, 0x5f3c, 0xaa55, 0x5f1b, 0xaa30, 0x5ef9, - 0xaa0a, 0x5ed7, 0xa9e5, 0x5eb6, 0xa9c0, 0x5e94, 0xa99b, 0x5e72, - 0xa976, 0x5e50, 0xa951, 0x5e2e, 0xa92c, 0x5e0c, 0xa907, 0x5dea, - 0xa8e2, 0x5dc8, 0xa8bd, 0x5da5, 0xa899, 0x5d83, 0xa874, 0x5d61, - 0xa84f, 0x5d3e, 0xa82b, 0x5d1c, 0xa806, 0x5cf9, 0xa7e2, 0x5cd7, - 0xa7bd, 0x5cb4, 0xa799, 0x5c91, 0xa774, 0x5c6f, 0xa750, 0x5c4c, - 0xa72c, 0x5c29, 0xa708, 0x5c06, 0xa6e4, 0x5be3, 0xa6c0, 0x5bc0, - 0xa69c, 0x5b9d, 0xa678, 0x5b7a, 0xa654, 0x5b57, 0xa630, 0x5b34, - 0xa60c, 0x5b10, 0xa5e8, 0x5aed, 0xa5c5, 0x5ac9, 0xa5a1, 0x5aa6, - 0xa57e, 0x5a82, 0xa55a, 0x5a5f, 0xa537, 0x5a3b, 0xa513, 0x5a18, - 0xa4f0, 0x59f4, 0xa4cc, 0x59d0, 0xa4a9, 0x59ac, 0xa486, 0x5988, - 0xa463, 0x5964, 0xa440, 0x5940, 0xa41d, 0x591c, 0xa3fa, 0x58f8, - 0xa3d7, 0x58d4, 0xa3b4, 0x58b0, 0xa391, 0x588c, 0xa36f, 0x5867, - 0xa34c, 0x5843, 0xa329, 0x581e, 0xa307, 0x57fa, 0xa2e4, 0x57d5, - 0xa2c2, 0x57b1, 0xa29f, 0x578c, 0xa27d, 0x5767, 0xa25b, 0x5743, - 0xa238, 0x571e, 0xa216, 0x56f9, 0xa1f4, 0x56d4, 0xa1d2, 0x56af, - 0xa1b0, 0x568a, 0xa18e, 0x5665, 0xa16c, 0x5640, 0xa14a, 0x561b, - 0xa129, 0x55f6, 0xa107, 0x55d0, 0xa0e5, 0x55ab, 0xa0c4, 0x5586, - 0xa0a2, 0x5560, 0xa080, 0x553b, 0xa05f, 0x5515, 0xa03e, 0x54f0, - 0xa01c, 0x54ca, 0x9ffb, 0x54a4, 0x9fda, 0x547f, 0x9fb9, 0x5459, - 0x9f98, 0x5433, 0x9f77, 0x540d, 0x9f56, 0x53e7, 0x9f35, 0x53c1, - 0x9f14, 0x539b, 0x9ef3, 0x5375, 0x9ed2, 0x534f, 0x9eb2, 0x5329, - 0x9e91, 0x5303, 0x9e70, 0x52dc, 0x9e50, 0x52b6, 0x9e2f, 0x5290, - 0x9e0f, 0x5269, 0x9def, 0x5243, 0x9dce, 0x521c, 0x9dae, 0x51f5, - 0x9d8e, 0x51cf, 0x9d6e, 0x51a8, 0x9d4e, 0x5181, 0x9d2e, 0x515b, - 0x9d0e, 0x5134, 0x9cee, 0x510d, 0x9cce, 0x50e6, 0x9caf, 0x50bf, - 0x9c8f, 0x5098, 0x9c6f, 0x5071, 0x9c50, 0x504a, 0x9c30, 0x5023, - 0x9c11, 0x4ffb, 0x9bf1, 0x4fd4, 0x9bd2, 0x4fad, 0x9bb3, 0x4f85, - 0x9b94, 0x4f5e, 0x9b75, 0x4f37, 0x9b55, 0x4f0f, 0x9b36, 0x4ee8, - 0x9b17, 0x4ec0, 0x9af9, 0x4e98, 0x9ada, 0x4e71, 0x9abb, 0x4e49, - 0x9a9c, 0x4e21, 0x9a7e, 0x4df9, 0x9a5f, 0x4dd1, 0x9a40, 0x4da9, - 0x9a22, 0x4d81, 0x9a04, 0x4d59, 0x99e5, 0x4d31, 0x99c7, 0x4d09, - 0x99a9, 0x4ce1, 0x998b, 0x4cb9, 0x996d, 0x4c91, 0x994e, 0x4c68, - 0x9930, 0x4c40, 0x9913, 0x4c17, 0x98f5, 0x4bef, 0x98d7, 0x4bc7, - 0x98b9, 0x4b9e, 0x989c, 0x4b75, 0x987e, 0x4b4d, 0x9860, 0x4b24, - 0x9843, 0x4afb, 0x9826, 0x4ad3, 0x9808, 0x4aaa, 0x97eb, 0x4a81, - 0x97ce, 0x4a58, 0x97b0, 0x4a2f, 0x9793, 0x4a06, 0x9776, 0x49dd, - 0x9759, 0x49b4, 0x973c, 0x498b, 0x9720, 0x4962, 0x9703, 0x4939, - 0x96e6, 0x490f, 0x96c9, 0x48e6, 0x96ad, 0x48bd, 0x9690, 0x4893, - 0x9674, 0x486a, 0x9657, 0x4840, 0x963b, 0x4817, 0x961f, 0x47ed, - 0x9603, 0x47c4, 0x95e6, 0x479a, 0x95ca, 0x4770, 0x95ae, 0x4747, - 0x9592, 0x471d, 0x9577, 0x46f3, 0x955b, 0x46c9, 0x953f, 0x469f, - 0x9523, 0x4675, 0x9508, 0x464b, 0x94ec, 0x4621, 0x94d0, 0x45f7, - 0x94b5, 0x45cd, 0x949a, 0x45a3, 0x947e, 0x4579, 0x9463, 0x454f, - 0x9448, 0x4524, 0x942d, 0x44fa, 0x9412, 0x44d0, 0x93f7, 0x44a5, - 0x93dc, 0x447b, 0x93c1, 0x4450, 0x93a6, 0x4426, 0x938b, 0x43fb, - 0x9371, 0x43d1, 0x9356, 0x43a6, 0x933c, 0x437b, 0x9321, 0x4351, - 0x9307, 0x4326, 0x92ec, 0x42fb, 0x92d2, 0x42d0, 0x92b8, 0x42a5, - 0x929e, 0x427a, 0x9284, 0x424f, 0x926a, 0x4224, 0x9250, 0x41f9, - 0x9236, 0x41ce, 0x921c, 0x41a3, 0x9202, 0x4178, 0x91e9, 0x414d, - 0x91cf, 0x4121, 0x91b6, 0x40f6, 0x919c, 0x40cb, 0x9183, 0x409f, - 0x9169, 0x4074, 0x9150, 0x4048, 0x9137, 0x401d, 0x911e, 0x3ff1, - 0x9105, 0x3fc6, 0x90ec, 0x3f9a, 0x90d3, 0x3f6f, 0x90ba, 0x3f43, - 0x90a1, 0x3f17, 0x9088, 0x3eec, 0x9070, 0x3ec0, 0x9057, 0x3e94, - 0x903e, 0x3e68, 0x9026, 0x3e3c, 0x900e, 0x3e10, 0x8ff5, 0x3de4, - 0x8fdd, 0x3db8, 0x8fc5, 0x3d8c, 0x8fad, 0x3d60, 0x8f95, 0x3d34, - 0x8f7d, 0x3d08, 0x8f65, 0x3cdc, 0x8f4d, 0x3caf, 0x8f35, 0x3c83, - 0x8f1d, 0x3c57, 0x8f06, 0x3c2a, 0x8eee, 0x3bfe, 0x8ed6, 0x3bd2, - 0x8ebf, 0x3ba5, 0x8ea8, 0x3b79, 0x8e90, 0x3b4c, 0x8e79, 0x3b20, - 0x8e62, 0x3af3, 0x8e4b, 0x3ac6, 0x8e34, 0x3a9a, 0x8e1d, 0x3a6d, - 0x8e06, 0x3a40, 0x8def, 0x3a13, 0x8dd8, 0x39e7, 0x8dc1, 0x39ba, - 0x8dab, 0x398d, 0x8d94, 0x3960, 0x8d7e, 0x3933, 0x8d67, 0x3906, - 0x8d51, 0x38d9, 0x8d3b, 0x38ac, 0x8d24, 0x387f, 0x8d0e, 0x3852, - 0x8cf8, 0x3825, 0x8ce2, 0x37f7, 0x8ccc, 0x37ca, 0x8cb6, 0x379d, - 0x8ca1, 0x3770, 0x8c8b, 0x3742, 0x8c75, 0x3715, 0x8c60, 0x36e8, - 0x8c4a, 0x36ba, 0x8c35, 0x368d, 0x8c1f, 0x365f, 0x8c0a, 0x3632, - 0x8bf5, 0x3604, 0x8bdf, 0x35d7, 0x8bca, 0x35a9, 0x8bb5, 0x357b, - 0x8ba0, 0x354e, 0x8b8b, 0x3520, 0x8b77, 0x34f2, 0x8b62, 0x34c4, - 0x8b4d, 0x3497, 0x8b39, 0x3469, 0x8b24, 0x343b, 0x8b10, 0x340d, - 0x8afb, 0x33df, 0x8ae7, 0x33b1, 0x8ad3, 0x3383, 0x8abe, 0x3355, - 0x8aaa, 0x3327, 0x8a96, 0x32f9, 0x8a82, 0x32cb, 0x8a6e, 0x329d, - 0x8a5a, 0x326e, 0x8a47, 0x3240, 0x8a33, 0x3212, 0x8a1f, 0x31e4, - 0x8a0c, 0x31b5, 0x89f8, 0x3187, 0x89e5, 0x3159, 0x89d2, 0x312a, - 0x89be, 0x30fc, 0x89ab, 0x30cd, 0x8998, 0x309f, 0x8985, 0x3070, - 0x8972, 0x3042, 0x895f, 0x3013, 0x894c, 0x2fe5, 0x8939, 0x2fb6, - 0x8927, 0x2f87, 0x8914, 0x2f59, 0x8902, 0x2f2a, 0x88ef, 0x2efb, - 0x88dd, 0x2ecc, 0x88ca, 0x2e9e, 0x88b8, 0x2e6f, 0x88a6, 0x2e40, - 0x8894, 0x2e11, 0x8882, 0x2de2, 0x8870, 0x2db3, 0x885e, 0x2d84, - 0x884c, 0x2d55, 0x883a, 0x2d26, 0x8828, 0x2cf7, 0x8817, 0x2cc8, - 0x8805, 0x2c99, 0x87f4, 0x2c6a, 0x87e2, 0x2c3b, 0x87d1, 0x2c0c, - 0x87c0, 0x2bdc, 0x87af, 0x2bad, 0x879d, 0x2b7e, 0x878c, 0x2b4f, - 0x877b, 0x2b1f, 0x876b, 0x2af0, 0x875a, 0x2ac1, 0x8749, 0x2a91, - 0x8738, 0x2a62, 0x8728, 0x2a32, 0x8717, 0x2a03, 0x8707, 0x29d3, - 0x86f6, 0x29a4, 0x86e6, 0x2974, 0x86d6, 0x2945, 0x86c6, 0x2915, - 0x86b6, 0x28e5, 0x86a5, 0x28b6, 0x8696, 0x2886, 0x8686, 0x2856, - 0x8676, 0x2827, 0x8666, 0x27f7, 0x8656, 0x27c7, 0x8647, 0x2797, - 0x8637, 0x2768, 0x8628, 0x2738, 0x8619, 0x2708, 0x8609, 0x26d8, - 0x85fa, 0x26a8, 0x85eb, 0x2678, 0x85dc, 0x2648, 0x85cd, 0x2618, - 0x85be, 0x25e8, 0x85af, 0x25b8, 0x85a0, 0x2588, 0x8592, 0x2558, - 0x8583, 0x2528, 0x8574, 0x24f8, 0x8566, 0x24c8, 0x8558, 0x2498, - 0x8549, 0x2467, 0x853b, 0x2437, 0x852d, 0x2407, 0x851f, 0x23d7, - 0x8511, 0x23a7, 0x8503, 0x2376, 0x84f5, 0x2346, 0x84e7, 0x2316, - 0x84d9, 0x22e5, 0x84cc, 0x22b5, 0x84be, 0x2284, 0x84b0, 0x2254, - 0x84a3, 0x2224, 0x8496, 0x21f3, 0x8488, 0x21c3, 0x847b, 0x2192, - 0x846e, 0x2162, 0x8461, 0x2131, 0x8454, 0x2101, 0x8447, 0x20d0, - 0x843a, 0x209f, 0x842d, 0x206f, 0x8421, 0x203e, 0x8414, 0x200e, - 0x8407, 0x1fdd, 0x83fb, 0x1fac, 0x83ef, 0x1f7b, 0x83e2, 0x1f4b, - 0x83d6, 0x1f1a, 0x83ca, 0x1ee9, 0x83be, 0x1eb8, 0x83b2, 0x1e88, - 0x83a6, 0x1e57, 0x839a, 0x1e26, 0x838e, 0x1df5, 0x8382, 0x1dc4, - 0x8377, 0x1d93, 0x836b, 0x1d62, 0x8360, 0x1d31, 0x8354, 0x1d01, - 0x8349, 0x1cd0, 0x833e, 0x1c9f, 0x8332, 0x1c6e, 0x8327, 0x1c3d, - 0x831c, 0x1c0c, 0x8311, 0x1bda, 0x8306, 0x1ba9, 0x82fb, 0x1b78, - 0x82f1, 0x1b47, 0x82e6, 0x1b16, 0x82db, 0x1ae5, 0x82d1, 0x1ab4, - 0x82c6, 0x1a83, 0x82bc, 0x1a51, 0x82b2, 0x1a20, 0x82a8, 0x19ef, - 0x829d, 0x19be, 0x8293, 0x198d, 0x8289, 0x195b, 0x827f, 0x192a, - 0x8276, 0x18f9, 0x826c, 0x18c7, 0x8262, 0x1896, 0x8259, 0x1865, - 0x824f, 0x1833, 0x8246, 0x1802, 0x823c, 0x17d1, 0x8233, 0x179f, - 0x822a, 0x176e, 0x8220, 0x173c, 0x8217, 0x170b, 0x820e, 0x16da, - 0x8205, 0x16a8, 0x81fd, 0x1677, 0x81f4, 0x1645, 0x81eb, 0x1614, - 0x81e2, 0x15e2, 0x81da, 0x15b1, 0x81d1, 0x157f, 0x81c9, 0x154d, - 0x81c1, 0x151c, 0x81b8, 0x14ea, 0x81b0, 0x14b9, 0x81a8, 0x1487, - 0x81a0, 0x1455, 0x8198, 0x1424, 0x8190, 0x13f2, 0x8188, 0x13c1, - 0x8181, 0x138f, 0x8179, 0x135d, 0x8172, 0x132b, 0x816a, 0x12fa, - 0x8163, 0x12c8, 0x815b, 0x1296, 0x8154, 0x1265, 0x814d, 0x1233, - 0x8146, 0x1201, 0x813f, 0x11cf, 0x8138, 0x119e, 0x8131, 0x116c, - 0x812a, 0x113a, 0x8123, 0x1108, 0x811d, 0x10d6, 0x8116, 0x10a4, - 0x8110, 0x1073, 0x8109, 0x1041, 0x8103, 0x100f, 0x80fd, 0xfdd, - 0x80f6, 0xfab, 0x80f0, 0xf79, 0x80ea, 0xf47, 0x80e4, 0xf15, - 0x80de, 0xee4, 0x80d9, 0xeb2, 0x80d3, 0xe80, 0x80cd, 0xe4e, - 0x80c8, 0xe1c, 0x80c2, 0xdea, 0x80bd, 0xdb8, 0x80b7, 0xd86, - 0x80b2, 0xd54, 0x80ad, 0xd22, 0x80a8, 0xcf0, 0x80a3, 0xcbe, - 0x809e, 0xc8c, 0x8099, 0xc5a, 0x8094, 0xc28, 0x808f, 0xbf6, - 0x808b, 0xbc4, 0x8086, 0xb92, 0x8082, 0xb60, 0x807d, 0xb2d, - 0x8079, 0xafb, 0x8075, 0xac9, 0x8070, 0xa97, 0x806c, 0xa65, - 0x8068, 0xa33, 0x8064, 0xa01, 0x8060, 0x9cf, 0x805d, 0x99d, - 0x8059, 0x96b, 0x8055, 0x938, 0x8052, 0x906, 0x804e, 0x8d4, - 0x804b, 0x8a2, 0x8047, 0x870, 0x8044, 0x83e, 0x8041, 0x80c, - 0x803e, 0x7d9, 0x803b, 0x7a7, 0x8038, 0x775, 0x8035, 0x743, - 0x8032, 0x711, 0x802f, 0x6de, 0x802d, 0x6ac, 0x802a, 0x67a, - 0x8027, 0x648, 0x8025, 0x616, 0x8023, 0x5e3, 0x8020, 0x5b1, - 0x801e, 0x57f, 0x801c, 0x54d, 0x801a, 0x51b, 0x8018, 0x4e8, - 0x8016, 0x4b6, 0x8014, 0x484, 0x8013, 0x452, 0x8011, 0x41f, - 0x800f, 0x3ed, 0x800e, 0x3bb, 0x800c, 0x389, 0x800b, 0x356, - 0x800a, 0x324, 0x8009, 0x2f2, 0x8008, 0x2c0, 0x8007, 0x28d, - 0x8006, 0x25b, 0x8005, 0x229, 0x8004, 0x1f7, 0x8003, 0x1c4, - 0x8002, 0x192, 0x8002, 0x160, 0x8001, 0x12e, 0x8001, 0xfb, - 0x8001, 0xc9, 0x8000, 0x97, 0x8000, 0x65, 0x8000, 0x32, - 0x8000, 0x0, 0x8000, 0xffce, 0x8000, 0xff9b, 0x8000, 0xff69, - 0x8001, 0xff37, 0x8001, 0xff05, 0x8001, 0xfed2, 0x8002, 0xfea0, - 0x8002, 0xfe6e, 0x8003, 0xfe3c, 0x8004, 0xfe09, 0x8005, 0xfdd7, - 0x8006, 0xfda5, 0x8007, 0xfd73, 0x8008, 0xfd40, 0x8009, 0xfd0e, - 0x800a, 0xfcdc, 0x800b, 0xfcaa, 0x800c, 0xfc77, 0x800e, 0xfc45, - 0x800f, 0xfc13, 0x8011, 0xfbe1, 0x8013, 0xfbae, 0x8014, 0xfb7c, - 0x8016, 0xfb4a, 0x8018, 0xfb18, 0x801a, 0xfae5, 0x801c, 0xfab3, - 0x801e, 0xfa81, 0x8020, 0xfa4f, 0x8023, 0xfa1d, 0x8025, 0xf9ea, - 0x8027, 0xf9b8, 0x802a, 0xf986, 0x802d, 0xf954, 0x802f, 0xf922, - 0x8032, 0xf8ef, 0x8035, 0xf8bd, 0x8038, 0xf88b, 0x803b, 0xf859, - 0x803e, 0xf827, 0x8041, 0xf7f4, 0x8044, 0xf7c2, 0x8047, 0xf790, - 0x804b, 0xf75e, 0x804e, 0xf72c, 0x8052, 0xf6fa, 0x8055, 0xf6c8, - 0x8059, 0xf695, 0x805d, 0xf663, 0x8060, 0xf631, 0x8064, 0xf5ff, - 0x8068, 0xf5cd, 0x806c, 0xf59b, 0x8070, 0xf569, 0x8075, 0xf537, - 0x8079, 0xf505, 0x807d, 0xf4d3, 0x8082, 0xf4a0, 0x8086, 0xf46e, - 0x808b, 0xf43c, 0x808f, 0xf40a, 0x8094, 0xf3d8, 0x8099, 0xf3a6, - 0x809e, 0xf374, 0x80a3, 0xf342, 0x80a8, 0xf310, 0x80ad, 0xf2de, - 0x80b2, 0xf2ac, 0x80b7, 0xf27a, 0x80bd, 0xf248, 0x80c2, 0xf216, - 0x80c8, 0xf1e4, 0x80cd, 0xf1b2, 0x80d3, 0xf180, 0x80d9, 0xf14e, - 0x80de, 0xf11c, 0x80e4, 0xf0eb, 0x80ea, 0xf0b9, 0x80f0, 0xf087, - 0x80f6, 0xf055, 0x80fd, 0xf023, 0x8103, 0xeff1, 0x8109, 0xefbf, - 0x8110, 0xef8d, 0x8116, 0xef5c, 0x811d, 0xef2a, 0x8123, 0xeef8, - 0x812a, 0xeec6, 0x8131, 0xee94, 0x8138, 0xee62, 0x813f, 0xee31, - 0x8146, 0xedff, 0x814d, 0xedcd, 0x8154, 0xed9b, 0x815b, 0xed6a, - 0x8163, 0xed38, 0x816a, 0xed06, 0x8172, 0xecd5, 0x8179, 0xeca3, - 0x8181, 0xec71, 0x8188, 0xec3f, 0x8190, 0xec0e, 0x8198, 0xebdc, - 0x81a0, 0xebab, 0x81a8, 0xeb79, 0x81b0, 0xeb47, 0x81b8, 0xeb16, - 0x81c1, 0xeae4, 0x81c9, 0xeab3, 0x81d1, 0xea81, 0x81da, 0xea4f, - 0x81e2, 0xea1e, 0x81eb, 0xe9ec, 0x81f4, 0xe9bb, 0x81fd, 0xe989, - 0x8205, 0xe958, 0x820e, 0xe926, 0x8217, 0xe8f5, 0x8220, 0xe8c4, - 0x822a, 0xe892, 0x8233, 0xe861, 0x823c, 0xe82f, 0x8246, 0xe7fe, - 0x824f, 0xe7cd, 0x8259, 0xe79b, 0x8262, 0xe76a, 0x826c, 0xe739, - 0x8276, 0xe707, 0x827f, 0xe6d6, 0x8289, 0xe6a5, 0x8293, 0xe673, - 0x829d, 0xe642, 0x82a8, 0xe611, 0x82b2, 0xe5e0, 0x82bc, 0xe5af, - 0x82c6, 0xe57d, 0x82d1, 0xe54c, 0x82db, 0xe51b, 0x82e6, 0xe4ea, - 0x82f1, 0xe4b9, 0x82fb, 0xe488, 0x8306, 0xe457, 0x8311, 0xe426, - 0x831c, 0xe3f4, 0x8327, 0xe3c3, 0x8332, 0xe392, 0x833e, 0xe361, - 0x8349, 0xe330, 0x8354, 0xe2ff, 0x8360, 0xe2cf, 0x836b, 0xe29e, - 0x8377, 0xe26d, 0x8382, 0xe23c, 0x838e, 0xe20b, 0x839a, 0xe1da, - 0x83a6, 0xe1a9, 0x83b2, 0xe178, 0x83be, 0xe148, 0x83ca, 0xe117, - 0x83d6, 0xe0e6, 0x83e2, 0xe0b5, 0x83ef, 0xe085, 0x83fb, 0xe054, - 0x8407, 0xe023, 0x8414, 0xdff2, 0x8421, 0xdfc2, 0x842d, 0xdf91, - 0x843a, 0xdf61, 0x8447, 0xdf30, 0x8454, 0xdeff, 0x8461, 0xdecf, - 0x846e, 0xde9e, 0x847b, 0xde6e, 0x8488, 0xde3d, 0x8496, 0xde0d, - 0x84a3, 0xdddc, 0x84b0, 0xddac, 0x84be, 0xdd7c, 0x84cc, 0xdd4b, - 0x84d9, 0xdd1b, 0x84e7, 0xdcea, 0x84f5, 0xdcba, 0x8503, 0xdc8a, - 0x8511, 0xdc59, 0x851f, 0xdc29, 0x852d, 0xdbf9, 0x853b, 0xdbc9, - 0x8549, 0xdb99, 0x8558, 0xdb68, 0x8566, 0xdb38, 0x8574, 0xdb08, - 0x8583, 0xdad8, 0x8592, 0xdaa8, 0x85a0, 0xda78, 0x85af, 0xda48, - 0x85be, 0xda18, 0x85cd, 0xd9e8, 0x85dc, 0xd9b8, 0x85eb, 0xd988, - 0x85fa, 0xd958, 0x8609, 0xd928, 0x8619, 0xd8f8, 0x8628, 0xd8c8, - 0x8637, 0xd898, 0x8647, 0xd869, 0x8656, 0xd839, 0x8666, 0xd809, - 0x8676, 0xd7d9, 0x8686, 0xd7aa, 0x8696, 0xd77a, 0x86a5, 0xd74a, - 0x86b6, 0xd71b, 0x86c6, 0xd6eb, 0x86d6, 0xd6bb, 0x86e6, 0xd68c, - 0x86f6, 0xd65c, 0x8707, 0xd62d, 0x8717, 0xd5fd, 0x8728, 0xd5ce, - 0x8738, 0xd59e, 0x8749, 0xd56f, 0x875a, 0xd53f, 0x876b, 0xd510, - 0x877b, 0xd4e1, 0x878c, 0xd4b1, 0x879d, 0xd482, 0x87af, 0xd453, - 0x87c0, 0xd424, 0x87d1, 0xd3f4, 0x87e2, 0xd3c5, 0x87f4, 0xd396, - 0x8805, 0xd367, 0x8817, 0xd338, 0x8828, 0xd309, 0x883a, 0xd2da, - 0x884c, 0xd2ab, 0x885e, 0xd27c, 0x8870, 0xd24d, 0x8882, 0xd21e, - 0x8894, 0xd1ef, 0x88a6, 0xd1c0, 0x88b8, 0xd191, 0x88ca, 0xd162, - 0x88dd, 0xd134, 0x88ef, 0xd105, 0x8902, 0xd0d6, 0x8914, 0xd0a7, - 0x8927, 0xd079, 0x8939, 0xd04a, 0x894c, 0xd01b, 0x895f, 0xcfed, - 0x8972, 0xcfbe, 0x8985, 0xcf90, 0x8998, 0xcf61, 0x89ab, 0xcf33, - 0x89be, 0xcf04, 0x89d2, 0xced6, 0x89e5, 0xcea7, 0x89f8, 0xce79, - 0x8a0c, 0xce4b, 0x8a1f, 0xce1c, 0x8a33, 0xcdee, 0x8a47, 0xcdc0, - 0x8a5a, 0xcd92, 0x8a6e, 0xcd63, 0x8a82, 0xcd35, 0x8a96, 0xcd07, - 0x8aaa, 0xccd9, 0x8abe, 0xccab, 0x8ad3, 0xcc7d, 0x8ae7, 0xcc4f, - 0x8afb, 0xcc21, 0x8b10, 0xcbf3, 0x8b24, 0xcbc5, 0x8b39, 0xcb97, - 0x8b4d, 0xcb69, 0x8b62, 0xcb3c, 0x8b77, 0xcb0e, 0x8b8b, 0xcae0, - 0x8ba0, 0xcab2, 0x8bb5, 0xca85, 0x8bca, 0xca57, 0x8bdf, 0xca29, - 0x8bf5, 0xc9fc, 0x8c0a, 0xc9ce, 0x8c1f, 0xc9a1, 0x8c35, 0xc973, - 0x8c4a, 0xc946, 0x8c60, 0xc918, 0x8c75, 0xc8eb, 0x8c8b, 0xc8be, - 0x8ca1, 0xc890, 0x8cb6, 0xc863, 0x8ccc, 0xc836, 0x8ce2, 0xc809, - 0x8cf8, 0xc7db, 0x8d0e, 0xc7ae, 0x8d24, 0xc781, 0x8d3b, 0xc754, - 0x8d51, 0xc727, 0x8d67, 0xc6fa, 0x8d7e, 0xc6cd, 0x8d94, 0xc6a0, - 0x8dab, 0xc673, 0x8dc1, 0xc646, 0x8dd8, 0xc619, 0x8def, 0xc5ed, - 0x8e06, 0xc5c0, 0x8e1d, 0xc593, 0x8e34, 0xc566, 0x8e4b, 0xc53a, - 0x8e62, 0xc50d, 0x8e79, 0xc4e0, 0x8e90, 0xc4b4, 0x8ea8, 0xc487, - 0x8ebf, 0xc45b, 0x8ed6, 0xc42e, 0x8eee, 0xc402, 0x8f06, 0xc3d6, - 0x8f1d, 0xc3a9, 0x8f35, 0xc37d, 0x8f4d, 0xc351, 0x8f65, 0xc324, - 0x8f7d, 0xc2f8, 0x8f95, 0xc2cc, 0x8fad, 0xc2a0, 0x8fc5, 0xc274, - 0x8fdd, 0xc248, 0x8ff5, 0xc21c, 0x900e, 0xc1f0, 0x9026, 0xc1c4, - 0x903e, 0xc198, 0x9057, 0xc16c, 0x9070, 0xc140, 0x9088, 0xc114, - 0x90a1, 0xc0e9, 0x90ba, 0xc0bd, 0x90d3, 0xc091, 0x90ec, 0xc066, - 0x9105, 0xc03a, 0x911e, 0xc00f, 0x9137, 0xbfe3, 0x9150, 0xbfb8, - 0x9169, 0xbf8c, 0x9183, 0xbf61, 0x919c, 0xbf35, 0x91b6, 0xbf0a, - 0x91cf, 0xbedf, 0x91e9, 0xbeb3, 0x9202, 0xbe88, 0x921c, 0xbe5d, - 0x9236, 0xbe32, 0x9250, 0xbe07, 0x926a, 0xbddc, 0x9284, 0xbdb1, - 0x929e, 0xbd86, 0x92b8, 0xbd5b, 0x92d2, 0xbd30, 0x92ec, 0xbd05, - 0x9307, 0xbcda, 0x9321, 0xbcaf, 0x933c, 0xbc85, 0x9356, 0xbc5a, - 0x9371, 0xbc2f, 0x938b, 0xbc05, 0x93a6, 0xbbda, 0x93c1, 0xbbb0, - 0x93dc, 0xbb85, 0x93f7, 0xbb5b, 0x9412, 0xbb30, 0x942d, 0xbb06, - 0x9448, 0xbadc, 0x9463, 0xbab1, 0x947e, 0xba87, 0x949a, 0xba5d, - 0x94b5, 0xba33, 0x94d0, 0xba09, 0x94ec, 0xb9df, 0x9508, 0xb9b5, - 0x9523, 0xb98b, 0x953f, 0xb961, 0x955b, 0xb937, 0x9577, 0xb90d, - 0x9592, 0xb8e3, 0x95ae, 0xb8b9, 0x95ca, 0xb890, 0x95e6, 0xb866, - 0x9603, 0xb83c, 0x961f, 0xb813, 0x963b, 0xb7e9, 0x9657, 0xb7c0, - 0x9674, 0xb796, 0x9690, 0xb76d, 0x96ad, 0xb743, 0x96c9, 0xb71a, - 0x96e6, 0xb6f1, 0x9703, 0xb6c7, 0x9720, 0xb69e, 0x973c, 0xb675, - 0x9759, 0xb64c, 0x9776, 0xb623, 0x9793, 0xb5fa, 0x97b0, 0xb5d1, - 0x97ce, 0xb5a8, 0x97eb, 0xb57f, 0x9808, 0xb556, 0x9826, 0xb52d, - 0x9843, 0xb505, 0x9860, 0xb4dc, 0x987e, 0xb4b3, 0x989c, 0xb48b, - 0x98b9, 0xb462, 0x98d7, 0xb439, 0x98f5, 0xb411, 0x9913, 0xb3e9, - 0x9930, 0xb3c0, 0x994e, 0xb398, 0x996d, 0xb36f, 0x998b, 0xb347, - 0x99a9, 0xb31f, 0x99c7, 0xb2f7, 0x99e5, 0xb2cf, 0x9a04, 0xb2a7, - 0x9a22, 0xb27f, 0x9a40, 0xb257, 0x9a5f, 0xb22f, 0x9a7e, 0xb207, - 0x9a9c, 0xb1df, 0x9abb, 0xb1b7, 0x9ada, 0xb18f, 0x9af9, 0xb168, - 0x9b17, 0xb140, 0x9b36, 0xb118, 0x9b55, 0xb0f1, 0x9b75, 0xb0c9, - 0x9b94, 0xb0a2, 0x9bb3, 0xb07b, 0x9bd2, 0xb053, 0x9bf1, 0xb02c, - 0x9c11, 0xb005, 0x9c30, 0xafdd, 0x9c50, 0xafb6, 0x9c6f, 0xaf8f, - 0x9c8f, 0xaf68, 0x9caf, 0xaf41, 0x9cce, 0xaf1a, 0x9cee, 0xaef3, - 0x9d0e, 0xaecc, 0x9d2e, 0xaea5, 0x9d4e, 0xae7f, 0x9d6e, 0xae58, - 0x9d8e, 0xae31, 0x9dae, 0xae0b, 0x9dce, 0xade4, 0x9def, 0xadbd, - 0x9e0f, 0xad97, 0x9e2f, 0xad70, 0x9e50, 0xad4a, 0x9e70, 0xad24, - 0x9e91, 0xacfd, 0x9eb2, 0xacd7, 0x9ed2, 0xacb1, 0x9ef3, 0xac8b, - 0x9f14, 0xac65, 0x9f35, 0xac3f, 0x9f56, 0xac19, 0x9f77, 0xabf3, - 0x9f98, 0xabcd, 0x9fb9, 0xaba7, 0x9fda, 0xab81, 0x9ffb, 0xab5c, - 0xa01c, 0xab36, 0xa03e, 0xab10, 0xa05f, 0xaaeb, 0xa080, 0xaac5, - 0xa0a2, 0xaaa0, 0xa0c4, 0xaa7a, 0xa0e5, 0xaa55, 0xa107, 0xaa30, - 0xa129, 0xaa0a, 0xa14a, 0xa9e5, 0xa16c, 0xa9c0, 0xa18e, 0xa99b, - 0xa1b0, 0xa976, 0xa1d2, 0xa951, 0xa1f4, 0xa92c, 0xa216, 0xa907, - 0xa238, 0xa8e2, 0xa25b, 0xa8bd, 0xa27d, 0xa899, 0xa29f, 0xa874, - 0xa2c2, 0xa84f, 0xa2e4, 0xa82b, 0xa307, 0xa806, 0xa329, 0xa7e2, - 0xa34c, 0xa7bd, 0xa36f, 0xa799, 0xa391, 0xa774, 0xa3b4, 0xa750, - 0xa3d7, 0xa72c, 0xa3fa, 0xa708, 0xa41d, 0xa6e4, 0xa440, 0xa6c0, - 0xa463, 0xa69c, 0xa486, 0xa678, 0xa4a9, 0xa654, 0xa4cc, 0xa630, - 0xa4f0, 0xa60c, 0xa513, 0xa5e8, 0xa537, 0xa5c5, 0xa55a, 0xa5a1, - 0xa57e, 0xa57e, 0xa5a1, 0xa55a, 0xa5c5, 0xa537, 0xa5e8, 0xa513, - 0xa60c, 0xa4f0, 0xa630, 0xa4cc, 0xa654, 0xa4a9, 0xa678, 0xa486, - 0xa69c, 0xa463, 0xa6c0, 0xa440, 0xa6e4, 0xa41d, 0xa708, 0xa3fa, - 0xa72c, 0xa3d7, 0xa750, 0xa3b4, 0xa774, 0xa391, 0xa799, 0xa36f, - 0xa7bd, 0xa34c, 0xa7e2, 0xa329, 0xa806, 0xa307, 0xa82b, 0xa2e4, - 0xa84f, 0xa2c2, 0xa874, 0xa29f, 0xa899, 0xa27d, 0xa8bd, 0xa25b, - 0xa8e2, 0xa238, 0xa907, 0xa216, 0xa92c, 0xa1f4, 0xa951, 0xa1d2, - 0xa976, 0xa1b0, 0xa99b, 0xa18e, 0xa9c0, 0xa16c, 0xa9e5, 0xa14a, - 0xaa0a, 0xa129, 0xaa30, 0xa107, 0xaa55, 0xa0e5, 0xaa7a, 0xa0c4, - 0xaaa0, 0xa0a2, 0xaac5, 0xa080, 0xaaeb, 0xa05f, 0xab10, 0xa03e, - 0xab36, 0xa01c, 0xab5c, 0x9ffb, 0xab81, 0x9fda, 0xaba7, 0x9fb9, - 0xabcd, 0x9f98, 0xabf3, 0x9f77, 0xac19, 0x9f56, 0xac3f, 0x9f35, - 0xac65, 0x9f14, 0xac8b, 0x9ef3, 0xacb1, 0x9ed2, 0xacd7, 0x9eb2, - 0xacfd, 0x9e91, 0xad24, 0x9e70, 0xad4a, 0x9e50, 0xad70, 0x9e2f, - 0xad97, 0x9e0f, 0xadbd, 0x9def, 0xade4, 0x9dce, 0xae0b, 0x9dae, - 0xae31, 0x9d8e, 0xae58, 0x9d6e, 0xae7f, 0x9d4e, 0xaea5, 0x9d2e, - 0xaecc, 0x9d0e, 0xaef3, 0x9cee, 0xaf1a, 0x9cce, 0xaf41, 0x9caf, - 0xaf68, 0x9c8f, 0xaf8f, 0x9c6f, 0xafb6, 0x9c50, 0xafdd, 0x9c30, - 0xb005, 0x9c11, 0xb02c, 0x9bf1, 0xb053, 0x9bd2, 0xb07b, 0x9bb3, - 0xb0a2, 0x9b94, 0xb0c9, 0x9b75, 0xb0f1, 0x9b55, 0xb118, 0x9b36, - 0xb140, 0x9b17, 0xb168, 0x9af9, 0xb18f, 0x9ada, 0xb1b7, 0x9abb, - 0xb1df, 0x9a9c, 0xb207, 0x9a7e, 0xb22f, 0x9a5f, 0xb257, 0x9a40, - 0xb27f, 0x9a22, 0xb2a7, 0x9a04, 0xb2cf, 0x99e5, 0xb2f7, 0x99c7, - 0xb31f, 0x99a9, 0xb347, 0x998b, 0xb36f, 0x996d, 0xb398, 0x994e, - 0xb3c0, 0x9930, 0xb3e9, 0x9913, 0xb411, 0x98f5, 0xb439, 0x98d7, - 0xb462, 0x98b9, 0xb48b, 0x989c, 0xb4b3, 0x987e, 0xb4dc, 0x9860, - 0xb505, 0x9843, 0xb52d, 0x9826, 0xb556, 0x9808, 0xb57f, 0x97eb, - 0xb5a8, 0x97ce, 0xb5d1, 0x97b0, 0xb5fa, 0x9793, 0xb623, 0x9776, - 0xb64c, 0x9759, 0xb675, 0x973c, 0xb69e, 0x9720, 0xb6c7, 0x9703, - 0xb6f1, 0x96e6, 0xb71a, 0x96c9, 0xb743, 0x96ad, 0xb76d, 0x9690, - 0xb796, 0x9674, 0xb7c0, 0x9657, 0xb7e9, 0x963b, 0xb813, 0x961f, - 0xb83c, 0x9603, 0xb866, 0x95e6, 0xb890, 0x95ca, 0xb8b9, 0x95ae, - 0xb8e3, 0x9592, 0xb90d, 0x9577, 0xb937, 0x955b, 0xb961, 0x953f, - 0xb98b, 0x9523, 0xb9b5, 0x9508, 0xb9df, 0x94ec, 0xba09, 0x94d0, - 0xba33, 0x94b5, 0xba5d, 0x949a, 0xba87, 0x947e, 0xbab1, 0x9463, - 0xbadc, 0x9448, 0xbb06, 0x942d, 0xbb30, 0x9412, 0xbb5b, 0x93f7, - 0xbb85, 0x93dc, 0xbbb0, 0x93c1, 0xbbda, 0x93a6, 0xbc05, 0x938b, - 0xbc2f, 0x9371, 0xbc5a, 0x9356, 0xbc85, 0x933c, 0xbcaf, 0x9321, - 0xbcda, 0x9307, 0xbd05, 0x92ec, 0xbd30, 0x92d2, 0xbd5b, 0x92b8, - 0xbd86, 0x929e, 0xbdb1, 0x9284, 0xbddc, 0x926a, 0xbe07, 0x9250, - 0xbe32, 0x9236, 0xbe5d, 0x921c, 0xbe88, 0x9202, 0xbeb3, 0x91e9, - 0xbedf, 0x91cf, 0xbf0a, 0x91b6, 0xbf35, 0x919c, 0xbf61, 0x9183, - 0xbf8c, 0x9169, 0xbfb8, 0x9150, 0xbfe3, 0x9137, 0xc00f, 0x911e, - 0xc03a, 0x9105, 0xc066, 0x90ec, 0xc091, 0x90d3, 0xc0bd, 0x90ba, - 0xc0e9, 0x90a1, 0xc114, 0x9088, 0xc140, 0x9070, 0xc16c, 0x9057, - 0xc198, 0x903e, 0xc1c4, 0x9026, 0xc1f0, 0x900e, 0xc21c, 0x8ff5, - 0xc248, 0x8fdd, 0xc274, 0x8fc5, 0xc2a0, 0x8fad, 0xc2cc, 0x8f95, - 0xc2f8, 0x8f7d, 0xc324, 0x8f65, 0xc351, 0x8f4d, 0xc37d, 0x8f35, - 0xc3a9, 0x8f1d, 0xc3d6, 0x8f06, 0xc402, 0x8eee, 0xc42e, 0x8ed6, - 0xc45b, 0x8ebf, 0xc487, 0x8ea8, 0xc4b4, 0x8e90, 0xc4e0, 0x8e79, - 0xc50d, 0x8e62, 0xc53a, 0x8e4b, 0xc566, 0x8e34, 0xc593, 0x8e1d, - 0xc5c0, 0x8e06, 0xc5ed, 0x8def, 0xc619, 0x8dd8, 0xc646, 0x8dc1, - 0xc673, 0x8dab, 0xc6a0, 0x8d94, 0xc6cd, 0x8d7e, 0xc6fa, 0x8d67, - 0xc727, 0x8d51, 0xc754, 0x8d3b, 0xc781, 0x8d24, 0xc7ae, 0x8d0e, - 0xc7db, 0x8cf8, 0xc809, 0x8ce2, 0xc836, 0x8ccc, 0xc863, 0x8cb6, - 0xc890, 0x8ca1, 0xc8be, 0x8c8b, 0xc8eb, 0x8c75, 0xc918, 0x8c60, - 0xc946, 0x8c4a, 0xc973, 0x8c35, 0xc9a1, 0x8c1f, 0xc9ce, 0x8c0a, - 0xc9fc, 0x8bf5, 0xca29, 0x8bdf, 0xca57, 0x8bca, 0xca85, 0x8bb5, - 0xcab2, 0x8ba0, 0xcae0, 0x8b8b, 0xcb0e, 0x8b77, 0xcb3c, 0x8b62, - 0xcb69, 0x8b4d, 0xcb97, 0x8b39, 0xcbc5, 0x8b24, 0xcbf3, 0x8b10, - 0xcc21, 0x8afb, 0xcc4f, 0x8ae7, 0xcc7d, 0x8ad3, 0xccab, 0x8abe, - 0xccd9, 0x8aaa, 0xcd07, 0x8a96, 0xcd35, 0x8a82, 0xcd63, 0x8a6e, - 0xcd92, 0x8a5a, 0xcdc0, 0x8a47, 0xcdee, 0x8a33, 0xce1c, 0x8a1f, - 0xce4b, 0x8a0c, 0xce79, 0x89f8, 0xcea7, 0x89e5, 0xced6, 0x89d2, - 0xcf04, 0x89be, 0xcf33, 0x89ab, 0xcf61, 0x8998, 0xcf90, 0x8985, - 0xcfbe, 0x8972, 0xcfed, 0x895f, 0xd01b, 0x894c, 0xd04a, 0x8939, - 0xd079, 0x8927, 0xd0a7, 0x8914, 0xd0d6, 0x8902, 0xd105, 0x88ef, - 0xd134, 0x88dd, 0xd162, 0x88ca, 0xd191, 0x88b8, 0xd1c0, 0x88a6, - 0xd1ef, 0x8894, 0xd21e, 0x8882, 0xd24d, 0x8870, 0xd27c, 0x885e, - 0xd2ab, 0x884c, 0xd2da, 0x883a, 0xd309, 0x8828, 0xd338, 0x8817, - 0xd367, 0x8805, 0xd396, 0x87f4, 0xd3c5, 0x87e2, 0xd3f4, 0x87d1, - 0xd424, 0x87c0, 0xd453, 0x87af, 0xd482, 0x879d, 0xd4b1, 0x878c, - 0xd4e1, 0x877b, 0xd510, 0x876b, 0xd53f, 0x875a, 0xd56f, 0x8749, - 0xd59e, 0x8738, 0xd5ce, 0x8728, 0xd5fd, 0x8717, 0xd62d, 0x8707, - 0xd65c, 0x86f6, 0xd68c, 0x86e6, 0xd6bb, 0x86d6, 0xd6eb, 0x86c6, - 0xd71b, 0x86b6, 0xd74a, 0x86a5, 0xd77a, 0x8696, 0xd7aa, 0x8686, - 0xd7d9, 0x8676, 0xd809, 0x8666, 0xd839, 0x8656, 0xd869, 0x8647, - 0xd898, 0x8637, 0xd8c8, 0x8628, 0xd8f8, 0x8619, 0xd928, 0x8609, - 0xd958, 0x85fa, 0xd988, 0x85eb, 0xd9b8, 0x85dc, 0xd9e8, 0x85cd, - 0xda18, 0x85be, 0xda48, 0x85af, 0xda78, 0x85a0, 0xdaa8, 0x8592, - 0xdad8, 0x8583, 0xdb08, 0x8574, 0xdb38, 0x8566, 0xdb68, 0x8558, - 0xdb99, 0x8549, 0xdbc9, 0x853b, 0xdbf9, 0x852d, 0xdc29, 0x851f, - 0xdc59, 0x8511, 0xdc8a, 0x8503, 0xdcba, 0x84f5, 0xdcea, 0x84e7, - 0xdd1b, 0x84d9, 0xdd4b, 0x84cc, 0xdd7c, 0x84be, 0xddac, 0x84b0, - 0xdddc, 0x84a3, 0xde0d, 0x8496, 0xde3d, 0x8488, 0xde6e, 0x847b, - 0xde9e, 0x846e, 0xdecf, 0x8461, 0xdeff, 0x8454, 0xdf30, 0x8447, - 0xdf61, 0x843a, 0xdf91, 0x842d, 0xdfc2, 0x8421, 0xdff2, 0x8414, - 0xe023, 0x8407, 0xe054, 0x83fb, 0xe085, 0x83ef, 0xe0b5, 0x83e2, - 0xe0e6, 0x83d6, 0xe117, 0x83ca, 0xe148, 0x83be, 0xe178, 0x83b2, - 0xe1a9, 0x83a6, 0xe1da, 0x839a, 0xe20b, 0x838e, 0xe23c, 0x8382, - 0xe26d, 0x8377, 0xe29e, 0x836b, 0xe2cf, 0x8360, 0xe2ff, 0x8354, - 0xe330, 0x8349, 0xe361, 0x833e, 0xe392, 0x8332, 0xe3c3, 0x8327, - 0xe3f4, 0x831c, 0xe426, 0x8311, 0xe457, 0x8306, 0xe488, 0x82fb, - 0xe4b9, 0x82f1, 0xe4ea, 0x82e6, 0xe51b, 0x82db, 0xe54c, 0x82d1, - 0xe57d, 0x82c6, 0xe5af, 0x82bc, 0xe5e0, 0x82b2, 0xe611, 0x82a8, - 0xe642, 0x829d, 0xe673, 0x8293, 0xe6a5, 0x8289, 0xe6d6, 0x827f, - 0xe707, 0x8276, 0xe739, 0x826c, 0xe76a, 0x8262, 0xe79b, 0x8259, - 0xe7cd, 0x824f, 0xe7fe, 0x8246, 0xe82f, 0x823c, 0xe861, 0x8233, - 0xe892, 0x822a, 0xe8c4, 0x8220, 0xe8f5, 0x8217, 0xe926, 0x820e, - 0xe958, 0x8205, 0xe989, 0x81fd, 0xe9bb, 0x81f4, 0xe9ec, 0x81eb, - 0xea1e, 0x81e2, 0xea4f, 0x81da, 0xea81, 0x81d1, 0xeab3, 0x81c9, - 0xeae4, 0x81c1, 0xeb16, 0x81b8, 0xeb47, 0x81b0, 0xeb79, 0x81a8, - 0xebab, 0x81a0, 0xebdc, 0x8198, 0xec0e, 0x8190, 0xec3f, 0x8188, - 0xec71, 0x8181, 0xeca3, 0x8179, 0xecd5, 0x8172, 0xed06, 0x816a, - 0xed38, 0x8163, 0xed6a, 0x815b, 0xed9b, 0x8154, 0xedcd, 0x814d, - 0xedff, 0x8146, 0xee31, 0x813f, 0xee62, 0x8138, 0xee94, 0x8131, - 0xeec6, 0x812a, 0xeef8, 0x8123, 0xef2a, 0x811d, 0xef5c, 0x8116, - 0xef8d, 0x8110, 0xefbf, 0x8109, 0xeff1, 0x8103, 0xf023, 0x80fd, - 0xf055, 0x80f6, 0xf087, 0x80f0, 0xf0b9, 0x80ea, 0xf0eb, 0x80e4, - 0xf11c, 0x80de, 0xf14e, 0x80d9, 0xf180, 0x80d3, 0xf1b2, 0x80cd, - 0xf1e4, 0x80c8, 0xf216, 0x80c2, 0xf248, 0x80bd, 0xf27a, 0x80b7, - 0xf2ac, 0x80b2, 0xf2de, 0x80ad, 0xf310, 0x80a8, 0xf342, 0x80a3, - 0xf374, 0x809e, 0xf3a6, 0x8099, 0xf3d8, 0x8094, 0xf40a, 0x808f, - 0xf43c, 0x808b, 0xf46e, 0x8086, 0xf4a0, 0x8082, 0xf4d3, 0x807d, - 0xf505, 0x8079, 0xf537, 0x8075, 0xf569, 0x8070, 0xf59b, 0x806c, - 0xf5cd, 0x8068, 0xf5ff, 0x8064, 0xf631, 0x8060, 0xf663, 0x805d, - 0xf695, 0x8059, 0xf6c8, 0x8055, 0xf6fa, 0x8052, 0xf72c, 0x804e, - 0xf75e, 0x804b, 0xf790, 0x8047, 0xf7c2, 0x8044, 0xf7f4, 0x8041, - 0xf827, 0x803e, 0xf859, 0x803b, 0xf88b, 0x8038, 0xf8bd, 0x8035, - 0xf8ef, 0x8032, 0xf922, 0x802f, 0xf954, 0x802d, 0xf986, 0x802a, - 0xf9b8, 0x8027, 0xf9ea, 0x8025, 0xfa1d, 0x8023, 0xfa4f, 0x8020, - 0xfa81, 0x801e, 0xfab3, 0x801c, 0xfae5, 0x801a, 0xfb18, 0x8018, - 0xfb4a, 0x8016, 0xfb7c, 0x8014, 0xfbae, 0x8013, 0xfbe1, 0x8011, - 0xfc13, 0x800f, 0xfc45, 0x800e, 0xfc77, 0x800c, 0xfcaa, 0x800b, - 0xfcdc, 0x800a, 0xfd0e, 0x8009, 0xfd40, 0x8008, 0xfd73, 0x8007, - 0xfda5, 0x8006, 0xfdd7, 0x8005, 0xfe09, 0x8004, 0xfe3c, 0x8003, - 0xfe6e, 0x8002, 0xfea0, 0x8002, 0xfed2, 0x8001, 0xff05, 0x8001, - 0xff37, 0x8001, 0xff69, 0x8000, 0xff9b, 0x8000, 0xffce, 0x8000, -}; - -/** - * @} end of CFFT_CIFFT group - */ - -/* -* @brief Q15 table for reciprocal -*/ -const q15_t ALIGN4 armRecipTableQ15[64] = { - 0x7F03, 0x7D13, 0x7B31, 0x795E, 0x7798, 0x75E0, - 0x7434, 0x7294, 0x70FF, 0x6F76, 0x6DF6, 0x6C82, - 0x6B16, 0x69B5, 0x685C, 0x670C, 0x65C4, 0x6484, - 0x634C, 0x621C, 0x60F3, 0x5FD0, 0x5EB5, 0x5DA0, - 0x5C91, 0x5B88, 0x5A85, 0x5988, 0x5890, 0x579E, - 0x56B0, 0x55C8, 0x54E4, 0x5405, 0x532B, 0x5255, - 0x5183, 0x50B6, 0x4FEC, 0x4F26, 0x4E64, 0x4DA6, - 0x4CEC, 0x4C34, 0x4B81, 0x4AD0, 0x4A23, 0x4978, - 0x48D1, 0x482D, 0x478C, 0x46ED, 0x4651, 0x45B8, - 0x4521, 0x448D, 0x43FC, 0x436C, 0x42DF, 0x4255, - 0x41CC, 0x4146, 0x40C2, 0x4040 -}; - -/* -* @brief Q31 table for reciprocal -*/ -const q31_t armRecipTableQ31[64] = { - 0x7F03F03F, 0x7D137420, 0x7B31E739, 0x795E9F94, 0x7798FD29, 0x75E06928, - 0x7434554D, 0x72943B4B, 0x70FF9C40, 0x6F760031, 0x6DF6F593, 0x6C8210E3, - 0x6B16EC3A, 0x69B526F6, 0x685C655F, 0x670C505D, 0x65C4952D, 0x6484E519, - 0x634CF53E, 0x621C7E4F, 0x60F33C61, 0x5FD0EEB3, 0x5EB55785, 0x5DA03BEB, - 0x5C9163A1, 0x5B8898E6, 0x5A85A85A, 0x598860DF, 0x58909373, 0x579E1318, - 0x56B0B4B8, 0x55C84F0B, 0x54E4BA80, 0x5405D124, 0x532B6E8F, 0x52556FD0, - 0x5183B35A, 0x50B618F3, 0x4FEC81A2, 0x4F26CFA2, 0x4E64E64E, 0x4DA6AA1D, - 0x4CEC008B, 0x4C34D010, 0x4B810016, 0x4AD078EF, 0x4A2323C4, 0x4978EA96, - 0x48D1B827, 0x482D77FE, 0x478C1657, 0x46ED801D, 0x4651A2E5, 0x45B86CE2, - 0x4521CCE1, 0x448DB244, 0x43FC0CFA, 0x436CCD78, 0x42DFE4B4, 0x42554426, - 0x41CCDDB6, 0x4146A3C6, 0x40C28923, 0x40408102 -}; diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c deleted file mode 100644 index 31bbaa7a80..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_f32.c +++ /dev/null @@ -1,174 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cmplx_conj_f32.c -* -* Description: Floating-point complex conjugate. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @ingroup groupCmplxMath - */ - -/** - * @defgroup cmplx_conj Complex Conjugate - * - * Conjugates the elements of a complex data vector. - * - * The pSrc points to the source data and - * pDst points to the where the result should be written. - * numSamples specifies the number of complex samples - * and the data in each array is stored in an interleaved fashion - * (real, imag, real, imag, ...). - * Each array has a total of 2*numSamples values. - * The underlying algorithm is used: - * - *
        
- * for(n=0; n        
- *        
- * There are separate functions for floating-point, Q15, and Q31 data types.        
- */
-
-/**        
- * @addtogroup cmplx_conj        
- * @{        
- */
-
-/**        
- * @brief  Floating-point complex conjugate.        
- * @param  *pSrc points to the input vector        
- * @param  *pDst points to the output vector        
- * @param  numSamples number of complex samples in each vector        
- * @return none.        
- */
-
-void arm_cmplx_conj_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  uint32_t blkCnt;                               /* loop counter */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  float32_t inR1, inR2, inR3, inR4;
-  float32_t inI1, inI2, inI3, inI4;
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    /* read real input samples */
-    inR1 = pSrc[0];
-    /* store real samples to destination */
-    pDst[0] = inR1;
-    inR2 = pSrc[2];
-    pDst[2] = inR2;
-    inR3 = pSrc[4];
-    pDst[4] = inR3;
-    inR4 = pSrc[6];
-    pDst[6] = inR4;
-
-    /* read imaginary input samples */
-    inI1 = pSrc[1];
-    inI2 = pSrc[3];
-
-    /* conjugate input */
-    inI1 = -inI1;
-
-    /* read imaginary input samples */
-    inI3 = pSrc[5];
-
-    /* conjugate input */
-    inI2 = -inI2;
-
-    /* read imaginary input samples */
-    inI4 = pSrc[7];
-
-    /* conjugate input */
-    inI3 = -inI3;
-
-    /* store imaginary samples to destination */
-    pDst[1] = inI1;
-    pDst[3] = inI2;
-
-    /* conjugate input */
-    inI4 = -inI4;
-
-    /* store imaginary samples to destination */
-    pDst[5] = inI3;
-
-    /* increment source pointer by 8 to process next sampels */
-    pSrc += 8u;
-
-    /* store imaginary sample to destination */
-    pDst[7] = inI4;
-
-    /* increment destination pointer by 8 to store next samples */
-    pDst += 8u;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  blkCnt = numSamples;
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* realOut + j (imagOut) = realIn + j (-1) imagIn */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = -*pSrc++;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of cmplx_conj group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c
deleted file mode 100644
index c5a3703157..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q15.c
+++ /dev/null
@@ -1,153 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_conj_q15.c    
-*    
-* Description:	Q15 complex conjugate.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_conj    
- * @{    
- */
-
-/**    
- * @brief  Q15 complex conjugate.    
- * @param  *pSrc points to the input vector    
- * @param  *pDst points to the output vector    
- * @param  numSamples number of complex samples in each vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function uses saturating arithmetic.    
- * The Q15 value -1 (0x8000) will be saturated to the maximum allowable positive value 0x7FFF.    
- */
-
-void arm_cmplx_conj_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-  q31_t in1, in2, in3, in4;
-  q31_t zero = 0;
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    in1 = *__SIMD32(pSrc)++;
-    in2 = *__SIMD32(pSrc)++;
-    in3 = *__SIMD32(pSrc)++;
-    in4 = *__SIMD32(pSrc)++;
-
-#ifndef ARM_MATH_BIG_ENDIAN
-
-    in1 = __QASX(zero, in1);
-    in2 = __QASX(zero, in2);
-    in3 = __QASX(zero, in3);
-    in4 = __QASX(zero, in4);
-
-#else
-
-    in1 = __QSAX(zero, in1);
-    in2 = __QSAX(zero, in2);
-    in3 = __QSAX(zero, in3);
-    in4 = __QSAX(zero, in4);
-
-#endif //       #ifndef ARM_MATH_BIG_ENDIAN
-
-    in1 = ((uint32_t) in1 >> 16) | ((uint32_t) in1 << 16);
-    in2 = ((uint32_t) in2 >> 16) | ((uint32_t) in2 << 16);
-    in3 = ((uint32_t) in3 >> 16) | ((uint32_t) in3 << 16);
-    in4 = ((uint32_t) in4 >> 16) | ((uint32_t) in4 << 16);
-
-    *__SIMD32(pDst)++ = in1;
-    *__SIMD32(pDst)++ = in2;
-    *__SIMD32(pDst)++ = in3;
-    *__SIMD32(pDst)++ = in4;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    *pDst++ = __SSAT(-*pSrc++, 16);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  q15_t in;
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut + j (imagOut) = realIn+ j (-1) imagIn */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == (q15_t) 0x8000) ? 0x7fff : -in;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of cmplx_conj group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c
deleted file mode 100644
index 7475962d53..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_conj_q31.c
+++ /dev/null
@@ -1,172 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_conj_q31.c    
-*    
-* Description:	Q31 complex conjugate.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-#include "arm_math.h"
-
-/**        
- * @ingroup groupCmplxMath        
- */
-
-/**        
- * @addtogroup cmplx_conj        
- * @{        
- */
-
-/**        
- * @brief  Q31 complex conjugate.        
- * @param  *pSrc points to the input vector        
- * @param  *pDst points to the output vector        
- * @param  numSamples number of complex samples in each vector        
- * @return none.        
- *        
- * Scaling and Overflow Behavior:        
- * \par        
- * The function uses saturating arithmetic.        
- * The Q31 value -1 (0x80000000) will be saturated to the maximum allowable positive value 0x7FFFFFFF.        
- */
-
-void arm_cmplx_conj_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  uint32_t blkCnt;                               /* loop counter */
-  q31_t in;                                      /* Input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  q31_t inR1, inR2, inR3, inR4;                  /* Temporary real variables */
-  q31_t inI1, inI2, inI3, inI4;                  /* Temporary imaginary variables */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
-    /* read real input sample */
-    inR1 = pSrc[0];
-    /* store real input sample */
-    pDst[0] = inR1;
-
-    /* read imaginary input sample */
-    inI1 = pSrc[1];
-
-    /* read real input sample */
-    inR2 = pSrc[2];
-    /* store real input sample */
-    pDst[2] = inR2;
-
-    /* read imaginary input sample */
-    inI2 = pSrc[3];
-
-    /* negate imaginary input sample */
-    inI1 = __QSUB(0, inI1);
-
-    /* read real input sample */
-    inR3 = pSrc[4];
-    /* store real input sample */
-    pDst[4] = inR3;
-
-    /* read imaginary input sample */
-    inI3 = pSrc[5];
-
-    /* negate imaginary input sample */
-    inI2 = __QSUB(0, inI2);
-
-    /* read real input sample */
-    inR4 = pSrc[6];
-    /* store real input sample */
-    pDst[6] = inR4;
-
-    /* negate imaginary input sample */
-    inI3 = __QSUB(0, inI3);
-
-    /* store imaginary input sample */
-    inI4 = pSrc[7];
-
-    /* store imaginary input samples */
-    pDst[1] = inI1;
-
-    /* negate imaginary input sample */
-    inI4 = __QSUB(0, inI4);
-
-    /* store imaginary input samples */
-    pDst[3] = inI2;
-
-    /* increment source pointer by 8 to proecess next samples */
-    pSrc += 8u;
-
-    /* store imaginary input samples */
-    pDst[5] = inI3;
-    pDst[7] = inI4;
-
-    /* increment destination pointer by 8 to process next samples */
-    pDst += 8u;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  blkCnt = numSamples;
-
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* C[0]+jC[1] = A[0]+ j (-1) A[1] */
-    /* Calculate Complex Conjugate and then store the results in the destination buffer. */
-    /* Saturated to 0x7fffffff if the input is -1(0x80000000) */
-    *pDst++ = *pSrc++;
-    in = *pSrc++;
-    *pDst++ = (in == 0x80000000) ? 0x7fffffff : -in;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of cmplx_conj group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c
deleted file mode 100644
index 4f265d6902..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_f32.c
+++ /dev/null
@@ -1,160 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_dot_prod_f32.c    
-*    
-* Description:	Floating-point complex dot product    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @defgroup cmplx_dot_prod Complex Dot Product    
- *    
- * Computes the dot product of two complex vectors.    
- * The vectors are multiplied element-by-element and then summed.    
- *   
- * The pSrcA points to the first complex input vector and    
- * pSrcB points to the second complex input vector.    
- * numSamples specifies the number of complex samples    
- * and the data in each array is stored in an interleaved fashion    
- * (real, imag, real, imag, ...).    
- * Each array has a total of 2*numSamples values.    
- *    
- * The underlying algorithm is used:    
- * 
    
- * realResult=0;    
- * imagResult=0;    
- * for(n=0; n    
- *    
- * There are separate functions for floating-point, Q15, and Q31 data types.    
- */
-
-/**    
- * @addtogroup cmplx_dot_prod    
- * @{    
- */
-
-/**    
- * @brief  Floating-point complex dot product    
- * @param  *pSrcA points to the first input vector    
- * @param  *pSrcB points to the second input vector    
- * @param  numSamples number of complex samples in each vector    
- * @param  *realResult real part of the result returned here    
- * @param  *imagResult imaginary part of the result returned here    
- * @return none.    
- */
-
-void arm_cmplx_dot_prod_f32(
-  float32_t * pSrcA,
-  float32_t * pSrcB,
-  uint32_t numSamples,
-  float32_t * realResult,
-  float32_t * imagResult)
-{
-  float32_t real_sum = 0.0f, imag_sum = 0.0f;    /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (*pSrcA++) * (*pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (*pSrcA++) * (*pSrcB++);
-
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in the destination buffers */
-  *realResult = real_sum;
-  *imagResult = imag_sum;
-}
-
-/**    
- * @} end of cmplx_dot_prod group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c
deleted file mode 100644
index 33df820a5c..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q15.c
+++ /dev/null
@@ -1,144 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_dot_prod_q15.c    
-*    
-* Description:	Processing function for the Q15 Complex Dot product    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_dot_prod    
- * @{    
- */
-
-/**    
- * @brief  Q15 complex dot product    
- * @param  *pSrcA points to the first input vector    
- * @param  *pSrcB points to the second input vector    
- * @param  numSamples number of complex samples in each vector    
- * @param  *realResult real part of the result returned here    
- * @param  *imagResult imaginary part of the result returned here    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function is implemented using an internal 64-bit accumulator.    
- * The intermediate 1.15 by 1.15 multiplications are performed with full precision and yield a 2.30 result.    
- * These are accumulated in a 64-bit accumulator with 34.30 precision.    
- * As a final step, the accumulators are converted to 8.24 format.    
- * The return results realResult and imagResult are in 8.24 format.    
- */
-
-void arm_cmplx_dot_prod_q15(
-  q15_t * pSrcA,
-  q15_t * pSrcB,
-  uint32_t numSamples,
-  q31_t * realResult,
-  q31_t * imagResult)
-{
-  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += ((q31_t) * pSrcA++ * *pSrcB++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in 8.24 format  */
-  /* Convert real data in 34.30 to 8.24 by 6 right shifts */
-  *realResult = (q31_t) (real_sum) >> 6;
-  /* Convert imaginary data in 34.30 to 8.24 by 6 right shifts */
-  *imagResult = (q31_t) (imag_sum) >> 6;
-}
-
-/**    
- * @} end of cmplx_dot_prod group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c
deleted file mode 100644
index d371dff8b2..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_dot_prod_q31.c
+++ /dev/null
@@ -1,145 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_dot_prod_q31.c    
-*    
-* Description:	Q31 complex dot product    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_dot_prod    
- * @{    
- */
-
-/**    
- * @brief  Q31 complex dot product    
- * @param  *pSrcA points to the first input vector    
- * @param  *pSrcB points to the second input vector    
- * @param  numSamples number of complex samples in each vector    
- * @param  *realResult real part of the result returned here    
- * @param  *imagResult imaginary part of the result returned here    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function is implemented using an internal 64-bit accumulator.    
- * The intermediate 1.31 by 1.31 multiplications are performed with 64-bit precision and then shifted to 16.48 format.    
- * The internal real and imaginary accumulators are in 16.48 format and provide 15 guard bits.    
- * Additions are nonsaturating and no overflow will occur as long as numSamples is less than 32768.    
- * The return results realResult and imagResult are in 16.48 format.    
- * Input down scaling is not required.    
- */
-
-void arm_cmplx_dot_prod_q31(
-  q31_t * pSrcA,
-  q31_t * pSrcB,
-  uint32_t numSamples,
-  q63_t * realResult,
-  q63_t * imagResult)
-{
-  q63_t real_sum = 0, imag_sum = 0;              /* Temporary result storage */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    /* Convert real data in 2.62 to 16.48 by 14 right shifts */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    /* Convert imag data in 2.62 to 16.48 by 14 right shifts */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples  is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* CReal = A[0]* B[0] + A[2]* B[2] + A[4]* B[4] + .....+ A[numSamples-2]* B[numSamples-2] */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* CImag = A[1]* B[1] + A[3]* B[3] + A[5]* B[5] + .....+ A[numSamples-1]* B[numSamples-1] */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* outReal = realA[0]* realB[0] + realA[2]* realB[2] + realA[4]* realB[4] + .....+ realA[numSamples-2]* realB[numSamples-2] */
-    real_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-    /* outImag = imagA[1]* imagB[1] + imagA[3]* imagB[3] + imagA[5]* imagB[5] + .....+ imagA[numSamples-1]* imagB[numSamples-1] */
-    imag_sum += (q63_t) * pSrcA++ * (*pSrcB++) >> 14;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Store the real and imaginary results in 16.48 format  */
-  *realResult = real_sum;
-  *imagResult = imag_sum;
-}
-
-/**    
- * @} end of cmplx_dot_prod group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
deleted file mode 100644
index 59bbc27422..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
+++ /dev/null
@@ -1,157 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_f32.c    
-*    
-* Description:	Floating-point complex magnitude.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @defgroup cmplx_mag Complex Magnitude    
- *    
- * Computes the magnitude of the elements of a complex data vector.    
- *   
- * The pSrc points to the source data and    
- * pDst points to the where the result should be written.    
- * numSamples specifies the number of complex samples    
- * in the input array and the data is stored in an interleaved fashion    
- * (real, imag, real, imag, ...).    
- * The input array has a total of 2*numSamples values;    
- * the output array has a total of numSamples values.    
- * The underlying algorithm is used:    
- *    
- * 
    
- * for(n=0; n    
- *    
- * There are separate functions for floating-point, Q15, and Q31 data types.    
- */
-
-/**    
- * @addtogroup cmplx_mag    
- * @{    
- */
-/**    
- * @brief Floating-point complex magnitude.    
- * @param[in]       *pSrc points to complex input buffer    
- * @param[out]      *pDst points to real output buffer    
- * @param[in]       numSamples number of complex samples in the input vector    
- * @return none.    
- *    
- */
-
-
-void arm_cmplx_mag_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t realIn, imagIn;                      /* Temporary variables to hold input values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = sqrt((real * real) + (imag * imag)) */
-    realIn = *pSrc++;
-    imagIn = *pSrc++;
-    /* store the result in the destination buffer. */
-    arm_sqrt_f32((realIn * realIn) + (imagIn * imagIn), pDst++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of cmplx_mag group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c
deleted file mode 100644
index 122ca8bc1f..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q15.c
+++ /dev/null
@@ -1,145 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_q15.c    
-*    
-* Description:	Q15 complex magnitude.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_mag    
- * @{    
- */
-
-
-/**    
- * @brief  Q15 complex magnitude    
- * @param  *pSrc points to the complex input vector    
- * @param  *pDst points to the real output vector    
- * @param  numSamples number of complex samples in the input vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 2.14 format.    
- */
-
-void arm_cmplx_mag_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-  q31_t in1, in2, in3, in4;
-  q31_t acc2, acc3;
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    in1 = *__SIMD32(pSrc)++;
-    in2 = *__SIMD32(pSrc)++;
-    in3 = *__SIMD32(pSrc)++;
-    in4 = *__SIMD32(pSrc)++;
-
-    acc0 = __SMUAD(in1, in1);
-    acc1 = __SMUAD(in2, in2);
-    acc2 = __SMUAD(in3, in3);
-    acc3 = __SMUAD(in4, in4);
-
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) ((acc0) >> 17), pDst++);
-    arm_sqrt_q15((q15_t) ((acc1) >> 17), pDst++);
-    arm_sqrt_q15((q15_t) ((acc2) >> 17), pDst++);
-    arm_sqrt_q15((q15_t) ((acc3) >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    in1 = *__SIMD32(pSrc)++;
-    acc0 = __SMUAD(in1, in1);
-
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (acc0 >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  q15_t real, imag;                              /* Temporary variables to hold input values */
-
-  while(numSamples > 0u)
-  {
-    /* out = sqrt(real * real + imag * imag) */
-    real = *pSrc++;
-    imag = *pSrc++;
-
-    acc0 = (real * real);
-    acc1 = (imag * imag);
-
-    /* store the result in 2.14 format in the destination buffer. */
-    arm_sqrt_q15((q15_t) (((q63_t) acc0 + acc1) >> 17), pDst++);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of cmplx_mag group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c
deleted file mode 100644
index 59384f5dc3..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_q31.c
+++ /dev/null
@@ -1,177 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_q31.c    
-*    
-* Description:	Q31 complex magnitude    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**        
- * @ingroup groupCmplxMath        
- */
-
-/**        
- * @addtogroup cmplx_mag        
- * @{        
- */
-
-/**        
- * @brief  Q31 complex magnitude        
- * @param  *pSrc points to the complex input vector        
- * @param  *pDst points to the real output vector        
- * @param  numSamples number of complex samples in the input vector        
- * @return none.        
- *        
- * Scaling and Overflow Behavior:        
- * \par        
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 2.30 format.        
- * Input down scaling is not required.        
- */
-
-void arm_cmplx_mag_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t real, imag;                              /* Temporary variables to hold input values */
-  q31_t acc0, acc1;                              /* Accumulators */
-  uint32_t blkCnt;                               /* loop counter */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  q31_t real1, real2, imag1, imag2;              /* Temporary variables to hold input values */
-  q31_t out1, out2, out3, out4;                  /* Accumulators */
-  q63_t mul1, mul2, mul3, mul4;                  /* Temporary variables */
-
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* read complex input from source buffer */
-    real1 = pSrc[0];
-    imag1 = pSrc[1];
-    real2 = pSrc[2];
-    imag2 = pSrc[3];
-
-    /* calculate power of input values */
-    mul1 = (q63_t) real1 *real1;
-    mul2 = (q63_t) imag1 *imag1;
-    mul3 = (q63_t) real2 *real2;
-    mul4 = (q63_t) imag2 *imag2;
-
-    /* get the result to 3.29 format */
-    out1 = (q31_t) (mul1 >> 33);
-    out2 = (q31_t) (mul2 >> 33);
-    out3 = (q31_t) (mul3 >> 33);
-    out4 = (q31_t) (mul4 >> 33);
-
-    /* add real and imaginary accumulators */
-    out1 = out1 + out2;
-    out3 = out3 + out4;
-
-    /* read complex input from source buffer */
-    real1 = pSrc[4];
-    imag1 = pSrc[5];
-    real2 = pSrc[6];
-    imag2 = pSrc[7];
-
-    /* calculate square root */
-    arm_sqrt_q31(out1, &pDst[0]);
-
-    /* calculate power of input values */
-    mul1 = (q63_t) real1 *real1;
-
-    /* calculate square root */
-    arm_sqrt_q31(out3, &pDst[1]);
-
-    /* calculate power of input values */
-    mul2 = (q63_t) imag1 *imag1;
-    mul3 = (q63_t) real2 *real2;
-    mul4 = (q63_t) imag2 *imag2;
-
-    /* get the result to 3.29 format */
-    out1 = (q31_t) (mul1 >> 33);
-    out2 = (q31_t) (mul2 >> 33);
-    out3 = (q31_t) (mul3 >> 33);
-    out4 = (q31_t) (mul4 >> 33);
-
-    /* add real and imaginary accumulators */
-    out1 = out1 + out2;
-    out3 = out3 + out4;
-
-    /* calculate square root */
-    arm_sqrt_q31(out1, &pDst[2]);
-
-    /* increment destination by 8 to process next samples */
-    pSrc += 8u;
-
-    /* calculate square root */
-    arm_sqrt_q31(out3, &pDst[3]);
-
-    /* increment destination by 4 to process next samples */
-    pDst += 4u;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  blkCnt = numSamples;
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = sqrt(A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 2.30 format in the destination buffer. */
-    arm_sqrt_q31(acc0 + acc1, pDst++);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of cmplx_mag group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c
deleted file mode 100644
index 7350fd1c9a..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_f32.c
+++ /dev/null
@@ -1,207 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_squared_f32.c    
-*    
-* Description:	Floating-point complex magnitude squared.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-#include "arm_math.h"
-
-/**        
- * @ingroup groupCmplxMath        
- */
-
-/**        
- * @defgroup cmplx_mag_squared Complex Magnitude Squared        
- *        
- * Computes the magnitude squared of the elements of a complex data vector.        
- *       
- * The pSrc points to the source data and        
- * pDst points to the where the result should be written.        
- * numSamples specifies the number of complex samples        
- * in the input array and the data is stored in an interleaved fashion        
- * (real, imag, real, imag, ...).        
- * The input array has a total of 2*numSamples values;        
- * the output array has a total of numSamples values.        
- *        
- * The underlying algorithm is used:        
- *        
- * 
        
- * for(n=0; n        
- *        
- * There are separate functions for floating-point, Q15, and Q31 data types.        
- */
-
-/**        
- * @addtogroup cmplx_mag_squared        
- * @{        
- */
-
-
-/**        
- * @brief  Floating-point complex magnitude squared        
- * @param[in]  *pSrc points to the complex input vector        
- * @param[out]  *pDst points to the real output vector        
- * @param[in]  numSamples number of complex samples in the input vector        
- * @return none.        
- */
-
-void arm_cmplx_mag_squared_f32(
-  float32_t * pSrc,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t real, imag;                          /* Temporary variables to store real and imaginary values */
-  uint32_t blkCnt;                               /* loop counter */
-
-#ifndef ARM_MATH_CM0
-  float32_t real1, real2, real3, real4;          /* Temporary variables to hold real values */
-  float32_t imag1, imag2, imag3, imag4;          /* Temporary variables to hold imaginary values */
-  float32_t mul1, mul2, mul3, mul4;              /* Temporary variables */
-  float32_t mul5, mul6, mul7, mul8;              /* Temporary variables */
-  float32_t out1, out2, out3, out4;              /* Temporary variables to hold output values */
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    /* read real input sample from source buffer */
-    real1 = pSrc[0];
-    /* read imaginary input sample from source buffer */
-    imag1 = pSrc[1];
-
-    /* calculate power of real value */
-    mul1 = real1 * real1;
-
-    /* read real input sample from source buffer */
-    real2 = pSrc[2];
-
-    /* calculate power of imaginary value */
-    mul2 = imag1 * imag1;
-
-    /* read imaginary input sample from source buffer */
-    imag2 = pSrc[3];
-
-    /* calculate power of real value */
-    mul3 = real2 * real2;
-
-    /* read real input sample from source buffer */
-    real3 = pSrc[4];
-
-    /* calculate power of imaginary value */
-    mul4 = imag2 * imag2;
-
-    /* read imaginary input sample from source buffer */
-    imag3 = pSrc[5];
-
-    /* calculate power of real value */
-    mul5 = real3 * real3;
-    /* calculate power of imaginary value */
-    mul6 = imag3 * imag3;
-
-    /* read real input sample from source buffer */
-    real4 = pSrc[6];
-
-    /* accumulate real and imaginary powers */
-    out1 = mul1 + mul2;
-
-    /* read imaginary input sample from source buffer */
-    imag4 = pSrc[7];
-
-    /* accumulate real and imaginary powers */
-    out2 = mul3 + mul4;
-
-    /* calculate power of real value */
-    mul7 = real4 * real4;
-    /* calculate power of imaginary value */
-    mul8 = imag4 * imag4;
-
-    /* store output to destination */
-    pDst[0] = out1;
-
-    /* accumulate real and imaginary powers */
-    out3 = mul5 + mul6;
-
-    /* store output to destination */
-    pDst[1] = out2;
-
-    /* accumulate real and imaginary powers */
-    out4 = mul7 + mul8;
-
-    /* store output to destination */
-    pDst[2] = out3;
-
-    /* increment destination pointer by 8 to process next samples */
-    pSrc += 8u;
-
-    /* store output to destination */
-    pDst[3] = out4;
-
-    /* increment destination pointer by 4 to process next samples */
-    pDst += 4u;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  blkCnt = numSamples;
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-
-    /* out = (real * real) + (imag * imag) */
-    /* store the result in the destination buffer. */
-    *pDst++ = (real * real) + (imag * imag);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of cmplx_mag_squared group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c
deleted file mode 100644
index 623229b8f7..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q15.c
+++ /dev/null
@@ -1,140 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_squared_q15.c    
-*    
-* Description:	Q15 complex magnitude squared.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_mag_squared    
- * @{    
- */
-
-/**    
- * @brief  Q15 complex magnitude squared    
- * @param  *pSrc points to the complex input vector    
- * @param  *pDst points to the real output vector    
- * @param  numSamples number of complex samples in the input vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.    
- */
-
-void arm_cmplx_mag_squared_q15(
-  q15_t * pSrc,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-  q31_t in1, in2, in3, in4;
-  q31_t acc2, acc3;
-
-  /*loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    in1 = *__SIMD32(pSrc)++;
-    in2 = *__SIMD32(pSrc)++;
-    in3 = *__SIMD32(pSrc)++;
-    in4 = *__SIMD32(pSrc)++;
-
-    acc0 = __SMUAD(in1, in1);
-    acc1 = __SMUAD(in2, in2);
-    acc2 = __SMUAD(in3, in3);
-    acc3 = __SMUAD(in4, in4);
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (acc0 >> 17);
-    *pDst++ = (q15_t) (acc1 >> 17);
-    *pDst++ = (q15_t) (acc2 >> 17);
-    *pDst++ = (q15_t) (acc3 >> 17);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    in1 = *__SIMD32(pSrc)++;
-    acc0 = __SMUAD(in1, in1);
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (acc0 >> 17);
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  q15_t real, imag;                              /* Temporary variables to store real and imaginary values */
-
-  while(numSamples > 0u)
-  {
-    /* out = ((real * real) + (imag * imag)) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (real * real);
-    acc1 = (imag * imag);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ = (q15_t) (((q63_t) acc0 + acc1) >> 17);
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of cmplx_mag_squared group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c
deleted file mode 100644
index d45ccfab2f..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mag_squared_q31.c
+++ /dev/null
@@ -1,153 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_cmplx_mag_squared_q31.c    
-*    
-* Description:	Q31 complex magnitude squared.    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ---------------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup cmplx_mag_squared    
- * @{    
- */
-
-
-/**    
- * @brief  Q31 complex magnitude squared    
- * @param  *pSrc points to the complex input vector    
- * @param  *pDst points to the real output vector    
- * @param  numSamples number of complex samples in the input vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.    
- * Input down scaling is not required.    
- */
-
-void arm_cmplx_mag_squared_q31(
-  q31_t * pSrc,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t real, imag;                              /* Temporary variables to store real and imaginary values */
-  q31_t acc0, acc1;                              /* Accumulators */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counter */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[0] = (A[0] * A[0] + A[1] * A[1]) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* out = ((real * real) + (imag * imag)) */
-    real = *pSrc++;
-    imag = *pSrc++;
-    acc0 = (q31_t) (((q63_t) real * real) >> 33);
-    acc1 = (q31_t) (((q63_t) imag * imag) >> 33);
-    /* store the result in 3.29 format in the destination buffer. */
-    *pDst++ = acc0 + acc1;
-
-    /* Decrement the loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of cmplx_mag_squared group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c
deleted file mode 100644
index 2ec9ee862b..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_f32.c
+++ /dev/null
@@ -1,199 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_cmplx_f32.c    
-*    
-* Description:	Floating-point complex-by-complex multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-#include "arm_math.h"
-
-/**        
- * @ingroup groupCmplxMath        
- */
-
-/**        
- * @defgroup CmplxByCmplxMult Complex-by-Complex Multiplication        
- *        
- * Multiplies a complex vector by another complex vector and generates a complex result.        
- * The data in the complex arrays is stored in an interleaved fashion        
- * (real, imag, real, imag, ...).        
- * The parameter numSamples represents the number of complex        
- * samples processed.  The complex arrays have a total of 2*numSamples        
- * real values.        
- *        
- * The underlying algorithm is used:        
- *        
- * 
        
- * for(n=0; n        
- *        
- * There are separate functions for floating-point, Q15, and Q31 data types.        
- */
-
-/**        
- * @addtogroup CmplxByCmplxMult        
- * @{        
- */
-
-
-/**        
- * @brief  Floating-point complex-by-complex multiplication        
- * @param[in]  *pSrcA points to the first input vector        
- * @param[in]  *pSrcB points to the second input vector        
- * @param[out]  *pDst  points to the output vector        
- * @param[in]  numSamples number of complex samples in each vector        
- * @return none.        
- */
-
-void arm_cmplx_mult_cmplx_f32(
-  float32_t * pSrcA,
-  float32_t * pSrcB,
-  float32_t * pDst,
-  uint32_t numSamples)
-{
-  float32_t a1, b1, c1, d1;                      /* Temporary variables to store real and imaginary values */
-  uint32_t blkCnt;                               /* loop counters */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  float32_t a2, b2, c2, d2;                      /* Temporary variables to store real and imaginary values */
-  float32_t acc1, acc2, acc3, acc4;
-
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a1 = *pSrcA;                /* A[2 * i] */
-    c1 = *pSrcB;                /* B[2 * i] */
-
-    b1 = *(pSrcA + 1);          /* A[2 * i + 1] */
-    acc1 = a1 * c1;             /* acc1 = A[2 * i] * B[2 * i] */
-
-    a2 = *(pSrcA + 2);          /* A[2 * i + 2] */
-    acc2 = (b1 * c1);           /* acc2 = A[2 * i + 1] * B[2 * i] */
-
-    d1 = *(pSrcB + 1);          /* B[2 * i + 1] */
-    c2 = *(pSrcB + 2);          /* B[2 * i + 2] */
-    acc1 -= b1 * d1;            /* acc1 =      A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1] */
-
-    d2 = *(pSrcB + 3);          /* B[2 * i + 3] */
-    acc3 = a2 * c2;             /* acc3 =       A[2 * i + 2] * B[2 * i + 2] */
-
-    b2 = *(pSrcA + 3);          /* A[2 * i + 3] */
-    acc2 += (a1 * d1);          /* acc2 =      A[2 * i + 1] * B[2 * i] + A[2 * i] * B[2 * i + 1] */
-
-    a1 = *(pSrcA + 4);          /* A[2 * i + 4] */
-    acc4 = (a2 * d2);           /* acc4 =   A[2 * i + 2] * B[2 * i + 3] */
-
-    c1 = *(pSrcB + 4);          /* B[2 * i + 4] */
-    acc3 -= (b2 * d2);          /* acc3 =       A[2 * i + 2] * B[2 * i + 2] - A[2 * i + 3] * B[2 * i + 3] */
-    *pDst = acc1;               /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1] */
-
-    b1 = *(pSrcA + 5);          /* A[2 * i + 5] */
-    acc4 += b2 * c2;            /* acc4 =   A[2 * i + 2] * B[2 * i + 3] + A[2 * i + 3] * B[2 * i + 2] */
-
-    *(pDst + 1) = acc2;         /* C[2 * i + 1] = A[2 * i + 1] * B[2 * i] + A[2 * i] * B[2 * i + 1]  */
-    acc1 = (a1 * c1);
-
-    d1 = *(pSrcB + 5);
-    acc2 = (b1 * c1);
-
-    *(pDst + 2) = acc3;
-    *(pDst + 3) = acc4;
-
-    a2 = *(pSrcA + 6);
-    acc1 -= (b1 * d1);
-
-    c2 = *(pSrcB + 6);
-    acc2 += (a1 * d1);
-
-    b2 = *(pSrcA + 7);
-    acc3 = (a2 * c2);
-
-    d2 = *(pSrcB + 7);
-    acc4 = (b2 * c2);
-
-    *(pDst + 4) = acc1;
-    pSrcA += 8u;
-
-    acc3 -= (b2 * d2);
-    acc4 += (a2 * d2);
-
-    *(pDst + 5) = acc2;
-    pSrcB += 8u;
-
-    *(pDst + 6) = acc3;
-    *(pDst + 7) = acc4;
-
-    pDst += 8u;
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  blkCnt = numSamples;
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a1 = *pSrcA++;
-    b1 = *pSrcA++;
-    c1 = *pSrcB++;
-    d1 = *pSrcB++;
-
-    /* store the result in the destination buffer. */
-    *pDst++ = (a1 * c1) - (b1 * d1);
-    *pDst++ = (a1 * d1) + (b1 * c1);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of CmplxByCmplxMult group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c
deleted file mode 100644
index 0219aea48a..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q15.c
+++ /dev/null
@@ -1,185 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_cmplx_q15.c    
-*    
-* Description:	Q15 complex-by-complex multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup CmplxByCmplxMult    
- * @{    
- */
-
-/**    
- * @brief  Q15 complex-by-complex multiplication    
- * @param[in]  *pSrcA points to the first input vector    
- * @param[in]  *pSrcB points to the second input vector    
- * @param[out]  *pDst  points to the output vector    
- * @param[in]  numSamples number of complex samples in each vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function implements 1.15 by 1.15 multiplications and finally output is converted into 3.13 format.    
- */
-
-void arm_cmplx_mult_cmplx_q15(
-  q15_t * pSrcA,
-  q15_t * pSrcB,
-  q15_t * pDst,
-  uint32_t numSamples)
-{
-  q15_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * c) >> 17) - (((q31_t) b * d) >> 17);
-    /* store the result in 3.13 format in the destination buffer. */
-    *pDst++ =
-      (q15_t) (q31_t) (((q31_t) a * d) >> 17) + (((q31_t) b * c) >> 17);
-
-    /* Decrement the blockSize loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of CmplxByCmplxMult group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c
deleted file mode 100644
index 13fc060a2e..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_cmplx_q31.c
+++ /dev/null
@@ -1,318 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_cmplx_q31.c    
-*    
-* Description:	Q31 complex-by-complex multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup CmplxByCmplxMult    
- * @{    
- */
-
-
-/**    
- * @brief  Q31 complex-by-complex multiplication    
- * @param[in]  *pSrcA points to the first input vector    
- * @param[in]  *pSrcB points to the second input vector    
- * @param[out]  *pDst  points to the output vector    
- * @param[in]  numSamples number of complex samples in each vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function implements 1.31 by 1.31 multiplications and finally output is converted into 3.29 format.    
- * Input down scaling is not required.    
- */
-
-void arm_cmplx_mult_cmplx_q31(
-  q31_t * pSrcA,
-  q31_t * pSrcB,
-  q31_t * pDst,
-  uint32_t numSamples)
-{
-  q31_t a, b, c, d;                              /* Temporary variables to store real and imaginary values */
-  uint32_t blkCnt;                               /* loop counters */
-  q31_t mul1, mul2, mul3, mul4;
-  q31_t out1, out2;
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 1u;
-
-  /* First part of the processing with loop unrolling.  Compute 2 outputs at a time.     
-   ** a second loop below computes the remaining 1 sample. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-  /* If the blockSize is not a multiple of 2, compute any remaining output samples here.     
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x2u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[2 * i] - A[2 * i + 1] * B[2 * i + 1].  */
-    /* C[2 * i + 1] = A[2 * i] * B[2 * i + 1] + A[2 * i + 1] * B[2 * i].  */
-    a = *pSrcA++;
-    b = *pSrcA++;
-    c = *pSrcB++;
-    d = *pSrcB++;
-
-    mul1 = (q31_t) (((q63_t) a * c) >> 32);
-    mul2 = (q31_t) (((q63_t) b * d) >> 32);
-    mul3 = (q31_t) (((q63_t) a * d) >> 32);
-    mul4 = (q31_t) (((q63_t) b * c) >> 32);
-
-    mul1 = (mul1 >> 1);
-    mul2 = (mul2 >> 1);
-    mul3 = (mul3 >> 1);
-    mul4 = (mul4 >> 1);
-
-    out1 = mul1 - mul2;
-    out2 = mul3 + mul4;
-
-    /* store the real result in 3.29 format in the destination buffer. */
-    *pDst++ = out1;
-    /* store the imag result in 3.29 format in the destination buffer. */
-    *pDst++ = out2;
-
-    /* Decrement the blockSize loop counter */
-    blkCnt--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of CmplxByCmplxMult group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c
deleted file mode 100644
index 7a5bdf9cda..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_f32.c
+++ /dev/null
@@ -1,217 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_real_f32.c    
-*    
-* Description:	Floating-point complex by real multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**        
- * @ingroup groupCmplxMath        
- */
-
-/**        
- * @defgroup CmplxByRealMult Complex-by-Real Multiplication        
- *        
- * Multiplies a complex vector by a real vector and generates a complex result.        
- * The data in the complex arrays is stored in an interleaved fashion        
- * (real, imag, real, imag, ...).        
- * The parameter numSamples represents the number of complex        
- * samples processed.  The complex arrays have a total of 2*numSamples        
- * real values while the real array has a total of numSamples        
- * real values.        
- *        
- * The underlying algorithm is used:        
- *        
- * 
        
- * for(n=0; n        
- *        
- * There are separate functions for floating-point, Q15, and Q31 data types.        
- */
-
-/**        
- * @addtogroup CmplxByRealMult        
- * @{        
- */
-
-
-/**        
- * @brief  Floating-point complex-by-real multiplication        
- * @param[in]  *pSrcCmplx points to the complex input vector        
- * @param[in]  *pSrcReal points to the real input vector        
- * @param[out]  *pCmplxDst points to the complex output vector        
- * @param[in]  numSamples number of samples in each vector        
- * @return none.        
- */
-
-void arm_cmplx_mult_real_f32(
-  float32_t * pSrcCmplx,
-  float32_t * pSrcReal,
-  float32_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  float32_t in;                                  /* Temporary variable to store input value */
-  uint32_t blkCnt;                               /* loop counters */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  float32_t inA1, inA2, inA3, inA4;              /* Temporary variables to hold input data */
-  float32_t inA5, inA6, inA7, inA8;              /* Temporary variables to hold input data */
-  float32_t inB1, inB2, inB3, inB4;              /* Temporary variables to hold input data */
-  float32_t out1, out2, out3, out4;              /* Temporary variables to hold output data */
-  float32_t out5, out6, out7, out8;              /* Temporary variables to hold output data */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.        
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    /* read input from complex input buffer */
-    inA1 = pSrcCmplx[0];
-    inA2 = pSrcCmplx[1];
-    /* read input from real input buffer */
-    inB1 = pSrcReal[0];
-
-    /* read input from complex input buffer */
-    inA3 = pSrcCmplx[2];
-
-    /* multiply complex buffer real input with real buffer input */
-    out1 = inA1 * inB1;
-
-    /* read input from complex input buffer */
-    inA4 = pSrcCmplx[3];
-
-    /* multiply complex buffer imaginary input with real buffer input */
-    out2 = inA2 * inB1;
-
-    /* read input from real input buffer */
-    inB2 = pSrcReal[1];
-    /* read input from complex input buffer */
-    inA5 = pSrcCmplx[4];
-
-    /* multiply complex buffer real input with real buffer input */
-    out3 = inA3 * inB2;
-
-    /* read input from complex input buffer */
-    inA6 = pSrcCmplx[5];
-    /* read input from real input buffer */
-    inB3 = pSrcReal[2];
-
-    /* multiply complex buffer imaginary input with real buffer input */
-    out4 = inA4 * inB2;
-
-    /* read input from complex input buffer */
-    inA7 = pSrcCmplx[6];
-
-    /* multiply complex buffer real input with real buffer input */
-    out5 = inA5 * inB3;
-
-    /* read input from complex input buffer */
-    inA8 = pSrcCmplx[7];
-
-    /* multiply complex buffer imaginary input with real buffer input */
-    out6 = inA6 * inB3;
-
-    /* read input from real input buffer */
-    inB4 = pSrcReal[3];
-
-    /* store result to destination bufer */
-    pCmplxDst[0] = out1;
-
-    /* multiply complex buffer real input with real buffer input */
-    out7 = inA7 * inB4;
-
-    /* store result to destination bufer */
-    pCmplxDst[1] = out2;
-
-    /* multiply complex buffer imaginary input with real buffer input */
-    out8 = inA8 * inB4;
-
-    /* store result to destination bufer */
-    pCmplxDst[2] = out3;
-    pCmplxDst[3] = out4;
-    pCmplxDst[4] = out5;
-
-    /* incremnet complex input buffer by 8 to process next samples */
-    pSrcCmplx += 8u;
-
-    /* store result to destination bufer */
-    pCmplxDst[5] = out6;
-
-    /* increment real input buffer by 4 to process next samples */
-    pSrcReal += 4u;
-
-    /* store result to destination bufer */
-    pCmplxDst[6] = out7;
-    pCmplxDst[7] = out8;
-
-    /* increment destination buffer by 8 to process next sampels */
-    pCmplxDst += 8u;
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.        
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-  blkCnt = numSamples;
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-    *pCmplxDst++ = (*pSrcCmplx++) * (in);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-}
-
-/**        
- * @} end of CmplxByRealMult group        
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c
deleted file mode 100644
index a44158c4ff..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q15.c
+++ /dev/null
@@ -1,195 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_real_q15.c    
-*    
-* Description:	Q15 complex by real multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup CmplxByRealMult    
- * @{    
- */
-
-
-/**    
- * @brief  Q15 complex-by-real multiplication    
- * @param[in]  *pSrcCmplx points to the complex input vector    
- * @param[in]  *pSrcReal points to the real input vector    
- * @param[out]  *pCmplxDst points to the complex output vector    
- * @param[in]  numSamples number of samples in each vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function uses saturating arithmetic.    
- * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated.    
- */
-
-void arm_cmplx_mult_real_q15(
-  q15_t * pSrcCmplx,
-  q15_t * pSrcReal,
-  q15_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  q15_t in;                                      /* Temporary variable to store input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-  q31_t inA1, inA2;                              /* Temporary variables to hold input data */
-  q31_t inB1;                                    /* Temporary variables to hold input data */
-  q15_t out1, out2, out3, out4;                  /* Temporary variables to hold output data */
-  q31_t mul1, mul2, mul3, mul4;                  /* Temporary variables to hold intermediate data */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    /* read complex number both real and imaginary from complex input buffer */
-    inA1 = *__SIMD32(pSrcCmplx)++;
-    /* read two real values at a time from real input buffer */
-    inB1 = *__SIMD32(pSrcReal)++;
-    /* read complex number both real and imaginary from complex input buffer */
-    inA2 = *__SIMD32(pSrcCmplx)++;
-
-    /* multiply complex number with real numbers */
-#ifndef ARM_MATH_BIG_ENDIAN
-
-    mul1 = (q31_t) ((q15_t) (inA1) * (q15_t) (inB1));
-    mul2 = (q31_t) ((q15_t) (inA1 >> 16) * (q15_t) (inB1));
-    mul3 = (q31_t) ((q15_t) (inA2) * (q15_t) (inB1 >> 16));
-    mul4 = (q31_t) ((q15_t) (inA2 >> 16) * (q15_t) (inB1 >> 16));
-
-#else
-
-    mul2 = (q31_t) ((q15_t) (inA1 >> 16) * (q15_t) (inB1 >> 16));
-    mul1 = (q31_t) ((q15_t) inA1 * (q15_t) (inB1 >> 16));
-    mul4 = (q31_t) ((q15_t) (inA2 >> 16) * (q15_t) inB1);
-    mul3 = (q31_t) ((q15_t) inA2 * (q15_t) inB1);
-
-#endif //      #ifndef ARM_MATH_BIG_ENDIAN
-
-    /* saturate the result */
-    out1 = (q15_t) __SSAT(mul1 >> 15u, 16);
-    out2 = (q15_t) __SSAT(mul2 >> 15u, 16);
-    out3 = (q15_t) __SSAT(mul3 >> 15u, 16);
-    out4 = (q15_t) __SSAT(mul4 >> 15u, 16);
-
-    /* pack real and imaginary outputs and store them to destination */
-    *__SIMD32(pCmplxDst)++ = __PKHBT(out1, out2, 16);
-    *__SIMD32(pCmplxDst)++ = __PKHBT(out3, out4, 16);
-
-    inA1 = *__SIMD32(pSrcCmplx)++;
-    inB1 = *__SIMD32(pSrcReal)++;
-    inA2 = *__SIMD32(pSrcCmplx)++;
-
-#ifndef ARM_MATH_BIG_ENDIAN
-
-    mul1 = (q31_t) ((q15_t) (inA1) * (q15_t) (inB1));
-    mul2 = (q31_t) ((q15_t) (inA1 >> 16) * (q15_t) (inB1));
-    mul3 = (q31_t) ((q15_t) (inA2) * (q15_t) (inB1 >> 16));
-    mul4 = (q31_t) ((q15_t) (inA2 >> 16) * (q15_t) (inB1 >> 16));
-
-#else
-
-    mul2 = (q31_t) ((q15_t) (inA1 >> 16) * (q15_t) (inB1 >> 16));
-    mul1 = (q31_t) ((q15_t) inA1 * (q15_t) (inB1 >> 16));
-    mul4 = (q31_t) ((q15_t) (inA2 >> 16) * (q15_t) inB1);
-    mul3 = (q31_t) ((q15_t) inA2 * (q15_t) inB1);
-
-#endif //      #ifndef ARM_MATH_BIG_ENDIAN
-
-    out1 = (q15_t) __SSAT(mul1 >> 15u, 16);
-    out2 = (q15_t) __SSAT(mul2 >> 15u, 16);
-    out3 = (q15_t) __SSAT(mul3 >> 15u, 16);
-    out4 = (q15_t) __SSAT(mul4 >> 15u, 16);
-
-    *__SIMD32(pCmplxDst)++ = __PKHBT(out1, out2, 16);
-    *__SIMD32(pCmplxDst)++ = __PKHBT(out3, out4, 16);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut = realA * realB.            */
-    /* imagOut = imagA * realB.                */
-    in = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-    *pCmplxDst++ =
-      (q15_t) __SSAT((((q31_t) (*pSrcCmplx++) * (in)) >> 15), 16);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of CmplxByRealMult group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c
deleted file mode 100644
index b286acdb6d..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ComplexMathFunctions/arm_cmplx_mult_real_q31.c
+++ /dev/null
@@ -1,215 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_cmplx_mult_real_q31.c    
-*    
-* Description:	Q31 complex by real multiplication    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupCmplxMath    
- */
-
-/**    
- * @addtogroup CmplxByRealMult    
- * @{    
- */
-
-
-/**    
- * @brief  Q31 complex-by-real multiplication    
- * @param[in]  *pSrcCmplx points to the complex input vector    
- * @param[in]  *pSrcReal points to the real input vector    
- * @param[out]  *pCmplxDst points to the complex output vector    
- * @param[in]  numSamples number of samples in each vector    
- * @return none.    
- *    
- * Scaling and Overflow Behavior:    
- * \par    
- * The function uses saturating arithmetic.    
- * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated.    
- */
-
-void arm_cmplx_mult_real_q31(
-  q31_t * pSrcCmplx,
-  q31_t * pSrcReal,
-  q31_t * pCmplxDst,
-  uint32_t numSamples)
-{
-  q31_t inA1;                                    /* Temporary variable to store input value */
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-  uint32_t blkCnt;                               /* loop counters */
-  q31_t inA2, inA3, inA4;                        /* Temporary variables to hold input data */
-  q31_t inB1, inB2;                              /* Temporary variabels to hold input data */
-  q31_t out1, out2, out3, out4;                  /* Temporary variables to hold output data */
-
-  /* loop Unrolling */
-  blkCnt = numSamples >> 2u;
-
-  /* First part of the processing with loop unrolling.  Compute 4 outputs at a time.    
-   ** a second loop below computes the remaining 1 to 3 samples. */
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    /* read real input from complex input buffer */
-    inA1 = *pSrcCmplx++;
-    inA2 = *pSrcCmplx++;
-    /* read input from real input bufer */
-    inB1 = *pSrcReal++;
-    inB2 = *pSrcReal++;
-    /* read imaginary input from complex input buffer */
-    inA3 = *pSrcCmplx++;
-    inA4 = *pSrcCmplx++;
-
-    /* multiply complex input with real input */
-    out1 = ((q63_t) inA1 * inB1) >> 32;
-    out2 = ((q63_t) inA2 * inB1) >> 32;
-    out3 = ((q63_t) inA3 * inB2) >> 32;
-    out4 = ((q63_t) inA4 * inB2) >> 32;
-
-    /* sature the result */
-    out1 = __SSAT(out1, 31);
-    out2 = __SSAT(out2, 31);
-    out3 = __SSAT(out3, 31);
-    out4 = __SSAT(out4, 31);
-
-    /* get result in 1.31 format */
-    out1 = out1 << 1;
-    out2 = out2 << 1;
-    out3 = out3 << 1;
-    out4 = out4 << 1;
-
-    /* store the result to destination buffer */
-    *pCmplxDst++ = out1;
-    *pCmplxDst++ = out2;
-    *pCmplxDst++ = out3;
-    *pCmplxDst++ = out4;
-
-    /* read real input from complex input buffer */
-    inA1 = *pSrcCmplx++;
-    inA2 = *pSrcCmplx++;
-    /* read input from real input bufer */
-    inB1 = *pSrcReal++;
-    inB2 = *pSrcReal++;
-    /* read imaginary input from complex input buffer */
-    inA3 = *pSrcCmplx++;
-    inA4 = *pSrcCmplx++;
-
-    /* multiply complex input with real input */
-    out1 = ((q63_t) inA1 * inB1) >> 32;
-    out2 = ((q63_t) inA2 * inB1) >> 32;
-    out3 = ((q63_t) inA3 * inB2) >> 32;
-    out4 = ((q63_t) inA4 * inB2) >> 32;
-
-    /* sature the result */
-    out1 = __SSAT(out1, 31);
-    out2 = __SSAT(out2, 31);
-    out3 = __SSAT(out3, 31);
-    out4 = __SSAT(out4, 31);
-
-    /* get result in 1.31 format */
-    out1 = out1 << 1;
-    out2 = out2 << 1;
-    out3 = out3 << 1;
-    out4 = out4 << 1;
-
-    /* store the result to destination buffer */
-    *pCmplxDst++ = out1;
-    *pCmplxDst++ = out2;
-    *pCmplxDst++ = out3;
-    *pCmplxDst++ = out4;
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-  /* If the numSamples is not a multiple of 4, compute any remaining output samples here.    
-   ** No loop unrolling is used. */
-  blkCnt = numSamples % 0x4u;
-
-  while(blkCnt > 0u)
-  {
-    /* C[2 * i] = A[2 * i] * B[i].            */
-    /* C[2 * i + 1] = A[2 * i + 1] * B[i].        */
-    /* read real input from complex input buffer */
-    inA1 = *pSrcCmplx++;
-    inA2 = *pSrcCmplx++;
-    /* read input from real input bufer */
-    inB1 = *pSrcReal++;
-
-    /* multiply complex input with real input */
-    out1 = ((q63_t) inA1 * inB1) >> 32;
-    out2 = ((q63_t) inA2 * inB1) >> 32;
-
-    /* sature the result */
-    out1 = __SSAT(out1, 31);
-    out2 = __SSAT(out2, 31);
-
-    /* get result in 1.31 format */
-    out1 = out1 << 1;
-    out2 = out2 << 1;
-
-    /* store the result to destination buffer */
-    *pCmplxDst++ = out1;
-    *pCmplxDst++ = out2;
-
-    /* Decrement the numSamples loop counter */
-    blkCnt--;
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  while(numSamples > 0u)
-  {
-    /* realOut = realA * realB.            */
-    /* imagReal = imagA * realB.               */
-    inA1 = *pSrcReal++;
-    /* store the result in the destination buffer. */
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * inA1) >> 31);
-    *pCmplxDst++ =
-      (q31_t) clip_q63_to_q31(((q63_t) * pSrcCmplx++ * inA1) >> 31);
-
-    /* Decrement the numSamples loop counter */
-    numSamples--;
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of CmplxByRealMult group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c
deleted file mode 100644
index 37e48f609b..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_f32.c
+++ /dev/null
@@ -1,79 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_init_f32.c    
-*    
-* Description:	Floating-point PID Control initialization function    
-*				   
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
- * @brief  Initialization function for the floating-point PID Control.   
- * @param[in,out] *S points to an instance of the PID structure.   
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state & 1 = reset the state.   
- * @return none.   
- * \par Description:   
- * \par    
- * The resetStateFlag specifies whether to set state to zero or not. \n   
- * The function computes the structure fields: A0, A1 A2    
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)    
- * also sets the state variables to all zeros.    
- */
-
-void arm_pid_init_f32(
-  arm_pid_instance_f32 * S,
-  int32_t resetStateFlag)
-{
-
-  /* Derived coefficient A0 */
-  S->A0 = S->Kp + S->Ki + S->Kd;
-
-  /* Derived coefficient A1 */
-  S->A1 = (-S->Kp) - ((float32_t) 2.0 * S->Kd);
-
-  /* Derived coefficient A2 */
-  S->A2 = S->Kd;
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(float32_t));
-  }
-
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c
deleted file mode 100644
index 1816bc9aa1..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q15.c
+++ /dev/null
@@ -1,114 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_init_q15.c    
-*    
-* Description:	Q15 PID Control initialization function    
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
- * @details    
- * @param[in,out] *S points to an instance of the Q15 PID structure.    
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.    
- * @return none.    
- * \par Description:   
- * \par    
- * The resetStateFlag specifies whether to set state to zero or not. \n   
- * The function computes the structure fields: A0, A1 A2    
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)    
- * also sets the state variables to all zeros.    
- */
-
-void arm_pid_init_q15(
-  arm_pid_instance_q15 * S,
-  int32_t resetStateFlag)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* Derived coefficient A0 */
-  S->A0 = __QADD16(__QADD16(S->Kp, S->Ki), S->Kd);
-
-  /* Derived coefficients and pack into A1 */
-
-#ifndef  ARM_MATH_BIG_ENDIAN
-
-  S->A1 = __PKHBT(-__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), S->Kd, 16);
-
-#else
-
-  S->A1 = __PKHBT(S->Kd, -__QADD16(__QADD16(S->Kd, S->Kd), S->Kp), 16);
-
-#endif /*      #ifndef  ARM_MATH_BIG_ENDIAN    */
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q15_t));
-  }
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  q31_t temp;                                    /*to store the sum */
-
-  /* Derived coefficient A0 */
-  temp = S->Kp + S->Ki + S->Kd;
-  S->A0 = (q15_t) __SSAT(temp, 16);
-
-  /* Derived coefficients and pack into A1 */
-  temp = -(S->Kd + S->Kd + S->Kp);
-  S->A1 = (q15_t) __SSAT(temp, 16);
-  S->A2 = S->Kd;
-
-
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q15_t));
-  }
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c
deleted file mode 100644
index da40ce973d..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_init_q31.c
+++ /dev/null
@@ -1,99 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_init_q31.c    
-*    
-* Description:	Q31 PID Control initialization function     
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
- * @brief  Initialization function for the Q31 PID Control.   
- * @param[in,out] *S points to an instance of the Q31 PID structure.   
- * @param[in]     resetStateFlag  flag to reset the state. 0 = no change in state 1 = reset the state.   
- * @return none.    
- * \par Description:   
- * \par    
- * The resetStateFlag specifies whether to set state to zero or not. \n   
- * The function computes the structure fields: A0, A1 A2    
- * using the proportional gain( \c Kp), integral gain( \c Ki) and derivative gain( \c Kd)    
- * also sets the state variables to all zeros.    
- */
-
-void arm_pid_init_q31(
-  arm_pid_instance_q31 * S,
-  int32_t resetStateFlag)
-{
-
-#ifndef ARM_MATH_CM0
-
-  /* Run the below code for Cortex-M4 and Cortex-M3 */
-
-  /* Derived coefficient A0 */
-  S->A0 = __QADD(__QADD(S->Kp, S->Ki), S->Kd);
-
-  /* Derived coefficient A1 */
-  S->A1 = -__QADD(__QADD(S->Kd, S->Kd), S->Kp);
-
-
-#else
-
-  /* Run the below code for Cortex-M0 */
-
-  q31_t temp;
-
-  /* Derived coefficient A0 */
-  temp = clip_q63_to_q31((q63_t) S->Kp + S->Ki);
-  S->A0 = clip_q63_to_q31((q63_t) temp + S->Kd);
-
-  /* Derived coefficient A1 */
-  temp = clip_q63_to_q31((q63_t) S->Kd + S->Kd);
-  S->A1 = -clip_q63_to_q31((q63_t) temp + S->Kp);
-
-#endif /* #ifndef ARM_MATH_CM0 */
-
-  /* Derived coefficient A2 */
-  S->A2 = S->Kd;
-
-  /* Check whether state needs reset or not */
-  if(resetStateFlag)
-  {
-    /* Clear the state buffer.  The size will be always 3 samples */
-    memset(S->state, 0, 3u * sizeof(q31_t));
-  }
-
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c
deleted file mode 100644
index 491ad5268b..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_f32.c
+++ /dev/null
@@ -1,57 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_reset_f32.c    
-*    
-* Description:	Floating-point PID Control reset function   
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
-* @brief  Reset function for the floating-point PID Control.   
-* @param[in] *S	Instance pointer of PID control data structure.   
-* @return none.    
-* \par Description:   
-* The function resets the state buffer to zeros.    
-*/
-void arm_pid_reset_f32(
-  arm_pid_instance_f32 * S)
-{
-
-  /* Clear the state buffer.  The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(float32_t));
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c
deleted file mode 100644
index dc00787460..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q15.c
+++ /dev/null
@@ -1,56 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_reset_q15.c    
-*    
-* Description:	Q15 PID Control reset function   
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
-* @brief  Reset function for the Q15 PID Control.   
-* @param[in] *S		Instance pointer of PID control data structure.   
-* @return none.    
-* \par Description:   
-* The function resets the state buffer to zeros.    
-*/
-void arm_pid_reset_q15(
-  arm_pid_instance_q15 * S)
-{
-  /* Reset state to zero, The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(q15_t));
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c
deleted file mode 100644
index b1ff753af3..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_pid_reset_q31.c
+++ /dev/null
@@ -1,57 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:	    arm_pid_reset_q31.c    
-*    
-* Description:	Q31 PID Control reset function   
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* ------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
- /**    
- * @addtogroup PID    
- * @{    
- */
-
-/**    
-* @brief  Reset function for the Q31 PID Control.   
-* @param[in] *S	Instance pointer of PID control data structure.   
-* @return none.    
-* \par Description:   
-* The function resets the state buffer to zeros.    
-*/
-void arm_pid_reset_q31(
-  arm_pid_instance_q31 * S)
-{
-
-  /* Clear the state buffer.  The size will be always 3 samples */
-  memset(S->state, 0, 3u * sizeof(q31_t));
-}
-
-/**    
- * @} end of PID group    
- */
diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c
deleted file mode 100644
index 1679a780c7..0000000000
--- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_f32.c
+++ /dev/null
@@ -1,428 +0,0 @@
-/* ----------------------------------------------------------------------    
-* Copyright (C) 2010 ARM Limited. All rights reserved.    
-*    
-* $Date:        15. February 2012  
-* $Revision: 	V1.1.0  
-*    
-* Project: 	    CMSIS DSP Library    
-* Title:		arm_sin_cos_f32.c    
-*    
-* Description:	Sine and Cosine calculation for floating-point values.   
-*    
-* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
-*  
-* Version 1.1.0 2012/02/15 
-*    Updated with more optimizations, bug fixes and minor API changes.  
-*   
-* Version 1.0.10 2011/7/15  
-*    Big Endian support added and Merged M0 and M3/M4 Source code.   
-*    
-* Version 1.0.3 2010/11/29   
-*    Re-organized the CMSIS folders and updated documentation.    
-*     
-* Version 1.0.2 2010/11/11    
-*    Documentation updated.     
-*    
-* Version 1.0.1 2010/10/05     
-*    Production release and review comments incorporated.    
-*    
-* Version 1.0.0 2010/09/20     
-*    Production release and review comments incorporated.    
-* -------------------------------------------------------------------- */
-
-#include "arm_math.h"
-
-/**    
- * @ingroup groupController    
- */
-
-/**    
- * @defgroup SinCos Sine Cosine   
- *    
- * Computes the trigonometric sine and cosine values using a combination of table lookup   
- * and linear interpolation.     
- * There are separate functions for Q31 and floating-point data types.   
- * The input to the floating-point version is in degrees while the   
- * fixed-point Q31 have a scaled input with the range   
- * [-1 0.9999] mapping to [-180 179] degrees.   
- *   
- * The implementation is based on table lookup using 360 values together with linear interpolation.   
- * The steps used are:   
- *  -# Calculation of the nearest integer table index.   
- *  -# Compute the fractional portion (fract) of the input.   
- *  -# Fetch the value corresponding to \c index from sine table to \c y0 and also value from \c index+1 to \c y1.      
- *  -# Sine value is computed as  *psinVal = y0 + (fract * (y1 - y0)).    
- *  -# Fetch the value corresponding to \c index from cosine table to \c y0 and also value from \c index+1 to \c y1.      
- *  -# Cosine value is computed as  *pcosVal = y0 + (fract * (y1 - y0)).    
- */
-
- /**    
- * @addtogroup SinCos    
- * @{    
- */
-
-
-/**    
-* \par    
-* Cosine Table is generated from following loop    
-* 
for(i = 0; i < 360; i++)    
-* {    
-*    cosTable[i]= cos((i-180) * PI/180.0);    
-* } 
-*/ - -static const float32_t cosTable[360] = { - -0.999847695156391270f, -0.999390827019095760f, -0.998629534754573830f, - -0.997564050259824200f, -0.996194698091745550f, -0.994521895368273290f, - -0.992546151641321980f, -0.990268068741570250f, - -0.987688340595137660f, -0.984807753012208020f, -0.981627183447663980f, - -0.978147600733805690f, -0.974370064785235250f, -0.970295726275996470f, - -0.965925826289068200f, -0.961261695938318670f, - -0.956304755963035440f, -0.951056516295153530f, -0.945518575599316740f, - -0.939692620785908320f, -0.933580426497201740f, -0.927183854566787310f, - -0.920504853452440150f, -0.913545457642600760f, - -0.906307787036649940f, -0.898794046299167040f, -0.891006524188367790f, - -0.882947592858926770f, -0.874619707139395740f, -0.866025403784438710f, - -0.857167300702112220f, -0.848048096156425960f, - -0.838670567945424160f, -0.829037572555041620f, -0.819152044288991580f, - -0.809016994374947340f, -0.798635510047292940f, -0.788010753606721900f, - -0.777145961456970680f, -0.766044443118977900f, - -0.754709580222772010f, -0.743144825477394130f, -0.731353701619170460f, - -0.719339800338651300f, -0.707106781186547460f, -0.694658370458997030f, - -0.681998360062498370f, -0.669130606358858240f, - -0.656059028990507500f, -0.642787609686539360f, -0.629320391049837280f, - -0.615661475325658290f, -0.601815023152048380f, -0.587785252292473030f, - -0.573576436351045830f, -0.559192903470746680f, - -0.544639035015027080f, -0.529919264233204790f, -0.515038074910054270f, - -0.499999999999999780f, -0.484809620246337000f, -0.469471562785890530f, - -0.453990499739546750f, -0.438371146789077510f, - -0.422618261740699330f, -0.406736643075800100f, -0.390731128489273600f, - -0.374606593415912070f, -0.358367949545300270f, -0.342020143325668710f, - -0.325568154457156420f, -0.309016994374947340f, - -0.292371704722736660f, -0.275637355816999050f, -0.258819045102520850f, - -0.241921895599667790f, -0.224951054343864810f, -0.207911690817759120f, - -0.190808995376544800f, -0.173648177666930300f, - -0.156434465040231040f, -0.139173100960065350f, -0.121869343405147370f, - -0.104528463267653330f, -0.087155742747658235f, -0.069756473744125330f, - -0.052335956242943620f, -0.034899496702500733f, - -0.017452406437283477f, 0.000000000000000061f, 0.017452406437283376f, - 0.034899496702501080f, 0.052335956242943966f, 0.069756473744125455f, - 0.087155742747658138f, 0.104528463267653460f, - 0.121869343405147490f, 0.139173100960065690f, 0.156434465040230920f, - 0.173648177666930410f, 0.190808995376544920f, 0.207911690817759450f, - 0.224951054343864920f, 0.241921895599667900f, - 0.258819045102520740f, 0.275637355816999160f, 0.292371704722736770f, - 0.309016994374947450f, 0.325568154457156760f, 0.342020143325668820f, - 0.358367949545300380f, 0.374606593415911960f, - 0.390731128489273940f, 0.406736643075800210f, 0.422618261740699440f, - 0.438371146789077460f, 0.453990499739546860f, 0.469471562785890860f, - 0.484809620246337110f, 0.500000000000000110f, - 0.515038074910054380f, 0.529919264233204900f, 0.544639035015027200f, - 0.559192903470746790f, 0.573576436351046050f, 0.587785252292473140f, - 0.601815023152048270f, 0.615661475325658290f, - 0.629320391049837500f, 0.642787609686539360f, 0.656059028990507280f, - 0.669130606358858240f, 0.681998360062498480f, 0.694658370458997370f, - 0.707106781186547570f, 0.719339800338651190f, - 0.731353701619170570f, 0.743144825477394240f, 0.754709580222772010f, - 0.766044443118978010f, 0.777145961456970900f, 0.788010753606722010f, - 0.798635510047292830f, 0.809016994374947450f, - 0.819152044288991800f, 0.829037572555041620f, 0.838670567945424050f, - 0.848048096156425960f, 0.857167300702112330f, 0.866025403784438710f, - 0.874619707139395740f, 0.882947592858926990f, - 0.891006524188367900f, 0.898794046299167040f, 0.906307787036649940f, - 0.913545457642600870f, 0.920504853452440370f, 0.927183854566787420f, - 0.933580426497201740f, 0.939692620785908430f, - 0.945518575599316850f, 0.951056516295153530f, 0.956304755963035440f, - 0.961261695938318890f, 0.965925826289068310f, 0.970295726275996470f, - 0.974370064785235250f, 0.978147600733805690f, - 0.981627183447663980f, 0.984807753012208020f, 0.987688340595137770f, - 0.990268068741570360f, 0.992546151641321980f, 0.994521895368273290f, - 0.996194698091745550f, 0.997564050259824200f, - 0.998629534754573830f, 0.999390827019095760f, 0.999847695156391270f, - 1.000000000000000000f, 0.999847695156391270f, 0.999390827019095760f, - 0.998629534754573830f, 0.997564050259824200f, - 0.996194698091745550f, 0.994521895368273290f, 0.992546151641321980f, - 0.990268068741570360f, 0.987688340595137770f, 0.984807753012208020f, - 0.981627183447663980f, 0.978147600733805690f, - 0.974370064785235250f, 0.970295726275996470f, 0.965925826289068310f, - 0.961261695938318890f, 0.956304755963035440f, 0.951056516295153530f, - 0.945518575599316850f, 0.939692620785908430f, - 0.933580426497201740f, 0.927183854566787420f, 0.920504853452440370f, - 0.913545457642600870f, 0.906307787036649940f, 0.898794046299167040f, - 0.891006524188367900f, 0.882947592858926990f, - 0.874619707139395740f, 0.866025403784438710f, 0.857167300702112330f, - 0.848048096156425960f, 0.838670567945424050f, 0.829037572555041620f, - 0.819152044288991800f, 0.809016994374947450f, - 0.798635510047292830f, 0.788010753606722010f, 0.777145961456970900f, - 0.766044443118978010f, 0.754709580222772010f, 0.743144825477394240f, - 0.731353701619170570f, 0.719339800338651190f, - 0.707106781186547570f, 0.694658370458997370f, 0.681998360062498480f, - 0.669130606358858240f, 0.656059028990507280f, 0.642787609686539360f, - 0.629320391049837500f, 0.615661475325658290f, - 0.601815023152048270f, 0.587785252292473140f, 0.573576436351046050f, - 0.559192903470746790f, 0.544639035015027200f, 0.529919264233204900f, - 0.515038074910054380f, 0.500000000000000110f, - 0.484809620246337110f, 0.469471562785890860f, 0.453990499739546860f, - 0.438371146789077460f, 0.422618261740699440f, 0.406736643075800210f, - 0.390731128489273940f, 0.374606593415911960f, - 0.358367949545300380f, 0.342020143325668820f, 0.325568154457156760f, - 0.309016994374947450f, 0.292371704722736770f, 0.275637355816999160f, - 0.258819045102520740f, 0.241921895599667900f, - 0.224951054343864920f, 0.207911690817759450f, 0.190808995376544920f, - 0.173648177666930410f, 0.156434465040230920f, 0.139173100960065690f, - 0.121869343405147490f, 0.104528463267653460f, - 0.087155742747658138f, 0.069756473744125455f, 0.052335956242943966f, - 0.034899496702501080f, 0.017452406437283376f, 0.000000000000000061f, - -0.017452406437283477f, -0.034899496702500733f, - -0.052335956242943620f, -0.069756473744125330f, -0.087155742747658235f, - -0.104528463267653330f, -0.121869343405147370f, -0.139173100960065350f, - -0.156434465040231040f, -0.173648177666930300f, - -0.190808995376544800f, -0.207911690817759120f, -0.224951054343864810f, - -0.241921895599667790f, -0.258819045102520850f, -0.275637355816999050f, - -0.292371704722736660f, -0.309016994374947340f, - -0.325568154457156420f, -0.342020143325668710f, -0.358367949545300270f, - -0.374606593415912070f, -0.390731128489273600f, -0.406736643075800100f, - -0.422618261740699330f, -0.438371146789077510f, - -0.453990499739546750f, -0.469471562785890530f, -0.484809620246337000f, - -0.499999999999999780f, -0.515038074910054270f, -0.529919264233204790f, - -0.544639035015027080f, -0.559192903470746680f, - -0.573576436351045830f, -0.587785252292473030f, -0.601815023152048380f, - -0.615661475325658290f, -0.629320391049837280f, -0.642787609686539360f, - -0.656059028990507500f, -0.669130606358858240f, - -0.681998360062498370f, -0.694658370458997030f, -0.707106781186547460f, - -0.719339800338651300f, -0.731353701619170460f, -0.743144825477394130f, - -0.754709580222772010f, -0.766044443118977900f, - -0.777145961456970680f, -0.788010753606721900f, -0.798635510047292940f, - -0.809016994374947340f, -0.819152044288991580f, -0.829037572555041620f, - -0.838670567945424160f, -0.848048096156425960f, - -0.857167300702112220f, -0.866025403784438710f, -0.874619707139395740f, - -0.882947592858926770f, -0.891006524188367790f, -0.898794046299167040f, - -0.906307787036649940f, -0.913545457642600760f, - -0.920504853452440150f, -0.927183854566787310f, -0.933580426497201740f, - -0.939692620785908320f, -0.945518575599316740f, -0.951056516295153530f, - -0.956304755963035440f, -0.961261695938318670f, - -0.965925826289068200f, -0.970295726275996470f, -0.974370064785235250f, - -0.978147600733805690f, -0.981627183447663980f, -0.984807753012208020f, - -0.987688340595137660f, -0.990268068741570250f, - -0.992546151641321980f, -0.994521895368273290f, -0.996194698091745550f, - -0.997564050259824200f, -0.998629534754573830f, -0.999390827019095760f, - -0.999847695156391270f, -1.000000000000000000f -}; - -/** -* \par -* Sine Table is generated from following loop -*
for(i = 0; i < 360; i++)    
-* {    
-*    sinTable[i]= sin((i-180) * PI/180.0);    
-* } 
-*/ - - -static const float32_t sinTable[360] = { - -0.017452406437283439f, -0.034899496702500699f, -0.052335956242943807f, - -0.069756473744125524f, -0.087155742747658638f, -0.104528463267653730f, - -0.121869343405147550f, -0.139173100960065740f, - -0.156434465040230980f, -0.173648177666930280f, -0.190808995376544970f, - -0.207911690817759310f, -0.224951054343864780f, -0.241921895599667730f, - -0.258819045102521020f, -0.275637355816999660f, - -0.292371704722737050f, -0.309016994374947510f, -0.325568154457156980f, - -0.342020143325668880f, -0.358367949545300210f, -0.374606593415912240f, - -0.390731128489274160f, -0.406736643075800430f, - -0.422618261740699500f, -0.438371146789077290f, -0.453990499739546860f, - -0.469471562785891080f, -0.484809620246337170f, -0.499999999999999940f, - -0.515038074910054380f, -0.529919264233204900f, - -0.544639035015026860f, -0.559192903470746900f, -0.573576436351046380f, - -0.587785252292473250f, -0.601815023152048160f, -0.615661475325658400f, - -0.629320391049837720f, -0.642787609686539470f, - -0.656059028990507280f, -0.669130606358858350f, -0.681998360062498590f, - -0.694658370458997140f, -0.707106781186547570f, -0.719339800338651410f, - -0.731353701619170570f, -0.743144825477394240f, - -0.754709580222771790f, -0.766044443118978010f, -0.777145961456971010f, - -0.788010753606722010f, -0.798635510047292720f, -0.809016994374947450f, - -0.819152044288992020f, -0.829037572555041740f, - -0.838670567945424050f, -0.848048096156426070f, -0.857167300702112330f, - -0.866025403784438710f, -0.874619707139395850f, -0.882947592858927100f, - -0.891006524188367900f, -0.898794046299166930f, - -0.906307787036650050f, -0.913545457642600980f, -0.920504853452440370f, - -0.927183854566787420f, -0.933580426497201740f, -0.939692620785908430f, - -0.945518575599316850f, -0.951056516295153640f, - -0.956304755963035550f, -0.961261695938318890f, -0.965925826289068310f, - -0.970295726275996470f, -0.974370064785235250f, -0.978147600733805690f, - -0.981627183447663980f, -0.984807753012208020f, - -0.987688340595137660f, -0.990268068741570360f, -0.992546151641322090f, - -0.994521895368273400f, -0.996194698091745550f, -0.997564050259824200f, - -0.998629534754573830f, -0.999390827019095760f, - -0.999847695156391270f, -1.000000000000000000f, -0.999847695156391270f, - -0.999390827019095760f, -0.998629534754573830f, -0.997564050259824200f, - -0.996194698091745550f, -0.994521895368273290f, - -0.992546151641321980f, -0.990268068741570250f, -0.987688340595137770f, - -0.984807753012208020f, -0.981627183447663980f, -0.978147600733805580f, - -0.974370064785235250f, -0.970295726275996470f, - -0.965925826289068310f, -0.961261695938318890f, -0.956304755963035440f, - -0.951056516295153530f, -0.945518575599316740f, -0.939692620785908320f, - -0.933580426497201740f, -0.927183854566787420f, - -0.920504853452440260f, -0.913545457642600870f, -0.906307787036649940f, - -0.898794046299167040f, -0.891006524188367790f, -0.882947592858926880f, - -0.874619707139395740f, -0.866025403784438600f, - -0.857167300702112220f, -0.848048096156426070f, -0.838670567945423940f, - -0.829037572555041740f, -0.819152044288991800f, -0.809016994374947450f, - -0.798635510047292830f, -0.788010753606722010f, - -0.777145961456970790f, -0.766044443118978010f, -0.754709580222772010f, - -0.743144825477394240f, -0.731353701619170460f, -0.719339800338651080f, - -0.707106781186547460f, -0.694658370458997250f, - -0.681998360062498480f, -0.669130606358858240f, -0.656059028990507160f, - -0.642787609686539250f, -0.629320391049837390f, -0.615661475325658180f, - -0.601815023152048270f, -0.587785252292473140f, - -0.573576436351046050f, -0.559192903470746900f, -0.544639035015027080f, - -0.529919264233204900f, -0.515038074910054160f, -0.499999999999999940f, - -0.484809620246337060f, -0.469471562785890810f, - -0.453990499739546750f, -0.438371146789077400f, -0.422618261740699440f, - -0.406736643075800150f, -0.390731128489273720f, -0.374606593415912010f, - -0.358367949545300270f, -0.342020143325668710f, - -0.325568154457156640f, -0.309016994374947400f, -0.292371704722736770f, - -0.275637355816999160f, -0.258819045102520740f, -0.241921895599667730f, - -0.224951054343865000f, -0.207911690817759310f, - -0.190808995376544800f, -0.173648177666930330f, -0.156434465040230870f, - -0.139173100960065440f, -0.121869343405147480f, -0.104528463267653460f, - -0.087155742747658166f, -0.069756473744125302f, - -0.052335956242943828f, -0.034899496702500969f, -0.017452406437283512f, - 0.000000000000000000f, 0.017452406437283512f, 0.034899496702500969f, - 0.052335956242943828f, 0.069756473744125302f, - 0.087155742747658166f, 0.104528463267653460f, 0.121869343405147480f, - 0.139173100960065440f, 0.156434465040230870f, 0.173648177666930330f, - 0.190808995376544800f, 0.207911690817759310f, - 0.224951054343865000f, 0.241921895599667730f, 0.258819045102520740f, - 0.275637355816999160f, 0.292371704722736770f, 0.309016994374947400f, - 0.325568154457156640f, 0.342020143325668710f, - 0.358367949545300270f, 0.374606593415912010f, 0.390731128489273720f, - 0.406736643075800150f, 0.422618261740699440f, 0.438371146789077400f, - 0.453990499739546750f, 0.469471562785890810f, - 0.484809620246337060f, 0.499999999999999940f, 0.515038074910054160f, - 0.529919264233204900f, 0.544639035015027080f, 0.559192903470746900f, - 0.573576436351046050f, 0.587785252292473140f, - 0.601815023152048270f, 0.615661475325658180f, 0.629320391049837390f, - 0.642787609686539250f, 0.656059028990507160f, 0.669130606358858240f, - 0.681998360062498480f, 0.694658370458997250f, - 0.707106781186547460f, 0.719339800338651080f, 0.731353701619170460f, - 0.743144825477394240f, 0.754709580222772010f, 0.766044443118978010f, - 0.777145961456970790f, 0.788010753606722010f, - 0.798635510047292830f, 0.809016994374947450f, 0.819152044288991800f, - 0.829037572555041740f, 0.838670567945423940f, 0.848048096156426070f, - 0.857167300702112220f, 0.866025403784438600f, - 0.874619707139395740f, 0.882947592858926880f, 0.891006524188367790f, - 0.898794046299167040f, 0.906307787036649940f, 0.913545457642600870f, - 0.920504853452440260f, 0.927183854566787420f, - 0.933580426497201740f, 0.939692620785908320f, 0.945518575599316740f, - 0.951056516295153530f, 0.956304755963035440f, 0.961261695938318890f, - 0.965925826289068310f, 0.970295726275996470f, - 0.974370064785235250f, 0.978147600733805580f, 0.981627183447663980f, - 0.984807753012208020f, 0.987688340595137770f, 0.990268068741570250f, - 0.992546151641321980f, 0.994521895368273290f, - 0.996194698091745550f, 0.997564050259824200f, 0.998629534754573830f, - 0.999390827019095760f, 0.999847695156391270f, 1.000000000000000000f, - 0.999847695156391270f, 0.999390827019095760f, - 0.998629534754573830f, 0.997564050259824200f, 0.996194698091745550f, - 0.994521895368273400f, 0.992546151641322090f, 0.990268068741570360f, - 0.987688340595137660f, 0.984807753012208020f, - 0.981627183447663980f, 0.978147600733805690f, 0.974370064785235250f, - 0.970295726275996470f, 0.965925826289068310f, 0.961261695938318890f, - 0.956304755963035550f, 0.951056516295153640f, - 0.945518575599316850f, 0.939692620785908430f, 0.933580426497201740f, - 0.927183854566787420f, 0.920504853452440370f, 0.913545457642600980f, - 0.906307787036650050f, 0.898794046299166930f, - 0.891006524188367900f, 0.882947592858927100f, 0.874619707139395850f, - 0.866025403784438710f, 0.857167300702112330f, 0.848048096156426070f, - 0.838670567945424050f, 0.829037572555041740f, - 0.819152044288992020f, 0.809016994374947450f, 0.798635510047292720f, - 0.788010753606722010f, 0.777145961456971010f, 0.766044443118978010f, - 0.754709580222771790f, 0.743144825477394240f, - 0.731353701619170570f, 0.719339800338651410f, 0.707106781186547570f, - 0.694658370458997140f, 0.681998360062498590f, 0.669130606358858350f, - 0.656059028990507280f, 0.642787609686539470f, - 0.629320391049837720f, 0.615661475325658400f, 0.601815023152048160f, - 0.587785252292473250f, 0.573576436351046380f, 0.559192903470746900f, - 0.544639035015026860f, 0.529919264233204900f, - 0.515038074910054380f, 0.499999999999999940f, 0.484809620246337170f, - 0.469471562785891080f, 0.453990499739546860f, 0.438371146789077290f, - 0.422618261740699500f, 0.406736643075800430f, - 0.390731128489274160f, 0.374606593415912240f, 0.358367949545300210f, - 0.342020143325668880f, 0.325568154457156980f, 0.309016994374947510f, - 0.292371704722737050f, 0.275637355816999660f, - 0.258819045102521020f, 0.241921895599667730f, 0.224951054343864780f, - 0.207911690817759310f, 0.190808995376544970f, 0.173648177666930280f, - 0.156434465040230980f, 0.139173100960065740f, - 0.121869343405147550f, 0.104528463267653730f, 0.087155742747658638f, - 0.069756473744125524f, 0.052335956242943807f, 0.034899496702500699f, - 0.017452406437283439f, 0.000000000000000122f -}; - - -/** - * @brief Floating-point sin_cos function. - * @param[in] theta input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cos output. - * @return none. - */ - - -void arm_sin_cos_f32( - float32_t theta, - float32_t * pSinVal, - float32_t * pCosVal) -{ - int32_t i; /* Index for reading nearwst output values */ - float32_t x1 = -179.0f; /* Initial input value */ - float32_t y0, y1; /* nearest output values */ - float32_t y2, y3; - float32_t fract; /* fractional part of input */ - - /* Calculation of fractional part */ - if(theta > 0.0f) - { - fract = theta - (float32_t) ((int32_t) theta); - } - else - { - fract = (theta - (float32_t) ((int32_t) theta)) + 1.0f; - } - - /* index calculation for reading nearest output values */ - i = (uint32_t) (theta - x1); - - /* Checking min and max index of table */ - if(i < 0) - { - i = 0; - } - else if(i >= 359) - { - i = 358; - } - - /* reading nearest sine output values */ - y0 = sinTable[i]; - y1 = sinTable[i + 1u]; - - /* reading nearest cosine output values */ - y2 = cosTable[i]; - y3 = cosTable[i + 1u]; - - y1 = y1 - y0; - y3 = y3 - y2; - - y1 = fract * y1; - y3 = fract * y3; - - /* Calculation of sine value */ - *pSinVal = y0 + y1; - - /* Calculation of cosine value */ - *pCosVal = y2 + y3; - -} - -/** - * @} end of SinCos group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c deleted file mode 100644 index e22d25e539..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/ControllerFunctions/arm_sin_cos_q31.c +++ /dev/null @@ -1,324 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sin_cos_q31.c -* -* Description: Cosine & Sine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupController - */ - - /** - * @addtogroup SinCos - * @{ - */ - -/** -* \par -* Sine Table is generated from following loop -*
for(i = 0; i < 360; i++)    
-* {    
-*    sinTable[i]= sin((i-180) * PI/180.0);    
-* } 
-* Convert above coefficients to fixed point 1.31 format. -*/ - -static const int32_t sinTableQ31[360] = { - - 0x0, 0xfdc41e9b, 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, - 0xf06695da, - 0xee2f9369, 0xebf9f498, 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, - 0xe108b40d, 0xdedf047d, - 0xdcb7ea46, 0xda939061, 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, - 0xd00ce422, 0xcdfc85bb, - 0xcbf00dbe, 0xc9e7a512, 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, - 0xc0000000, 0xbe133b7c, - 0xbc2b9b05, 0xba4944a2, 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, - 0xb1320139, 0xaf726def, - 0xadb922b7, 0xac0641fb, 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, - 0xa3ecac65, 0xa263007d, - 0xa0e0a15f, 0x9f65ad2d, 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, - 0x98722192, 0x9726069c, - 0x95e218c9, 0x94a6715d, 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, - 0x8efb92c2, 0x8df37f8b, - 0x8cf45113, 0x8bfe1b3f, 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, - 0x87b826f7, 0x86f93f50, - 0x8643c7b3, 0x8597ce46, 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, - 0x82cc0f36, 0x825a0a5b, - 0x81f1d1ce, 0x81936daf, 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, - 0x804fd23a, 0x802ce84c, - 0x8013f61d, 0x8004fda0, 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, - 0x804fd23a, 0x807cb130, - 0x80b381ac, 0x80f43f69, 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, - 0x82cc0f36, 0x8347d77b, - 0x83cd5982, 0x845c8ae3, 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, - 0x87b826f7, 0x88806fc4, - 0x89520a1a, 0x8a2ce59f, 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, - 0x8efb92c2, 0x900c7621, - 0x9126145f, 0x92485786, 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, - 0x98722192, 0x99c64fc5, - 0x9b2276b0, 0x9c867b2c, 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, - 0xa3ecac65, 0xa57d8666, - 0xa7156f3c, 0xa8b4471a, 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, - 0xb1320139, 0xb2f7b9af, - 0xb4c373ee, 0xb6950c1e, 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, - 0xc0000000, 0xc1f1c224, - 0xc3e85b18, 0xc5e3a3a9, 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, - 0xd00ce422, 0xd220ffc0, - 0xd438af17, 0xd653c860, 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, - 0xe108b40d, 0xe334cdc9, - 0xe5632654, 0xe7939223, 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, - 0xf29ecfb2, 0xf4d814a4, - 0xf7123849, 0xf94d0e2e, 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, - 0x6b2f1d2, - 0x8edc7b7, 0xb27eb5c, 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, - 0x163a1a7e, 0x186c6ddd, - 0x1a9cd9ac, 0x1ccb3237, 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, - 0x278dde6e, 0x29ac37a0, - 0x2bc750e9, 0x2ddf0040, 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, - 0x381c8bb5, 0x3a1c5c57, - 0x3c17a4e8, 0x3e0e3ddc, 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, - 0x4793a210, 0x496af3e2, - 0x4b3c8c12, 0x4d084651, 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, - 0x55a6125c, 0x574bb8e6, - 0x58ea90c4, 0x5a82799a, 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, - 0x620dbe8b, 0x637984d4, - 0x64dd8950, 0x6639b03b, 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, - 0x6c8cd70b, 0x6db7a87a, - 0x6ed9eba1, 0x6ff389df, 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, - 0x74ef0ebc, 0x75d31a61, - 0x76adf5e6, 0x777f903c, 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, - 0x7b0a9f8d, 0x7ba3751d, - 0x7c32a67e, 0x7cb82885, 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, - 0x7ec11aa5, 0x7f0bc097, - 0x7f4c7e54, 0x7f834ed0, 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, - 0x7fffffff, 0x7ffb0260, - 0x7fec09e3, 0x7fd317b4, 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, - 0x7ec11aa5, 0x7e6c9251, - 0x7e0e2e32, 0x7da5f5a5, 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, - 0x7b0a9f8d, 0x7a6831ba, - 0x79bc384d, 0x7906c0b0, 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, - 0x74ef0ebc, 0x7401e4c1, - 0x730baeed, 0x720c8075, 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, - 0x6c8cd70b, 0x6b598ea3, - 0x6a1de737, 0x68d9f964, 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, - 0x620dbe8b, 0x609a52d3, - 0x5f1f5ea1, 0x5d9cff83, 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, - 0x55a6125c, 0x53f9be05, - 0x5246dd49, 0x508d9211, 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, - 0x4793a210, 0x45b6bb5e, - 0x43d464fb, 0x41ecc484, 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, - 0x381c8bb5, 0x36185aee, - 0x340ff242, 0x32037a45, 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, - 0x278dde6e, 0x256c6f9f, - 0x234815ba, 0x2120fb83, 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, - 0x163a1a7e, 0x14060b68, - 0x11d06c97, 0xf996a26, 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, - 0x4779632, 0x23be165, - - -}; - -/** -* \par -* Cosine Table is generated from following loop -*
for(i = 0; i < 360; i++)    
-* {    
-*    cosTable[i]= cos((i-180) * PI/180.0);    
-* } 
-* \par -* Convert above coefficients to fixed point 1.31 format. -*/ -static const int32_t cosTableQ31[360] = { - 0x80000000, 0x8004fda0, 0x8013f61d, 0x802ce84c, 0x804fd23a, 0x807cb130, - 0x80b381ac, 0x80f43f69, - 0x813ee55b, 0x81936daf, 0x81f1d1ce, 0x825a0a5b, 0x82cc0f36, 0x8347d77b, - 0x83cd5982, 0x845c8ae3, - 0x84f56073, 0x8597ce46, 0x8643c7b3, 0x86f93f50, 0x87b826f7, 0x88806fc4, - 0x89520a1a, 0x8a2ce59f, - 0x8b10f144, 0x8bfe1b3f, 0x8cf45113, 0x8df37f8b, 0x8efb92c2, 0x900c7621, - 0x9126145f, 0x92485786, - 0x937328f5, 0x94a6715d, 0x95e218c9, 0x9726069c, 0x98722192, 0x99c64fc5, - 0x9b2276b0, 0x9c867b2c, - 0x9df24175, 0x9f65ad2d, 0xa0e0a15f, 0xa263007d, 0xa3ecac65, 0xa57d8666, - 0xa7156f3c, 0xa8b4471a, - 0xaa59eda4, 0xac0641fb, 0xadb922b7, 0xaf726def, 0xb1320139, 0xb2f7b9af, - 0xb4c373ee, 0xb6950c1e, - 0xb86c5df0, 0xba4944a2, 0xbc2b9b05, 0xbe133b7c, 0xc0000000, 0xc1f1c224, - 0xc3e85b18, 0xc5e3a3a9, - 0xc7e3744b, 0xc9e7a512, 0xcbf00dbe, 0xcdfc85bb, 0xd00ce422, 0xd220ffc0, - 0xd438af17, 0xd653c860, - 0xd8722192, 0xda939061, 0xdcb7ea46, 0xdedf047d, 0xe108b40d, 0xe334cdc9, - 0xe5632654, 0xe7939223, - 0xe9c5e582, 0xebf9f498, 0xee2f9369, 0xf06695da, 0xf29ecfb2, 0xf4d814a4, - 0xf7123849, 0xf94d0e2e, - 0xfb8869ce, 0xfdc41e9b, 0x0, 0x23be165, 0x4779632, 0x6b2f1d2, 0x8edc7b7, - 0xb27eb5c, - 0xd61304e, 0xf996a26, 0x11d06c97, 0x14060b68, 0x163a1a7e, 0x186c6ddd, - 0x1a9cd9ac, 0x1ccb3237, - 0x1ef74bf3, 0x2120fb83, 0x234815ba, 0x256c6f9f, 0x278dde6e, 0x29ac37a0, - 0x2bc750e9, 0x2ddf0040, - 0x2ff31bde, 0x32037a45, 0x340ff242, 0x36185aee, 0x381c8bb5, 0x3a1c5c57, - 0x3c17a4e8, 0x3e0e3ddc, - 0x40000000, 0x41ecc484, 0x43d464fb, 0x45b6bb5e, 0x4793a210, 0x496af3e2, - 0x4b3c8c12, 0x4d084651, - 0x4ecdfec7, 0x508d9211, 0x5246dd49, 0x53f9be05, 0x55a6125c, 0x574bb8e6, - 0x58ea90c4, 0x5a82799a, - 0x5c13539b, 0x5d9cff83, 0x5f1f5ea1, 0x609a52d3, 0x620dbe8b, 0x637984d4, - 0x64dd8950, 0x6639b03b, - 0x678dde6e, 0x68d9f964, 0x6a1de737, 0x6b598ea3, 0x6c8cd70b, 0x6db7a87a, - 0x6ed9eba1, 0x6ff389df, - 0x71046d3e, 0x720c8075, 0x730baeed, 0x7401e4c1, 0x74ef0ebc, 0x75d31a61, - 0x76adf5e6, 0x777f903c, - 0x7847d909, 0x7906c0b0, 0x79bc384d, 0x7a6831ba, 0x7b0a9f8d, 0x7ba3751d, - 0x7c32a67e, 0x7cb82885, - 0x7d33f0ca, 0x7da5f5a5, 0x7e0e2e32, 0x7e6c9251, 0x7ec11aa5, 0x7f0bc097, - 0x7f4c7e54, 0x7f834ed0, - 0x7fb02dc6, 0x7fd317b4, 0x7fec09e3, 0x7ffb0260, 0x7fffffff, 0x7ffb0260, - 0x7fec09e3, 0x7fd317b4, - 0x7fb02dc6, 0x7f834ed0, 0x7f4c7e54, 0x7f0bc097, 0x7ec11aa5, 0x7e6c9251, - 0x7e0e2e32, 0x7da5f5a5, - 0x7d33f0ca, 0x7cb82885, 0x7c32a67e, 0x7ba3751d, 0x7b0a9f8d, 0x7a6831ba, - 0x79bc384d, 0x7906c0b0, - 0x7847d909, 0x777f903c, 0x76adf5e6, 0x75d31a61, 0x74ef0ebc, 0x7401e4c1, - 0x730baeed, 0x720c8075, - 0x71046d3e, 0x6ff389df, 0x6ed9eba1, 0x6db7a87a, 0x6c8cd70b, 0x6b598ea3, - 0x6a1de737, 0x68d9f964, - 0x678dde6e, 0x6639b03b, 0x64dd8950, 0x637984d4, 0x620dbe8b, 0x609a52d3, - 0x5f1f5ea1, 0x5d9cff83, - 0x5c13539b, 0x5a82799a, 0x58ea90c4, 0x574bb8e6, 0x55a6125c, 0x53f9be05, - 0x5246dd49, 0x508d9211, - 0x4ecdfec7, 0x4d084651, 0x4b3c8c12, 0x496af3e2, 0x4793a210, 0x45b6bb5e, - 0x43d464fb, 0x41ecc484, - 0x40000000, 0x3e0e3ddc, 0x3c17a4e8, 0x3a1c5c57, 0x381c8bb5, 0x36185aee, - 0x340ff242, 0x32037a45, - 0x2ff31bde, 0x2ddf0040, 0x2bc750e9, 0x29ac37a0, 0x278dde6e, 0x256c6f9f, - 0x234815ba, 0x2120fb83, - 0x1ef74bf3, 0x1ccb3237, 0x1a9cd9ac, 0x186c6ddd, 0x163a1a7e, 0x14060b68, - 0x11d06c97, 0xf996a26, - 0xd61304e, 0xb27eb5c, 0x8edc7b7, 0x6b2f1d2, 0x4779632, 0x23be165, 0x0, - 0xfdc41e9b, - 0xfb8869ce, 0xf94d0e2e, 0xf7123849, 0xf4d814a4, 0xf29ecfb2, 0xf06695da, - 0xee2f9369, 0xebf9f498, - 0xe9c5e582, 0xe7939223, 0xe5632654, 0xe334cdc9, 0xe108b40d, 0xdedf047d, - 0xdcb7ea46, 0xda939061, - 0xd8722192, 0xd653c860, 0xd438af17, 0xd220ffc0, 0xd00ce422, 0xcdfc85bb, - 0xcbf00dbe, 0xc9e7a512, - 0xc7e3744b, 0xc5e3a3a9, 0xc3e85b18, 0xc1f1c224, 0xc0000000, 0xbe133b7c, - 0xbc2b9b05, 0xba4944a2, - 0xb86c5df0, 0xb6950c1e, 0xb4c373ee, 0xb2f7b9af, 0xb1320139, 0xaf726def, - 0xadb922b7, 0xac0641fb, - 0xaa59eda4, 0xa8b4471a, 0xa7156f3c, 0xa57d8666, 0xa3ecac65, 0xa263007d, - 0xa0e0a15f, 0x9f65ad2d, - 0x9df24175, 0x9c867b2c, 0x9b2276b0, 0x99c64fc5, 0x98722192, 0x9726069c, - 0x95e218c9, 0x94a6715d, - 0x937328f5, 0x92485786, 0x9126145f, 0x900c7621, 0x8efb92c2, 0x8df37f8b, - 0x8cf45113, 0x8bfe1b3f, - 0x8b10f144, 0x8a2ce59f, 0x89520a1a, 0x88806fc4, 0x87b826f7, 0x86f93f50, - 0x8643c7b3, 0x8597ce46, - 0x84f56073, 0x845c8ae3, 0x83cd5982, 0x8347d77b, 0x82cc0f36, 0x825a0a5b, - 0x81f1d1ce, 0x81936daf, - 0x813ee55b, 0x80f43f69, 0x80b381ac, 0x807cb130, 0x804fd23a, 0x802ce84c, - 0x8013f61d, 0x8004fda0, - -}; - - -/** - * @brief Q31 sin_cos function. - * @param[in] theta scaled input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cosine output. - * @return none. - * - * The Q31 input value is in the range [-1 0.999999] and is mapped to a degree value in the range [-180 179]. - * - */ - - -void arm_sin_cos_q31( - q31_t theta, - q31_t * pSinVal, - q31_t * pCosVal) -{ - q31_t x0; /* Nearest input value */ - q31_t y0, y1; /* Nearest output values */ - q31_t xSpacing = INPUT_SPACING; /* Spaing between inputs */ - int32_t i; /* Index */ - q31_t oneByXSpacing; /* 1/ xSpacing value */ - q31_t out; /* temporary variable */ - uint32_t sign_bits; /* No.of sign bits */ - uint32_t firstX = 0x80000000; /* First X value */ - - /* Calculation of index */ - i = ((uint32_t) theta - firstX) / (uint32_t) xSpacing; - - /* Checking min and max index of table */ - if(i < 0) - { - i = 0; - } - else if(i >= 359) - { - i = 358; - } - - /* Calculation of first nearest input value */ - x0 = (q31_t) firstX + ((q31_t) i * xSpacing); - - /* Reading nearest sine output values from table */ - y0 = sinTableQ31[i]; - y1 = sinTableQ31[i + 1u]; - - /* Calculation of 1/(x1-x0) */ - /* (x1-x0) is xSpacing which is fixed value */ - sign_bits = 8u; - oneByXSpacing = 0x5A000000; - - /* Calculation of (theta - x0)/(x1-x0) */ - out = - (((q31_t) (((q63_t) (theta - x0) * oneByXSpacing) >> 32)) << sign_bits); - - /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ - *pSinVal = __QADD(y0, ((q31_t) (((q63_t) (y1 - y0) * out) >> 30))); - - /* Reading nearest cosine output values from table */ - y0 = cosTableQ31[i]; - y1 = cosTableQ31[i + 1u]; - - /* Calculation of y0 + (y1 - y0) * ((theta - x0)/(x1-x0)) */ - *pCosVal = __QADD(y0, ((q31_t) (((q63_t) (y1 - y0) * out) >> 30))); - -} - -/** - * @} end of SinCos group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c deleted file mode 100644 index bee758bff7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_f32.c +++ /dev/null @@ -1,280 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cos_f32.c -* -* Description: Fast cosine calculation for floating-point values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFastMath - */ - -/** - * @defgroup cos Cosine - * - * Computes the trigonometric cosine function using a combination of table lookup - * and cubic interpolation. There are separate functions for - * Q15, Q31, and floating-point data types. - * The input to the floating-point version is in radians while the - * fixed-point Q15 and Q31 have a scaled input with the range - * [0 +0.9999] mapping to [0 2*pi), Where range excludes 2*pi. - * - * The implementation is based on table lookup using 256 values together with cubic interpolation. - * The steps used are: - * -# Calculation of the nearest integer table index - * -# Fetch the four table values a, b, c, and d - * -# Compute the fractional portion (fract) of the table index. - * -# Calculation of wa, wb, wc, wd - * -# The final result equals a*wa + b*wb + c*wc + d*wd - * - * where - *
    
- *    a=Table[index-1];    
- *    b=Table[index+0];    
- *    c=Table[index+1];    
- *    d=Table[index+2];    
- * 
- * and - *
    
- *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;    
- *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;    
- *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;    
- *    wd=(1/6)*fract.^3 - (1/6)*fract;    
- * 
- */ - - /** - * @addtogroup cos - * @{ - */ - - -/** -* \par -* Example code for Generation of Cos Table: -* tableSize = 256; -*
for(n = -1; n < (tableSize + 2); n++)    
-* {    
-*	cosTable[n+1]= cos(2*pi*n/tableSize);    
-* } 
-* where pi value is 3.14159265358979 -*/ - -static const float32_t cosTable[260] = { - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, - 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, - 0.992479562759399410f, 0.989176511764526370f, - 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, - 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, - 0.949528157711029050f, 0.941544055938720700f, - 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, - 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, - 0.870086967945098880f, 0.857728600502014160f, - 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, - 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, - 0.757208824157714840f, 0.740951120853424070f, - 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, - 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, - 0.615231573581695560f, 0.595699310302734380f, - 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, - 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, - 0.449611335992813110f, 0.427555084228515630f, - 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, - 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, - 0.266712754964828490f, 0.242980182170867920f, - 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, - 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, - 0.073564566671848297f, 0.049067676067352295f, - 0.024541229009628296f, 0.000000000000000061f, -0.024541229009628296f, - -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, - -0.122410677373409270f, -0.146730467677116390f, - -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, - -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, - -0.313681751489639280f, -0.336889863014221190f, - -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, - -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, - -0.492898195981979370f, -0.514102756977081300f, - -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, - -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, - -0.653172850608825680f, -0.671558976173400880f, - -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, - -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, - -0.788346409797668460f, -0.803207516670227050f, - -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, - -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, - -0.893224298954010010f, -0.903989315032958980f, - -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, - -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, - -0.963776051998138430f, -0.970031261444091800f, - -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, - -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, - -0.997290432453155520f, -0.998795449733734130f, - -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, - -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, - -0.992479562759399410f, -0.989176511764526370f, - -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, - -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, - -0.949528157711029050f, -0.941544055938720700f, - -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, - -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, - -0.870086967945098880f, -0.857728600502014160f, - -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, - -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, - -0.757208824157714840f, -0.740951120853424070f, - -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, - -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, - -0.615231573581695560f, -0.595699310302734380f, - -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, - -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, - -0.449611335992813110f, -0.427555084228515630f, - -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, - -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, - -0.266712754964828490f, -0.242980182170867920f, - -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, - -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, - -0.073564566671848297f, -0.049067676067352295f, - -0.024541229009628296f, -0.000000000000000184f, 0.024541229009628296f, - 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, - 0.122410677373409270f, 0.146730467677116390f, - 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, - 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, - 0.313681751489639280f, 0.336889863014221190f, - 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, - 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, - 0.492898195981979370f, 0.514102756977081300f, - 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, - 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, - 0.653172850608825680f, 0.671558976173400880f, - 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, - 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, - 0.788346409797668460f, 0.803207516670227050f, - 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, - 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, - 0.893224298954010010f, 0.903989315032958980f, - 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, - 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, - 0.963776051998138430f, 0.970031261444091800f, - 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, - 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, - 0.997290432453155520f, 0.998795449733734130f, - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, - 0.998795449733734130f -}; - -/** - * @brief Fast approximation to the trigonometric cosine function for floating-point data. - * @param[in] x input value in radians. - * @return cos(x). - */ - - -float32_t arm_cos_f32( - float32_t x) -{ - float32_t cosVal, fract, in; - int32_t index; - uint32_t tableSize = (uint32_t) TABLE_SIZE; - float32_t wa, wb, wc, wd; - float32_t a, b, c, d; - float32_t *tablePtr; - int32_t n; - float32_t fractsq, fractby2, fractby6, fractby3, fractsqby2; - float32_t oneminusfractby2; - float32_t frby2xfrsq, frby6xfrsq; - - /* input x is in radians */ - /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ - in = x * 0.159154943092f; - - /* Calculation of floor value of input */ - n = (int32_t) in; - - /* Make negative values towards -infinity */ - if(x < 0.0f) - { - n = n - 1; - } - - /* Map input value to [0 1] */ - in = in - (float32_t) n; - - /* Calculation of index of the table */ - index = (uint32_t) (tableSize * in); - - /* fractional value calculation */ - fract = ((float32_t) tableSize * in) - (float32_t) index; - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (float32_t *) & cosTable[index]; - - /* Read four nearest values of input value from the cos table */ - a = tablePtr[0]; - b = tablePtr[1]; - c = tablePtr[2]; - d = tablePtr[3]; - - /* Cubic interpolation process */ - fractsq = fract * fract; - fractby2 = fract * 0.5f; - fractby6 = fract * 0.166666667f; - fractby3 = fract * 0.3333333333333f; - fractsqby2 = fractsq * 0.5f; - frby2xfrsq = (fractby2) * fractsq; - frby6xfrsq = (fractby6) * fractsq; - oneminusfractby2 = 1.0f - fractby2; - wb = fractsqby2 - fractby3; - wc = (fractsqby2 + fract); - wa = wb - frby6xfrsq; - wb = frby2xfrsq - fractsq; - cosVal = wa * a; - wc = wc - frby2xfrsq; - wd = (frby6xfrsq) - fractby6; - wb = wb + oneminusfractby2; - - /* Calculate cos value */ - cosVal = (cosVal + (b * wb)) + ((c * wc) + (d * wd)); - - /* Return the output value */ - return (cosVal); - -} - -/** - * @} end of cos group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c deleted file mode 100644 index 0edf68b893..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q15.c +++ /dev/null @@ -1,205 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cos_q15.c -* -* Description: Fast cosine calculation for Q15 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup cos - * @{ - */ - -/** -* \par -* Table Values are in Q15(1.15 Fixed point format) and generation is done in three steps -* \par -* First Generate cos values in floating point: -* tableSize = 256; -*
for(n = -1; n < (tableSize + 1); n++)    
-* {    
-*	cosTable[n+1]= cos(2*pi*n/tableSize);    
-* }
-* where pi value is 3.14159265358979 -* \par -* Secondly Convert Floating point to Q15(Fixed point): -* (cosTable[i] * pow(2, 15)) -* \par -* Finally Rounding to nearest integer is done -* cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); -*/ - -static const q15_t cosTableQ15[259] = { - 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, - 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, - 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, - 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, - 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, - 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, - 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, - 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, - 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, - 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, - 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, - 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, - 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, - 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, - 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, - 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, - 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, - 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, - 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, - 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, - 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, - 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, - 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, - 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, - 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, - 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, - 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, - 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, - 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, - 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, - 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, - 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, - 0x7ff6, 0x7fff, 0x7ff6 -}; - - -/** - * @brief Fast approximation to the trigonometric cosine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - * - * The Q15 input value is in the range [0 +0.9999] and is mapped to a radian value in the range [0 2*pi), Here range excludes 2*pi. - */ - -q15_t arm_cos_q15( - q15_t x) -{ - q31_t cosVal; /* Temporary variable for output */ - q15_t *tablePtr; /* Pointer to table */ - q15_t in, in2; /* Temporary variables for input */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q15_t a, b, c, d; /* Four nearest output values */ - q15_t fract, fractCube, fractSquare; /* Variables for fractional value */ - q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ - q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ - int32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = (int32_t) in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q15_t) index *tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = (q15_t) ((fract * fract) >> 15); - - /* fractCube = fract * fract * fract */ - fractCube = (q15_t) ((fractSquare * fract) >> 15); - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (q15_t *) & cosTableQ15[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ - wa = (q31_t) oneBy6 *fractCube; - wa += (q31_t) 0x2AAA *fract; - wa = -(wa >> 15); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the cos table */ - a = *tablePtr++; - - /* cosVal = a * wa */ - cosVal = a * wa; - - /* Calculation of wb */ - wb = (((fractCube >> 1u) - fractSquare) - (fract >> 1u)) + 0x7FFF; - - /* Read second nearest value of output from the cos table */ - b = *tablePtr++; - - /* cosVal += b*wb */ - cosVal += b * wb; - - /* Calculation of wc */ - wc = -(q31_t) fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the cos table */ - c = *tablePtr++; - - /* cosVal += c*wc */ - cosVal += c * wc; - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); - - /* Read fourth nearest value of output from the cos table */ - d = *tablePtr++; - - /* cosVal += d*wd; */ - cosVal += d * wd; - - /* Convert output value in 1.15(q15) format and saturate */ - cosVal = __SSAT((cosVal >> 15), 16); - - /* Return the output value in 1.15(q15) format */ - return ((q15_t) cosVal); - -} - -/** - * @} end of cos group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c deleted file mode 100644 index 1326215fe4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_cos_q31.c +++ /dev/null @@ -1,239 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cos_q31.c -* -* Description: Fast cosine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup cos - * @{ - */ - -/** - * \par - * Table Values are in Q31(1.31 Fixed point format) and generation is done in three steps - * First Generate cos values in floating point: - * tableSize = 256; - *
for(n = -1; n < (tableSize + 1); n++)    
- * {    
- *	cosTable[n+1]= cos(2*pi*n/tableSize);    
- * } 
- * where pi value is 3.14159265358979 - * \par - * Secondly Convert Floating point to Q31(Fixed point): - * (cosTable[i] * pow(2, 31)) - * \par - * Finally Rounding to nearest integer is done - * cosTable[i] += (cosTable[i] > 0 ? 0.5 :-0.5); - */ - - -static const q31_t cosTableQ31[259] = { - 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, - 0x7f0991c4, 0x7e9d55fc, - 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, - 0x798a23b1, 0x78848414, - 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, - 0x6f5f02b2, 0x6dca0d14, - 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, - 0x60ec3830, 0x5ed77c8a, - 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, - 0x4ebfe8a5, 0x4c3fdff4, - 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, - 0x398cdd32, 0x36ba2014, - 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, - 0x2223a4c5, 0x1f19f97b, - 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, - 0x96a9049, 0x647d97c, - 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, - 0xed37ef91, - 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, - 0xd7d946d8, 0xd4e0cb15, - 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, - 0xc0e8b648, 0xbe31e19b, - 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, - 0xac64d510, 0xaa0a5b2e, - 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, - 0x9b1776da, 0x99307ee0, - 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, - 0x8daad37b, 0x8c4a142f, - 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, - 0x84a2fc62, 0x83d60412, - 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, - 0x8058c94c, 0x80277872, - 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, - 0x80f66e3c, 0x8162aa04, - 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, - 0x8675dc4f, 0x877b7bec, - 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, - 0x90a0fd4e, 0x9235f2ec, - 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, - 0x9f13c7d0, 0xa1288376, - 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, - 0xb140175b, 0xb3c0200c, - 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, - 0xc67322ce, 0xc945dfec, - 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, - 0xdddc5b3b, 0xe0e60685, - 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, - 0xf6956fb7, 0xf9b82684, - 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, - 0x12c8106f, - 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, - 0x2826b928, 0x2b1f34eb, - 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, - 0x3f1749b8, 0x41ce1e65, - 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, - 0x539b2af0, 0x55f5a4d2, - 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, - 0x64e88926, 0x66cf8120, - 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, - 0x72552c85, 0x73b5ebd1, - 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, - 0x7b5d039e, 0x7c29fbee, - 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, - 0x7fa736b4, 0x7fd8878e, - 0x7ff62182, 0x7fffffff, 0x7ff62182 -}; - -/** - * @brief Fast approximation to the trigonometric cosine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - * - * The Q31 input value is in the range [0 +0.9999] and is mapped to a radian value in the range [0 2*pi), Here range excludes 2*pi. - */ - -q31_t arm_cos_q31( - q31_t x) -{ - q31_t cosVal, in, in2; /* Temporary variables for input, output */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q31_t a, b, c, d; /* Four nearest output values */ - q31_t *tablePtr; /* Pointer to table */ - q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ - q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ - q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ - q31_t temp; /* Temporary variable for intermediate process */ - int32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = ((q31_t) index) * tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); - fractSquare = fractSquare << 1; - - /* fractCube = fract * fract * fract */ - fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); - fractCube = fractCube << 1; - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (q31_t *) & cosTableQ31[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ - wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - temp = 0x2AAAAAAA; - wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); - wa = -(wa << 1u); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the cos table */ - a = *tablePtr++; - - /* cosVal = a*wa */ - cosVal = ((q31_t) (((q63_t) a * wa) >> 32)); - - /* q31(1.31) Fixed point value of 1 */ - temp = 0x7FFFFFFF; - - /* Calculation of wb */ - wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; - /* Read second nearest value of output from the cos table */ - b = *tablePtr++; - - /* cosVal += b*wb */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) b * (wb))) >> 32); - - /* Calculation of wc */ - wc = -fractCube + fractSquare; - wc = (wc >> 1u) + fract; - /* Read third nearest values of output value from the cos table */ - c = *tablePtr++; - - /* cosVal += c*wc */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) c * (wc))) >> 32); - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - wd = (wd << 1u); - - /* Read fourth nearest value of output from the cos table */ - d = *tablePtr++; - - /* cosVal += d*wd; */ - cosVal = (q31_t) ((((q63_t) cosVal << 32) + ((q63_t) d * (wd))) >> 32); - - - /* convert cosVal in 2.30 format to 1.31 format */ - return (__QADD(cosVal, cosVal)); - -} - -/** - * @} end of cos group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c deleted file mode 100644 index bfe58d5c81..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_f32.c +++ /dev/null @@ -1,281 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sin_f32.c -* -* Description: Fast sine calculation for floating-point values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - -/** - * @defgroup sin Sine - * - * Computes the trigonometric sine function using a combination of table lookup - * and cubic interpolation. There are separate functions for - * Q15, Q31, and floating-point data types. - * The input to the floating-point version is in radians while the - * fixed-point Q15 and Q31 have a scaled input with the range - * [0 +0.9999] mapping to [0 2*pi), Where range excludes 2*pi. - * - * The implementation is based on table lookup using 256 values together with cubic interpolation. - * The steps used are: - * -# Calculation of the nearest integer table index - * -# Fetch the four table values a, b, c, and d - * -# Compute the fractional portion (fract) of the table index. - * -# Calculation of wa, wb, wc, wd - * -# The final result equals a*wa + b*wb + c*wc + d*wd - * - * where - *
    
- *    a=Table[index-1];    
- *    b=Table[index+0];    
- *    c=Table[index+1];    
- *    d=Table[index+2];    
- * 
- * and - *
    
- *    wa=-(1/6)*fract.^3 + (1/2)*fract.^2 - (1/3)*fract;    
- *    wb=(1/2)*fract.^3 - fract.^2 - (1/2)*fract + 1;    
- *    wc=-(1/2)*fract.^3+(1/2)*fract.^2+fract;    
- *    wd=(1/6)*fract.^3 - (1/6)*fract;    
- * 
- */ - -/** - * @addtogroup sin - * @{ - */ - - -/** - * \par - * Example code for Generation of Floating-point Sin Table: - * tableSize = 256; - *
for(n = -1; n < (tableSize + 1); n++)    
- * {    
- *	sinTable[n+1]=sin(2*pi*n/tableSize);    
- * }
- * \par - * where pi value is 3.14159265358979 - */ - -static const float32_t sinTable[259] = { - -0.024541229009628296f, 0.000000000000000000f, 0.024541229009628296f, - 0.049067676067352295f, 0.073564566671848297f, 0.098017141222953796f, - 0.122410677373409270f, 0.146730467677116390f, - 0.170961886644363400f, 0.195090323686599730f, 0.219101235270500180f, - 0.242980182170867920f, 0.266712754964828490f, 0.290284663438797000f, - 0.313681751489639280f, 0.336889863014221190f, - 0.359895050525665280f, 0.382683426141738890f, 0.405241310596466060f, - 0.427555084228515630f, 0.449611335992813110f, 0.471396744251251220f, - 0.492898195981979370f, 0.514102756977081300f, - 0.534997642040252690f, 0.555570244789123540f, 0.575808167457580570f, - 0.595699310302734380f, 0.615231573581695560f, 0.634393274784088130f, - 0.653172850608825680f, 0.671558976173400880f, - 0.689540565013885500f, 0.707106769084930420f, 0.724247097969055180f, - 0.740951120853424070f, 0.757208824157714840f, 0.773010432720184330f, - 0.788346409797668460f, 0.803207516670227050f, - 0.817584812641143800f, 0.831469595432281490f, 0.844853579998016360f, - 0.857728600502014160f, 0.870086967945098880f, 0.881921291351318360f, - 0.893224298954010010f, 0.903989315032958980f, - 0.914209783077239990f, 0.923879504203796390f, 0.932992815971374510f, - 0.941544055938720700f, 0.949528157711029050f, 0.956940352916717530f, - 0.963776051998138430f, 0.970031261444091800f, - 0.975702106952667240f, 0.980785250663757320f, 0.985277652740478520f, - 0.989176511764526370f, 0.992479562759399410f, 0.995184719562530520f, - 0.997290432453155520f, 0.998795449733734130f, - 0.999698817729949950f, 1.000000000000000000f, 0.999698817729949950f, - 0.998795449733734130f, 0.997290432453155520f, 0.995184719562530520f, - 0.992479562759399410f, 0.989176511764526370f, - 0.985277652740478520f, 0.980785250663757320f, 0.975702106952667240f, - 0.970031261444091800f, 0.963776051998138430f, 0.956940352916717530f, - 0.949528157711029050f, 0.941544055938720700f, - 0.932992815971374510f, 0.923879504203796390f, 0.914209783077239990f, - 0.903989315032958980f, 0.893224298954010010f, 0.881921291351318360f, - 0.870086967945098880f, 0.857728600502014160f, - 0.844853579998016360f, 0.831469595432281490f, 0.817584812641143800f, - 0.803207516670227050f, 0.788346409797668460f, 0.773010432720184330f, - 0.757208824157714840f, 0.740951120853424070f, - 0.724247097969055180f, 0.707106769084930420f, 0.689540565013885500f, - 0.671558976173400880f, 0.653172850608825680f, 0.634393274784088130f, - 0.615231573581695560f, 0.595699310302734380f, - 0.575808167457580570f, 0.555570244789123540f, 0.534997642040252690f, - 0.514102756977081300f, 0.492898195981979370f, 0.471396744251251220f, - 0.449611335992813110f, 0.427555084228515630f, - 0.405241310596466060f, 0.382683426141738890f, 0.359895050525665280f, - 0.336889863014221190f, 0.313681751489639280f, 0.290284663438797000f, - 0.266712754964828490f, 0.242980182170867920f, - 0.219101235270500180f, 0.195090323686599730f, 0.170961886644363400f, - 0.146730467677116390f, 0.122410677373409270f, 0.098017141222953796f, - 0.073564566671848297f, 0.049067676067352295f, - 0.024541229009628296f, 0.000000000000000122f, -0.024541229009628296f, - -0.049067676067352295f, -0.073564566671848297f, -0.098017141222953796f, - -0.122410677373409270f, -0.146730467677116390f, - -0.170961886644363400f, -0.195090323686599730f, -0.219101235270500180f, - -0.242980182170867920f, -0.266712754964828490f, -0.290284663438797000f, - -0.313681751489639280f, -0.336889863014221190f, - -0.359895050525665280f, -0.382683426141738890f, -0.405241310596466060f, - -0.427555084228515630f, -0.449611335992813110f, -0.471396744251251220f, - -0.492898195981979370f, -0.514102756977081300f, - -0.534997642040252690f, -0.555570244789123540f, -0.575808167457580570f, - -0.595699310302734380f, -0.615231573581695560f, -0.634393274784088130f, - -0.653172850608825680f, -0.671558976173400880f, - -0.689540565013885500f, -0.707106769084930420f, -0.724247097969055180f, - -0.740951120853424070f, -0.757208824157714840f, -0.773010432720184330f, - -0.788346409797668460f, -0.803207516670227050f, - -0.817584812641143800f, -0.831469595432281490f, -0.844853579998016360f, - -0.857728600502014160f, -0.870086967945098880f, -0.881921291351318360f, - -0.893224298954010010f, -0.903989315032958980f, - -0.914209783077239990f, -0.923879504203796390f, -0.932992815971374510f, - -0.941544055938720700f, -0.949528157711029050f, -0.956940352916717530f, - -0.963776051998138430f, -0.970031261444091800f, - -0.975702106952667240f, -0.980785250663757320f, -0.985277652740478520f, - -0.989176511764526370f, -0.992479562759399410f, -0.995184719562530520f, - -0.997290432453155520f, -0.998795449733734130f, - -0.999698817729949950f, -1.000000000000000000f, -0.999698817729949950f, - -0.998795449733734130f, -0.997290432453155520f, -0.995184719562530520f, - -0.992479562759399410f, -0.989176511764526370f, - -0.985277652740478520f, -0.980785250663757320f, -0.975702106952667240f, - -0.970031261444091800f, -0.963776051998138430f, -0.956940352916717530f, - -0.949528157711029050f, -0.941544055938720700f, - -0.932992815971374510f, -0.923879504203796390f, -0.914209783077239990f, - -0.903989315032958980f, -0.893224298954010010f, -0.881921291351318360f, - -0.870086967945098880f, -0.857728600502014160f, - -0.844853579998016360f, -0.831469595432281490f, -0.817584812641143800f, - -0.803207516670227050f, -0.788346409797668460f, -0.773010432720184330f, - -0.757208824157714840f, -0.740951120853424070f, - -0.724247097969055180f, -0.707106769084930420f, -0.689540565013885500f, - -0.671558976173400880f, -0.653172850608825680f, -0.634393274784088130f, - -0.615231573581695560f, -0.595699310302734380f, - -0.575808167457580570f, -0.555570244789123540f, -0.534997642040252690f, - -0.514102756977081300f, -0.492898195981979370f, -0.471396744251251220f, - -0.449611335992813110f, -0.427555084228515630f, - -0.405241310596466060f, -0.382683426141738890f, -0.359895050525665280f, - -0.336889863014221190f, -0.313681751489639280f, -0.290284663438797000f, - -0.266712754964828490f, -0.242980182170867920f, - -0.219101235270500180f, -0.195090323686599730f, -0.170961886644363400f, - -0.146730467677116390f, -0.122410677373409270f, -0.098017141222953796f, - -0.073564566671848297f, -0.049067676067352295f, - -0.024541229009628296f, -0.000000000000000245f, 0.024541229009628296f -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for floating-point data. - * @param[in] x input value in radians. - * @return sin(x). - */ - -float32_t arm_sin_f32( - float32_t x) -{ - float32_t sinVal, fract, in; /* Temporary variables for input, output */ - int32_t index; /* Index variable */ - uint32_t tableSize = (uint32_t) TABLE_SIZE; /* Initialise tablesize */ - float32_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - float32_t a, b, c, d; /* Four nearest output values */ - float32_t *tablePtr; /* Pointer to table */ - int32_t n; - float32_t fractsq, fractby2, fractby6, fractby3, fractsqby2; - float32_t oneminusfractby2; - float32_t frby2xfrsq, frby6xfrsq; - - /* input x is in radians */ - /* Scale the input to [0 1] range from [0 2*PI] , divide input by 2*pi */ - in = x * 0.159154943092f; - - /* Calculation of floor value of input */ - n = (int32_t) in; - - /* Make negative values towards -infinity */ - if(x < 0.0f) - { - n = n - 1; - } - - /* Map input value to [0 1] */ - in = in - (float32_t) n; - - /* Calculation of index of the table */ - index = (uint32_t) (tableSize * in); - - /* fractional value calculation */ - fract = ((float32_t) tableSize * in) - (float32_t) index; - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (float32_t *) & sinTable[index]; - - /* Read four nearest values of input value from the sin table */ - a = tablePtr[0]; - b = tablePtr[1]; - c = tablePtr[2]; - d = tablePtr[3]; - - /* Cubic interpolation process */ - fractsq = fract * fract; - fractby2 = fract * 0.5f; - fractby6 = fract * 0.166666667f; - fractby3 = fract * 0.3333333333333f; - fractsqby2 = fractsq * 0.5f; - frby2xfrsq = (fractby2) * fractsq; - frby6xfrsq = (fractby6) * fractsq; - oneminusfractby2 = 1.0f - fractby2; - wb = fractsqby2 - fractby3; - wc = (fractsqby2 + fract); - wa = wb - frby6xfrsq; - wb = frby2xfrsq - fractsq; - sinVal = wa * a; - wc = wc - frby2xfrsq; - wd = (frby6xfrsq) - fractby6; - wb = wb + oneminusfractby2; - - /* Calculate sin value */ - sinVal = (sinVal + (b * wb)) + ((c * wc) + (d * wd)); - - /* Return the output value */ - return (sinVal); - -} - -/** - * @} end of sin group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c deleted file mode 100644 index b53ca3ecc4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q15.c +++ /dev/null @@ -1,208 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sin_q15.c -* -* Description: Fast sine calculation for Q15 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup sin - * @{ - */ - - -/** - * \par - * Example code for Generation of Q15 Sin Table: - * \par - *
tableSize = 256;    
- * for(n = -1; n < (tableSize + 1); n++)    
- * {    
- *	sinTable[n+1]=sin(2*pi*n/tableSize);    
- * } 
- * where pi value is 3.14159265358979 - * \par - * Convert Floating point to Q15(Fixed point): - * (sinTable[i] * pow(2, 15)) - * \par - * rounding to nearest integer is done - * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); - */ - - -static const q15_t sinTableQ15[259] = { - 0xfcdc, 0x0, 0x324, 0x648, 0x96b, 0xc8c, 0xfab, 0x12c8, - 0x15e2, 0x18f9, 0x1c0c, 0x1f1a, 0x2224, 0x2528, 0x2827, 0x2b1f, - 0x2e11, 0x30fc, 0x33df, 0x36ba, 0x398d, 0x3c57, 0x3f17, 0x41ce, - 0x447b, 0x471d, 0x49b4, 0x4c40, 0x4ec0, 0x5134, 0x539b, 0x55f6, - 0x5843, 0x5a82, 0x5cb4, 0x5ed7, 0x60ec, 0x62f2, 0x64e9, 0x66d0, - 0x68a7, 0x6a6e, 0x6c24, 0x6dca, 0x6f5f, 0x70e3, 0x7255, 0x73b6, - 0x7505, 0x7642, 0x776c, 0x7885, 0x798a, 0x7a7d, 0x7b5d, 0x7c2a, - 0x7ce4, 0x7d8a, 0x7e1e, 0x7e9d, 0x7f0a, 0x7f62, 0x7fa7, 0x7fd9, - 0x7ff6, 0x7fff, 0x7ff6, 0x7fd9, 0x7fa7, 0x7f62, 0x7f0a, 0x7e9d, - 0x7e1e, 0x7d8a, 0x7ce4, 0x7c2a, 0x7b5d, 0x7a7d, 0x798a, 0x7885, - 0x776c, 0x7642, 0x7505, 0x73b6, 0x7255, 0x70e3, 0x6f5f, 0x6dca, - 0x6c24, 0x6a6e, 0x68a7, 0x66d0, 0x64e9, 0x62f2, 0x60ec, 0x5ed7, - 0x5cb4, 0x5a82, 0x5843, 0x55f6, 0x539b, 0x5134, 0x4ec0, 0x4c40, - 0x49b4, 0x471d, 0x447b, 0x41ce, 0x3f17, 0x3c57, 0x398d, 0x36ba, - 0x33df, 0x30fc, 0x2e11, 0x2b1f, 0x2827, 0x2528, 0x2224, 0x1f1a, - 0x1c0c, 0x18f9, 0x15e2, 0x12c8, 0xfab, 0xc8c, 0x96b, 0x648, - 0x324, 0x0, 0xfcdc, 0xf9b8, 0xf695, 0xf374, 0xf055, 0xed38, - 0xea1e, 0xe707, 0xe3f4, 0xe0e6, 0xdddc, 0xdad8, 0xd7d9, 0xd4e1, - 0xd1ef, 0xcf04, 0xcc21, 0xc946, 0xc673, 0xc3a9, 0xc0e9, 0xbe32, - 0xbb85, 0xb8e3, 0xb64c, 0xb3c0, 0xb140, 0xaecc, 0xac65, 0xaa0a, - 0xa7bd, 0xa57e, 0xa34c, 0xa129, 0x9f14, 0x9d0e, 0x9b17, 0x9930, - 0x9759, 0x9592, 0x93dc, 0x9236, 0x90a1, 0x8f1d, 0x8dab, 0x8c4a, - 0x8afb, 0x89be, 0x8894, 0x877b, 0x8676, 0x8583, 0x84a3, 0x83d6, - 0x831c, 0x8276, 0x81e2, 0x8163, 0x80f6, 0x809e, 0x8059, 0x8027, - 0x800a, 0x8000, 0x800a, 0x8027, 0x8059, 0x809e, 0x80f6, 0x8163, - 0x81e2, 0x8276, 0x831c, 0x83d6, 0x84a3, 0x8583, 0x8676, 0x877b, - 0x8894, 0x89be, 0x8afb, 0x8c4a, 0x8dab, 0x8f1d, 0x90a1, 0x9236, - 0x93dc, 0x9592, 0x9759, 0x9930, 0x9b17, 0x9d0e, 0x9f14, 0xa129, - 0xa34c, 0xa57e, 0xa7bd, 0xaa0a, 0xac65, 0xaecc, 0xb140, 0xb3c0, - 0xb64c, 0xb8e3, 0xbb85, 0xbe32, 0xc0e9, 0xc3a9, 0xc673, 0xc946, - 0xcc21, 0xcf04, 0xd1ef, 0xd4e1, 0xd7d9, 0xdad8, 0xdddc, 0xe0e6, - 0xe3f4, 0xe707, 0xea1e, 0xed38, 0xf055, 0xf374, 0xf695, 0xf9b8, - 0xfcdc, 0x0, 0x324 -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - * - * The Q15 input value is in the range [0 +0.9999] and is mapped to a radian value in the range [0 2*pi), Here range excludes 2*pi. - */ - -q15_t arm_sin_q15( - q15_t x) -{ - q31_t sinVal; /* Temporary variables output */ - q15_t *tablePtr; /* Pointer to table */ - q15_t fract, in, in2; /* Temporary variables for input, output */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q15_t a, b, c, d; /* Four nearest output values */ - q15_t fractCube, fractSquare; /* Temporary values for fractional value */ - q15_t oneBy6 = 0x1555; /* Fixed point value of 1/6 */ - q15_t tableSpacing = TABLE_SPACING_Q15; /* Table spacing */ - int32_t index; /* Index variable */ - - in = x; - - /* Calculate the nearest index */ - index = (int32_t) in / tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q15_t) ((index) * tableSpacing); - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = (q15_t) ((fract * fract) >> 15); - - /* fractCube = fract * fract * fract */ - fractCube = (q15_t) ((fractSquare * fract) >> 15); - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (q15_t *) & sinTableQ15[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAA)*fract; */ - wa = (q31_t) oneBy6 *fractCube; - wa += (q31_t) 0x2AAA *fract; - wa = -(wa >> 15); - wa += ((q31_t) fractSquare >> 1u); - - /* Read first nearest value of output from the sin table */ - a = *tablePtr++; - - /* sinVal = a * wa */ - sinVal = a * wa; - - /* Calculation of wb */ - wb = (((q31_t) fractCube >> 1u) - (q31_t) fractSquare) - - (((q31_t) fract >> 1u) - 0x7FFF); - - /* Read second nearest value of output from the sin table */ - b = *tablePtr++; - - /* sinVal += b*wb */ - sinVal += b * wb; - - - /* Calculation of wc */ - wc = -(q31_t) fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the sin table */ - c = *tablePtr++; - - /* sinVal += c*wc */ - sinVal += c * wc; - - /* Calculation of wd */ - /* wd = (oneBy6)*fractCube - (oneBy6)*fract; */ - fractCube = fractCube - fract; - wd = ((q15_t) (((q31_t) oneBy6 * fractCube) >> 15)); - - /* Read fourth nearest value of output from the sin table */ - d = *tablePtr++; - - /* sinVal += d*wd; */ - sinVal += d * wd; - - /* Convert output value in 1.15(q15) format and saturate */ - sinVal = __SSAT((sinVal >> 15), 16); - - /* Return the output value in 1.15(q15) format */ - return ((q15_t) sinVal); - -} - -/** - * @} end of sin group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c deleted file mode 100644 index 336796b5c1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sin_q31.c +++ /dev/null @@ -1,240 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sin_q31.c -* -* Description: Fast sine calculation for Q31 values. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFastMath - */ - - /** - * @addtogroup sin - * @{ - */ - -/** - * \par - * Tables generated are in Q31(1.31 Fixed point format) - * Generation of sin values in floating point: - *
tableSize = 256;      
- * for(n = -1; n < (tableSize + 1); n++)    
- * {    
- *	sinTable[n+1]= sin(2*pi*n/tableSize);    
- * } 
- * where pi value is 3.14159265358979 - * \par - * Convert Floating point to Q31(Fixed point): - * (sinTable[i] * pow(2, 31)) - * \par - * rounding to nearest integer is done - * sinTable[i] += (sinTable[i] > 0 ? 0.5 :-0.5); - */ - -static const q31_t sinTableQ31[259] = { - 0xfcdbd541, 0x0, 0x3242abf, 0x647d97c, 0x96a9049, 0xc8bd35e, 0xfab272b, - 0x12c8106f, - 0x15e21445, 0x18f8b83c, 0x1c0b826a, 0x1f19f97b, 0x2223a4c5, 0x25280c5e, - 0x2826b928, 0x2b1f34eb, - 0x2e110a62, 0x30fbc54d, 0x33def287, 0x36ba2014, 0x398cdd32, 0x3c56ba70, - 0x3f1749b8, 0x41ce1e65, - 0x447acd50, 0x471cece7, 0x49b41533, 0x4c3fdff4, 0x4ebfe8a5, 0x5133cc94, - 0x539b2af0, 0x55f5a4d2, - 0x5842dd54, 0x5a82799a, 0x5cb420e0, 0x5ed77c8a, 0x60ec3830, 0x62f201ac, - 0x64e88926, 0x66cf8120, - 0x68a69e81, 0x6a6d98a4, 0x6c242960, 0x6dca0d14, 0x6f5f02b2, 0x70e2cbc6, - 0x72552c85, 0x73b5ebd1, - 0x7504d345, 0x7641af3d, 0x776c4edb, 0x78848414, 0x798a23b1, 0x7a7d055b, - 0x7b5d039e, 0x7c29fbee, - 0x7ce3ceb2, 0x7d8a5f40, 0x7e1d93ea, 0x7e9d55fc, 0x7f0991c4, 0x7f62368f, - 0x7fa736b4, 0x7fd8878e, - 0x7ff62182, 0x7fffffff, 0x7ff62182, 0x7fd8878e, 0x7fa736b4, 0x7f62368f, - 0x7f0991c4, 0x7e9d55fc, - 0x7e1d93ea, 0x7d8a5f40, 0x7ce3ceb2, 0x7c29fbee, 0x7b5d039e, 0x7a7d055b, - 0x798a23b1, 0x78848414, - 0x776c4edb, 0x7641af3d, 0x7504d345, 0x73b5ebd1, 0x72552c85, 0x70e2cbc6, - 0x6f5f02b2, 0x6dca0d14, - 0x6c242960, 0x6a6d98a4, 0x68a69e81, 0x66cf8120, 0x64e88926, 0x62f201ac, - 0x60ec3830, 0x5ed77c8a, - 0x5cb420e0, 0x5a82799a, 0x5842dd54, 0x55f5a4d2, 0x539b2af0, 0x5133cc94, - 0x4ebfe8a5, 0x4c3fdff4, - 0x49b41533, 0x471cece7, 0x447acd50, 0x41ce1e65, 0x3f1749b8, 0x3c56ba70, - 0x398cdd32, 0x36ba2014, - 0x33def287, 0x30fbc54d, 0x2e110a62, 0x2b1f34eb, 0x2826b928, 0x25280c5e, - 0x2223a4c5, 0x1f19f97b, - 0x1c0b826a, 0x18f8b83c, 0x15e21445, 0x12c8106f, 0xfab272b, 0xc8bd35e, - 0x96a9049, 0x647d97c, - 0x3242abf, 0x0, 0xfcdbd541, 0xf9b82684, 0xf6956fb7, 0xf3742ca2, 0xf054d8d5, - 0xed37ef91, - 0xea1debbb, 0xe70747c4, 0xe3f47d96, 0xe0e60685, 0xdddc5b3b, 0xdad7f3a2, - 0xd7d946d8, 0xd4e0cb15, - 0xd1eef59e, 0xcf043ab3, 0xcc210d79, 0xc945dfec, 0xc67322ce, 0xc3a94590, - 0xc0e8b648, 0xbe31e19b, - 0xbb8532b0, 0xb8e31319, 0xb64beacd, 0xb3c0200c, 0xb140175b, 0xaecc336c, - 0xac64d510, 0xaa0a5b2e, - 0xa7bd22ac, 0xa57d8666, 0xa34bdf20, 0xa1288376, 0x9f13c7d0, 0x9d0dfe54, - 0x9b1776da, 0x99307ee0, - 0x9759617f, 0x9592675c, 0x93dbd6a0, 0x9235f2ec, 0x90a0fd4e, 0x8f1d343a, - 0x8daad37b, 0x8c4a142f, - 0x8afb2cbb, 0x89be50c3, 0x8893b125, 0x877b7bec, 0x8675dc4f, 0x8582faa5, - 0x84a2fc62, 0x83d60412, - 0x831c314e, 0x8275a0c0, 0x81e26c16, 0x8162aa04, 0x80f66e3c, 0x809dc971, - 0x8058c94c, 0x80277872, - 0x8009de7e, 0x80000000, 0x8009de7e, 0x80277872, 0x8058c94c, 0x809dc971, - 0x80f66e3c, 0x8162aa04, - 0x81e26c16, 0x8275a0c0, 0x831c314e, 0x83d60412, 0x84a2fc62, 0x8582faa5, - 0x8675dc4f, 0x877b7bec, - 0x8893b125, 0x89be50c3, 0x8afb2cbb, 0x8c4a142f, 0x8daad37b, 0x8f1d343a, - 0x90a0fd4e, 0x9235f2ec, - 0x93dbd6a0, 0x9592675c, 0x9759617f, 0x99307ee0, 0x9b1776da, 0x9d0dfe54, - 0x9f13c7d0, 0xa1288376, - 0xa34bdf20, 0xa57d8666, 0xa7bd22ac, 0xaa0a5b2e, 0xac64d510, 0xaecc336c, - 0xb140175b, 0xb3c0200c, - 0xb64beacd, 0xb8e31319, 0xbb8532b0, 0xbe31e19b, 0xc0e8b648, 0xc3a94590, - 0xc67322ce, 0xc945dfec, - 0xcc210d79, 0xcf043ab3, 0xd1eef59e, 0xd4e0cb15, 0xd7d946d8, 0xdad7f3a2, - 0xdddc5b3b, 0xe0e60685, - 0xe3f47d96, 0xe70747c4, 0xea1debbb, 0xed37ef91, 0xf054d8d5, 0xf3742ca2, - 0xf6956fb7, 0xf9b82684, - 0xfcdbd541, 0x0, 0x3242abf -}; - - -/** - * @brief Fast approximation to the trigonometric sine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - * - * The Q31 input value is in the range [0 +0.9999] and is mapped to a radian value in the range [0 2*pi), Here range excludes 2*pi. - */ - -q31_t arm_sin_q31( - q31_t x) -{ - q31_t sinVal, in, in2; /* Temporary variables for input, output */ - int32_t index; /* Index variables */ - q31_t wa, wb, wc, wd; /* Cubic interpolation coefficients */ - q31_t a, b, c, d; /* Four nearest output values */ - q31_t *tablePtr; /* Pointer to table */ - q31_t fract, fractCube, fractSquare; /* Temporary values for fractional values */ - q31_t oneBy6 = 0x15555555; /* Fixed point value of 1/6 */ - q31_t tableSpacing = TABLE_SPACING_Q31; /* Table spacing */ - q31_t temp; /* Temporary variable for intermediate process */ - - in = x; - - /* Calculate the nearest index */ - index = (uint32_t) in / (uint32_t) tableSpacing; - - /* Calculate the nearest value of input */ - in2 = (q31_t) index *tableSpacing; - - /* Calculation of fractional value */ - fract = (in - in2) << 8; - - /* fractSquare = fract * fract */ - fractSquare = ((q31_t) (((q63_t) fract * fract) >> 32)); - fractSquare = fractSquare << 1; - - /* fractCube = fract * fract * fract */ - fractCube = ((q31_t) (((q63_t) fractSquare * fract) >> 32)); - fractCube = fractCube << 1; - - /* Checking min and max index of table */ - if(index < 0) - { - index = 0; - } - else if(index > 256) - { - index = 256; - } - - /* Initialise table pointer */ - tablePtr = (q31_t *) & sinTableQ31[index]; - - /* Cubic interpolation process */ - /* Calculation of wa */ - /* wa = -(oneBy6)*fractCube + (fractSquare >> 1u) - (0x2AAAAAAA)*fract; */ - wa = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - temp = 0x2AAAAAAA; - wa = (q31_t) ((((q63_t) wa << 32) + ((q63_t) temp * fract)) >> 32); - wa = -(wa << 1u); - wa += (fractSquare >> 1u); - - /* Read first nearest value of output from the sin table */ - a = *tablePtr++; - - /* sinVal = a*wa */ - sinVal = ((q31_t) (((q63_t) a * wa) >> 32)); - - /* q31(1.31) Fixed point value of 1 */ - temp = 0x7FFFFFFF; - - /* Calculation of wb */ - wb = ((fractCube >> 1u) - (fractSquare + (fract >> 1u))) + temp; - - /* Read second nearest value of output from the sin table */ - b = *tablePtr++; - - /* sinVal += b*wb */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + (q63_t) b * (wb)) >> 32); - - /* Calculation of wc */ - wc = -fractCube + fractSquare; - wc = (wc >> 1u) + fract; - - /* Read third nearest value of output from the sin table */ - c = *tablePtr++; - - /* sinVal += c*wc */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) c * wc)) >> 32); - - /* Calculation of wd */ - /* wd = (oneBy6) * fractCube - (oneBy6) * fract; */ - fractCube = fractCube - fract; - wd = ((q31_t) (((q63_t) oneBy6 * fractCube) >> 32)); - wd = (wd << 1u); - - /* Read fourth nearest value of output from the sin table */ - d = *tablePtr++; - - /* sinVal += d*wd; */ - sinVal = (q31_t) ((((q63_t) sinVal << 32) + ((q63_t) d * wd)) >> 32); - - /* convert sinVal in 2.30 format to 1.31 format */ - return (__QADD(sinVal, sinVal)); - -} - -/** - * @} end of sin group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c deleted file mode 100644 index 0a6d6a53a2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q15.c +++ /dev/null @@ -1,131 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2011 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sqrt_q15.c -* -* Description: Q15 square root function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.0 2011/03/08 -* Alpha release. -* -* Version 1.0.1 2011/09/30 -* Beta release. -* -* -------------------------------------------------------------------- */ -#include "arm_math.h" -#include "arm_common_tables.h" - - -/** - * @ingroup groupFastMath - */ - -/** - * @addtogroup SQRT - * @{ - */ - - /** - * @brief Q15 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. - * @param[out] *pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - -arm_status arm_sqrt_q15( - q15_t in, - q15_t * pOut) -{ - q15_t number, temp1, var1, signBits1, half; - q31_t bits_val1; - float32_t temp_float1; - - number = in; - - /* If the input is a positive number then compute the signBits. */ - if(number > 0) - { - signBits1 = __CLZ(number) - 17; - - /* Shift by the number of signBits1 */ - if((signBits1 % 2) == 0) - { - number = number << signBits1; - } - else - { - number = number << (signBits1 - 1); - } - - /* Calculate half value of the number */ - half = number >> 1; - /* Store the number for later use */ - temp1 = number; - - /*Convert to float */ - temp_float1 = number * 3.051757812500000e-005f; - /*Store as integer */ - bits_val1 = *(int *) &temp_float1; - /* Subtract the shifted value from the magic number to give intial guess */ - bits_val1 = 0x5f3759df - (bits_val1 >> 1); // gives initial guess - /* Store as float */ - temp_float1 = *(float *) &bits_val1; - /* Convert to integer format */ - var1 = (q31_t) (temp_float1 * 16384); - - /* 1st iteration */ - var1 = ((q15_t) ((q31_t) var1 * (0x3000 - - ((q15_t) - ((((q15_t) - (((q31_t) var1 * var1) >> 15)) * - (q31_t) half) >> 15))) >> 15)) << 2; - /* 2nd iteration */ - var1 = ((q15_t) ((q31_t) var1 * (0x3000 - - ((q15_t) - ((((q15_t) - (((q31_t) var1 * var1) >> 15)) * - (q31_t) half) >> 15))) >> 15)) << 2; - /* 3rd iteration */ - var1 = ((q15_t) ((q31_t) var1 * (0x3000 - - ((q15_t) - ((((q15_t) - (((q31_t) var1 * var1) >> 15)) * - (q31_t) half) >> 15))) >> 15)) << 2; - - /* Multiply the inverse square root with the original value */ - var1 = ((q15_t) (((q31_t) temp1 * var1) >> 15)) << 1; - - /* Shift the output down accordingly */ - if((signBits1 % 2) == 0) - { - var1 = var1 >> (signBits1 / 2); - } - else - { - var1 = var1 >> ((signBits1 - 1) / 2); - } - *pOut = var1; - - return (ARM_MATH_SUCCESS); - } - /* If the number is a negative number then store zero as its square root value */ - else - { - *pOut = 0; - return (ARM_MATH_ARGUMENT_ERROR); - } -} - -/** - * @} end of SQRT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c deleted file mode 100644 index 2a3b7ac18d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FastMathFunctions/arm_sqrt_q31.c +++ /dev/null @@ -1,129 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2011 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_sqrt_q31.c -* -* Description: Q31 square root function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.0 2011/03/08 -* Alpha release. -* -* Version 1.0.1 2011/09/30 -* Beta release. -* -* -------------------------------------------------------------------- */ -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupFastMath - */ - -/** - * @addtogroup SQRT - * @{ - */ - -/** - * @brief Q31 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. - * @param[out] *pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - -arm_status arm_sqrt_q31( - q31_t in, - q31_t * pOut) -{ - q31_t number, temp1, bits_val1, var1, signBits1, half; - float32_t temp_float1; - - number = in; - - /* If the input is a positive number then compute the signBits. */ - if(number > 0) - { - signBits1 = __CLZ(number) - 1; - - /* Shift by the number of signBits1 */ - if((signBits1 % 2) == 0) - { - number = number << signBits1; - } - else - { - number = number << (signBits1 - 1); - } - - /* Calculate half value of the number */ - half = number >> 1; - /* Store the number for later use */ - temp1 = number; - - /*Convert to float */ - temp_float1 = number * 4.6566128731e-010f; - /*Store as integer */ - bits_val1 = *(int *) &temp_float1; - /* Subtract the shifted value from the magic number to give intial guess */ - bits_val1 = 0x5f3759df - (bits_val1 >> 1); // gives initial guess - /* Store as float */ - temp_float1 = *(float *) &bits_val1; - /* Convert to integer format */ - var1 = (q31_t) (temp_float1 * 1073741824); - - /* 1st iteration */ - var1 = ((q31_t) ((q63_t) var1 * (0x30000000 - - ((q31_t) - ((((q31_t) - (((q63_t) var1 * var1) >> 31)) * - (q63_t) half) >> 31))) >> 31)) << 2; - /* 2nd iteration */ - var1 = ((q31_t) ((q63_t) var1 * (0x30000000 - - ((q31_t) - ((((q31_t) - (((q63_t) var1 * var1) >> 31)) * - (q63_t) half) >> 31))) >> 31)) << 2; - /* 3rd iteration */ - var1 = ((q31_t) ((q63_t) var1 * (0x30000000 - - ((q31_t) - ((((q31_t) - (((q63_t) var1 * var1) >> 31)) * - (q63_t) half) >> 31))) >> 31)) << 2; - - /* Multiply the inverse square root with the original value */ - var1 = ((q31_t) (((q63_t) temp1 * var1) >> 31)) << 1; - - /* Shift the output down accordingly */ - if((signBits1 % 2) == 0) - { - var1 = var1 >> (signBits1 / 2); - } - else - { - var1 = var1 >> ((signBits1 - 1) / 2); - } - *pOut = var1; - - return (ARM_MATH_SUCCESS); - } - /* If the number is a negative number then store zero as its square root value */ - else - { - *pOut = 0; - return (ARM_MATH_ARGUMENT_ERROR); - } -} - -/** - * @} end of SQRT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c deleted file mode 100644 index a6745c0cd4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_init_q31.c +++ /dev/null @@ -1,105 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_32x64_init_q31.c -* -* Description: High precision Q31 Biquad cascade filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1_32x64 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format. - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
    
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}    
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState points to state variables array and size of each state variable is 1.63 format. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the state array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cas_df1_32x64_init_q31( - arm_biquad_cas_df1_32x64_ins_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q63_t * pState, - uint8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q63_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1_32x64 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c deleted file mode 100644 index 82d6164ee1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_32x64_q31.c +++ /dev/null @@ -1,553 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_32x64_q31.c -* -* Description: High precision Q31 Biquad cascade filter processing function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF1_32x64 High Precision Q31 Biquad Cascade Filter - * - * This function implements a high precision Biquad cascade filter which operates on - * Q31 data values. The filter coefficients are in 1.31 format and the state variables - * are in 1.63 format. The double precision state variables reduce quantization noise - * in the filter and provide a cleaner output. - * These filters are particularly useful when implementing filters in which the - * singularities are close to the unit circle. This is common for low pass or high - * pass filters with very low cutoff frequencies. - * - * The function operates on blocks of input and output data - * and each call to the function processes blockSize samples through - * the filter. pSrc and pDst points to input and output arrays - * containing blockSize Q31 values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
    
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]    
- * 
- * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. - * \image html Biquad.gif "Single Biquad filter stage" - * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools use the difference equation - *
    
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]    
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" - * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * The pState points to state variables array . - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2] and each state variable in 1.63 format to improve precision. - * The state variables are arranged in the array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * - * \par - * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values of data in 1.63 format. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * - * \par Init Function - * There is also an associated initialization function which performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * For example, to statically initialize the filter instance structure use - *
    
- *     arm_biquad_cas_df1_32x64_ins_q31 S1 = {numStages, pState, pCoeffs, postShift};    
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; postShift shift to be applied which is described in detail below. - * \par Fixed-Point Behavior - * Care must be taken while using Biquad Cascade 32x64 filter function. - * Following issues must be considered: - * - Scaling of coefficients - * - Filter gain - * - Overflow and saturation - * - * \par - * Filter coefficients are represented as fractional values and - * restricted to lie in the range [-1 +1). - * The processing function has an additional scaling parameter postShift - * which allows the filter coefficients to exceed the range [+1 -1). - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" - * This essentially scales the filter coefficients by 2^postShift. - * For example, to realize the coefficients - *
    
- *    {1.5, -0.8, 1.2, 1.6, -0.9}    
- * 
- * set the Coefficient array to: - *
    
- *    {0.75, -0.4, 0.6, 0.8, -0.45}    
- * 
- * and set postShift=1 - * - * \par - * The second thing to keep in mind is the gain through the filter. - * The frequency response of a Biquad filter is a function of its coefficients. - * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. - * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. - * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. - * - * \par - * The third item to consider is the overflow and saturation behavior of the fixed-point Q31 version. - * This is described in the function specific documentation below. - */ - -/** - * @addtogroup BiquadCascadeDF1_32x64 - * @{ - */ - -/** - * @details - - * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). - * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to - * 1.31 format by discarding the low 32 bits. - * - * \par - * Two related functions are provided in the CMSIS DSP library. - * arm_biquad_cascade_df1_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q63 accumulator. - * arm_biquad_cascade_df1_fast_q31() implements a Biquad cascade with 32-bit coefficients and state variables with a Q31 accumulator. - */ - -void arm_biquad_cas_df1_32x64_q31( - const arm_biquad_cas_df1_32x64_ins_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q63_t *pState = S->pState; /* state pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q63_t acc; /* accumulator */ - q31_t Xn1, Xn2; /* Input Filter state variables */ - q63_t Yn1, Yn2; /* Output Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q31_t Xn; /* temporary input */ - int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ - uint32_t sample, stage = S->numStages; /* loop counters */ - q31_t acc_l, acc_h; /* temporary output */ - uint32_t uShift = ((uint32_t) S->postShift + 1u); - uint32_t lShift = 32u - uShift; /* Shift to be applied to the output */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = (q31_t) (pState[0]); - Xn2 = (q31_t) (pState[1]); - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output value that is being computed and - * stored in the destination buffer - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) Xn *b0; - - /* acc += b1 * x[n-1] */ - acc += (q63_t) Xn1 *b1; - - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn2 *b2; - - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* The result is converted to 1.63 , Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut = acc_h; - - /* Read the second input into Xn2, to reuse the value */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc += b1 * x[n-1] */ - acc = (q63_t) Xn *b1; - - /* acc = b0 * x[n] */ - acc += (q63_t) Xn2 *b0; - - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn1 *b2; - - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn2, a1); - - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn1, a2); - - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Read the third input into Xn1, to reuse the value */ - Xn1 = *pIn++; - - /* The result is converted to 1.31 */ - /* Store the output in the destination buffer. */ - *(pOut + 1u) = acc_h; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) Xn1 *b0; - - /* acc += b1 * x[n-1] */ - acc += (q63_t) Xn2 *b1; - - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn *b2; - - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* The result is converted to 1.63, Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer in 1.31 format. */ - *(pOut + 2u) = acc_h; - - /* Read the fourth input into Xn, to reuse the value */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q63_t) Xn *b0; - - /* acc += b1 * x[n-1] */ - acc += (q63_t) Xn1 *b1; - - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn2 *b2; - - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn2, a1); - - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn1, a2); - - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer in 1.31 format. */ - *(pOut + 3u) = acc_h; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* update output pointer */ - pOut += 4u; - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) Xn *b0; - /* acc += b1 * x[n-1] */ - acc += (q63_t) Xn1 *b1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn2 *b2; - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = acc_h; - //Yn1 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ -// *pOut++ = (q31_t) (acc >> (32 - shift)); - - /* decrement the loop counter */ - sample--; - } - - /* The first stage output is given as input to the second stage. */ - pIn = pDst; - - /* Reset to destination buffer working pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - /* Store the updated state variables back into the pState array */ - *pState++ = (q63_t) Xn1; - *pState++ = (q63_t) Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variable acc hold output value that is being computed and - * stored in the destination buffer - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q63_t) Xn *b0; - /* acc += b1 * x[n-1] */ - acc += (q63_t) Xn1 *b1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) Xn2 *b2; - /* acc += a1 * y[n-1] */ - acc += mult32x64(Yn1, a1); - /* acc += a2 * y[n-2] */ - acc += mult32x64(Yn2, a2); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - - /* The result is converted to 1.63, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc_h = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer in 1.31 format. */ - *pOut++ = acc_h; - - //Yn1 = acc << shift; - - /* Store the output in the destination buffer in 1.31 format. */ - //*pOut++ = (q31_t) (acc >> (32 - shift)); - - /* decrement the loop counter */ - sample--; - } - - /* The first stage output is given as input to the second stage. */ - pIn = pDst; - - /* Reset to destination buffer working pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = (q63_t) Xn1; - *pState++ = (q63_t) Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ -} - - /** - * @} end of BiquadCascadeDF1_32x64 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c deleted file mode 100644 index ee20dfeec2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_f32.c +++ /dev/null @@ -1,421 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_f32.c -* -* Description: Processing function for the -* floating-point Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF1 Biquad Cascade IIR Filters Using Direct Form I Structure - * - * This set of functions implements arbitrary order recursive (IIR) filters. - * The filters are implemented as a cascade of second order Biquad sections. - * The functions support Q15, Q31 and floating-point data types. - * Fast version of Q15 and Q31 also supported on CortexM4 and Cortex-M3. - * - * The functions operate on blocks of input and output data and each call to the function - * processes blockSize samples through the filter. - * pSrc points to the array of input data and - * pDst points to the array of output data. - * Both arrays contain blockSize values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
    
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2]    
- * 
- * A Direct Form I algorithm is used with 5 coefficients and 4 state variables per stage. - * \image html Biquad.gif "Single Biquad filter stage" - * Coefficients b0, b1 and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools use the difference equation - *
    
- *     y[n] = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] - a1 * y[n-1] - a2 * y[n-2]    
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * \image html BiquadCascade.gif "8th order filter using a cascade of Biquad stages" - * A 9th order filter would be realized with numStages=5 second order stages with the coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * The pState points to state variables array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * - * \par - * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Init Functions - * There is also an associated initialization function for each data type. - * The initialization function performs following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 3 different data type filter instance structures - *
    
- *     arm_biquad_casd_df1_inst_f32 S1 = {numStages, pState, pCoeffs};    
- *     arm_biquad_casd_df1_inst_q15 S2 = {numStages, pState, pCoeffs, postShift};    
- *     arm_biquad_casd_df1_inst_q31 S3 = {numStages, pState, pCoeffs, postShift};    
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; postShift shift to be applied. - * - * \par Fixed-Point Behavior - * Care must be taken when using the Q15 and Q31 versions of the Biquad Cascade filter functions. - * Following issues must be considered: - * - Scaling of coefficients - * - Filter gain - * - Overflow and saturation - * - * \par - * Scaling of coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift - * which allow the filter coefficients to exceed the range [+1 -1). - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * \image html BiquadPostshift.gif "Fixed-point Biquad with shift by postShift bits after accumulator" - * This essentially scales the filter coefficients by 2^postShift. - * For example, to realize the coefficients - *
    
- *    {1.5, -0.8, 1.2, 1.6, -0.9}    
- * 
- * set the pCoeffs array to: - *
    
- *    {0.75, -0.4, 0.6, 0.8, -0.45}    
- * 
- * and set postShift=1 - * - * \par - * Filter gain: - * The frequency response of a Biquad filter is a function of its coefficients. - * It is possible for the gain through the filter to exceed 1.0 meaning that the filter increases the amplitude of certain frequencies. - * This means that an input signal with amplitude < 1.0 may result in an output > 1.0 and these are saturated or overflowed based on the implementation of the filter. - * To avoid this behavior the filter needs to be scaled down such that its peak gain < 1.0 or the input signal must be scaled down so that the combination of input and filter are never overflowed. - * - * \par - * Overflow and saturation: - * For Q15 and Q31 versions, it is described separately as part of the function specific documentation below. - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @param[in] *S points to an instance of the floating-point Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - */ - -void arm_biquad_cascade_df1_f32( - const arm_biquad_casd_df1_inst_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* source pointer */ - float32_t *pOut = pDst; /* destination pointer */ - float32_t *pState = S->pState; /* pState pointer */ - float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ - float32_t acc; /* Simulates the accumulator */ - float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ - float32_t Xn1, Xn2, Yn1, Yn2; /* Filter pState variables */ - float32_t Xn; /* temporary input */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the pState values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the first input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn2 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn2; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the second input */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn1 = (b0 * Xn2) + (b1 * Xn) + (b2 * Xn1) + (a1 * Yn2) + (a2 * Yn1); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn1; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the third input */ - Xn1 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn2 = (b0 * Xn1) + (b1 * Xn2) + (b2 * Xn) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn2; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - - /* Read the forth input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - Yn1 = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn2) + (a2 * Yn1); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = Yn1; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = blockSize & 0x3u; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* decrement the loop counter */ - sample--; - - } - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent numStages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the pState values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - acc = (b0 * Xn) + (b1 * Xn1) + (b2 * Xn2) + (a1 * Yn1) + (a2 * Yn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent numStages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - /** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c deleted file mode 100644 index 29afffa03c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q15.c +++ /dev/null @@ -1,283 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_fast_q15.c -* -* Description: Fast processing function for the -* Q15 Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/16 -* Initial version -* -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * @param[in] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). - * The 2.30 accumulator is then shifted by postShift bits and the result truncated to 1.15 format by discarding the low 16 bits. - * - * \par - * Refer to the function arm_biquad_cascade_df1_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. - * Use the function arm_biquad_cascade_df1_init_q15() to initialize the filter structure. - * - */ - -void arm_biquad_cascade_df1_fast_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q31_t in; /* Temporary variable to hold input value */ - q31_t out; /* Temporary variable to hold output value */ - q31_t b0; /* Temporary variable to hold bo value */ - q31_t b1, a1; /* Filter coefficients */ - q31_t state_in, state_out; /* Filter state variables */ - q31_t acc; /* Accumulator */ - int32_t shift = (int32_t) (15 - S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - uint32_t sample, stage = S->numStages; /* Stage loop counter */ - - - - do - { - - /* Read the b0 and 0 coefficients using SIMD */ - b0 = *__SIMD32(pCoeffs)++; - - /* Read the b1 and b2 coefficients using SIMD */ - b1 = *__SIMD32(pCoeffs)++; - - /* Read the a1 and a2 coefficients using SIMD */ - a1 = *__SIMD32(pCoeffs)++; - - /* Read the input state values from the state buffer: x[n-1], x[n-2] */ - state_in = *__SIMD32(pState)++; - - /* Read the output state values from the state buffer: y[n-1], y[n-2] */ - state_out = *__SIMD32(pState)--; - - /* Apply loop unrolling and compute 2 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - sample = blockSize >> 1u; - - /* First part of the processing with loop unrolling. Compute 2 outputs at a time. - ** a second loop below computes the remaining 1 sample. */ - while(sample > 0u) - { - - /* Read the input */ - in = *__SIMD32(pIn)++; - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUAD(b0, in); - /* acc = b1 * x[n-1] + acc += b2 * x[n-2] + out */ - acc = __SMLAD(b1, state_in, out); - /* acc += a1 * y[n-1] + acc += a2 * y[n-2] */ - acc = __SMLAD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, (in >> 16), 16); - state_out = __PKHBT(state_out >> 16, (out), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUADX(b0, in); - /* acc0 = b1 * x[n-1] , acc0 += b2 * x[n-2] + out */ - acc = __SMLAD(b1, state_in, out); - /* acc += a1 * y[n-1] + acc += a2 * y[n-2] */ - acc = __SMLAD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - - /* Store the output in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in >> 16, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - - if((blockSize & 0x1u) != 0u) - { - /* Read the input */ - in = *pIn++; - - /* out = b0 * x[n] + 0 * 0 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out = __SMUAD(b0, in); - -#else - - out = __SMUADX(b0, in); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc = b1 * x[n-1], acc += b2 * x[n-2] + out */ - acc = __SMLAD(b1, state_in, out); - /* acc += a1 * y[n-1] + acc += a2 * y[n-2] */ - acc = __SMLAD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 and then saturation is applied */ - out = __SSAT((acc >> shift), 16); - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) out; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent (numStages - 1) occur in-place in the output buffer */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* Store the updated state variables back into the state array */ - *__SIMD32(pState)++ = state_in; - *__SIMD32(pState)++ = state_out; - - - /* Decrement the loop counter */ - stage--; - - } while(stage > 0u); -} - - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c deleted file mode 100644 index 0a479fe6b8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_fast_q31.c +++ /dev/null @@ -1,275 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_fast_q31.c -* -* Description: Processing function for the -* Q31 Fast Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/27 -* Initial version -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by two bits and lie in the range [-0.25 +0.25). Use the intialization function - * arm_biquad_cascade_df1_init_q31() to initialize filter structure. - * - * \par - * Refer to the function arm_biquad_cascade_df1_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. Both the slow and the fast versions use the same instance structure. - * Use the function arm_biquad_cascade_df1_init_q31() to initialize the filter structure. - */ - -void arm_biquad_cascade_df1_fast_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t acc; /* accumulator */ - q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q31_t *pState = S->pState; /* pState pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q31_t Xn; /* temporary input */ - int32_t shift = (int32_t) S->postShift + 1; /* Shift to be applied to the output */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variables acc ... acc3 hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b1 * Xn1) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b0 * (Xn))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - - /* The result is converted to 1.31 , Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Read the second input */ - Xn2 = *(pIn + 1u); - - /* Store the output in the destination buffer. */ - *pOut = Yn2; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn2)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn1))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Read the third input */ - Xn1 = *(pIn + 2u); - - /* Store the output in the destination buffer. */ - *(pOut + 1u) = Yn1; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn1)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn2))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - - /* The result is converted to 1.31, Yn2 variable is reused */ - Yn2 = acc << shift; - - /* Read the forth input */ - Xn = *(pIn + 3u); - - /* Store the output in the destination buffer. */ - *(pOut + 2u) = Yn2; - pIn += 4u; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn2))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn1))) >> 32); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - Xn2 = Xn1; - - /* The result is converted to 1.31, Yn1 variable is reused */ - Yn1 = acc << shift; - - /* Xn1 = Xn */ - Xn1 = Xn; - - /* Store the output in the destination buffer. */ - *(pOut + 3u) = Yn1; - pOut += 4u; - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) (((q63_t) b0 * (Xn)) >> 32); - /* acc += b1 * x[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b1 * (Xn1))) >> 32); - /* acc += b[2] * x[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) b2 * (Xn2))) >> 32); - /* acc += a1 * y[n-1] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a1 * (Yn1))) >> 32); - /* acc += a2 * y[n-2] */ - acc = (q31_t) ((((q63_t) acc << 32) + ((q63_t) a2 * (Yn2))) >> 32); - /* The result is converted to 1.31 */ - acc = acc << shift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = acc; - - /* Store the output in the destination buffer. */ - *pOut++ = acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); -} - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c deleted file mode 100644 index d50b69f3c1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_f32.c +++ /dev/null @@ -1,107 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_f32.c -* -* Description: floating-point Biquad cascade DirectFormI(DF1) filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * @brief Initialization function for the floating-point Biquad cascade filter. - * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients array. - * @param[in] *pState points to the state array. - * @return none - * - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
    
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}    
- * 
- * - * \par - * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState is a pointer to state array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - */ - -void arm_biquad_cascade_df1_init_f32( - arm_biquad_casd_df1_inst_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c deleted file mode 100644 index d5fda28ac5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q15.c +++ /dev/null @@ -1,109 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_q15.c -* -* Description: Q15 Biquad cascade DirectFormI(DF1) filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied to the accumulator result. Varies according to the coefficients format - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
    
- *     {b10, 0, b11, b12, a11, a12, b20, 0, b21, b22, a21, a22, ...}    
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 6*numStages values. - * The zero coefficient between b1 and b2 facilities use of 16-bit SIMD instructions on the Cortex-M4. - * - * \par - * The state variables are stored in the array pState. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df1_init_q15( - arm_biquad_casd_df1_inst_q15 * S, - uint8_t numStages, - q15_t * pCoeffs, - q15_t * pState, - int8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c deleted file mode 100644 index dbbb8aa2b5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_init_q31.c +++ /dev/null @@ -1,109 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_init_q31.c -* -* Description: Q31 Biquad cascade DirectFormI(DF1) filter initialization function. -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] postShift Shift to be applied after the accumulator. Varies according to the coefficients format - * @return none - * - * Coefficient and State Ordering: - * - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
    
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}    
- * 
- * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState points to state variables array. - * Each Biquad stage has 4 state variables x[n-1], x[n-2], y[n-1], and y[n-2]. - * The state variables are arranged in the pState array as: - *
    
- *     {x[n-1], x[n-2], y[n-1], y[n-2]}    
- * 
- * The 4 state variables for stage 1 are first, then the 4 state variables for stage 2, and so on. - * The state array has a total length of 4*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df1_init_q31( - arm_biquad_casd_df1_inst_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q31_t * pState, - int8_t postShift) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign postShift to be applied to the output */ - S->postShift = postShift; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 4 * numStages */ - memset(pState, 0, (4u * (uint32_t) numStages) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c deleted file mode 100644 index 484cd85e89..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q15.c +++ /dev/null @@ -1,408 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_q15.c -* -* Description: Processing function for the -* Q15 Biquad cascade DirectFormI(DF1) filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @brief Processing function for the Q15 Biquad cascade filter. - * @param[in] *S points to an instance of the Q15 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is then shifted by postShift bits to truncate the result to 1.15 format by discarding the low 16 bits. - * Finally, the result is saturated to 1.15 format. - * - * \par - * Refer to the function arm_biquad_cascade_df1_fast_q15() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_biquad_cascade_df1_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q31_t in; /* Temporary variable to hold input value */ - q31_t out; /* Temporary variable to hold output value */ - q31_t b0; /* Temporary variable to hold bo value */ - q31_t b1, a1; /* Filter coefficients */ - q31_t state_in, state_out; /* Filter state variables */ - q31_t acc_l, acc_h; - q63_t acc; /* Accumulator */ - int32_t lShift = (15 - (int32_t) S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ - int32_t uShift = (32 - lShift); - - do - { - /* Read the b0 and 0 coefficients using SIMD */ - b0 = *__SIMD32(pCoeffs)++; - - /* Read the b1 and b2 coefficients using SIMD */ - b1 = *__SIMD32(pCoeffs)++; - - /* Read the a1 and a2 coefficients using SIMD */ - a1 = *__SIMD32(pCoeffs)++; - - /* Read the input state values from the state buffer: x[n-1], x[n-2] */ - state_in = *__SIMD32(pState)++; - - /* Read the output state values from the state buffer: y[n-1], y[n-2] */ - state_out = *__SIMD32(pState)--; - - /* Apply loop unrolling and compute 2 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - sample = blockSize >> 1u; - - /* First part of the processing with loop unrolling. Compute 2 outputs at a time. - ** a second loop below computes the remaining 1 sample. */ - while(sample > 0u) - { - - /* Read the input */ - in = *__SIMD32(pIn)++; - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUAD(b0, in); - - /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - out = (uint32_t) acc_l >> lShift | acc_h << uShift; - - out = __SSAT(out, 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, (in >> 16), 16); - state_out = __PKHBT(state_out >> 16, (out), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* out = b0 * x[n] + 0 * 0 */ - out = __SMUADX(b0, in); - /* acc += b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - out = (uint32_t) acc_l >> lShift | acc_h << uShift; - - out = __SSAT(out, 16); - - /* Store the output in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(state_out, out, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(out, state_out >> 16, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in >> 16, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - - if((blockSize & 0x1u) != 0u) - { - /* Read the input */ - in = *pIn++; - - /* out = b0 * x[n] + 0 * 0 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out = __SMUAD(b0, in); - -#else - - out = __SMUADX(b0, in); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc = b1 * x[n-1] + b2 * x[n-2] + out */ - acc = __SMLALD(b1, state_in, out); - /* acc += a1 * y[n-1] + a2 * y[n-2] */ - acc = __SMLALD(a1, state_out, acc); - - /* The result is converted from 3.29 to 1.31 if postShift = 1, and then saturation is applied */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - out = (uint32_t) acc_l >> lShift | acc_h << uShift; - - out = __SSAT(out, 16); - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) out; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - /* x[n-N], x[n-N-1] are packed together to make state_in of type q31 */ - /* y[n-N], y[n-N-1] are packed together to make state_out of type q31 */ - -#ifndef ARM_MATH_BIG_ENDIAN - - state_in = __PKHBT(in, state_in, 16); - state_out = __PKHBT(out, state_out, 16); - -#else - - state_in = __PKHBT(state_in >> 16, in, 16); - state_out = __PKHBT(state_out >> 16, out, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } - - /* The first stage goes from the input wire to the output wire. */ - /* Subsequent numStages occur in-place in the output wire */ - pIn = pDst; - - /* Reset the output pointer */ - pOut = pDst; - - /* Store the updated state variables back into the state array */ - *__SIMD32(pState)++ = state_in; - *__SIMD32(pState)++ = state_out; - - - /* Decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn = pSrc; /* Source pointer */ - q15_t *pOut = pDst; /* Destination pointer */ - q15_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q15_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q15_t Xn; /* temporary input */ - q63_t acc; /* Accumulator */ - int32_t shift = (15 - (int32_t) S->postShift); /* Post shift */ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - uint32_t sample, stage = (uint32_t) S->numStages; /* Stage loop counter */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q31_t) b0 *Xn; - - /* acc += b1 * x[n-1] */ - acc += (q31_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q31_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q31_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q31_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = __SSAT((acc >> shift), 16); - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q15_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c deleted file mode 100644 index 5626bdd1ca..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df1_q31.c +++ /dev/null @@ -1,400 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df1_q31.c -* -* Description: Processing function for the -* Q31 Biquad cascade filter -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF1 - * @{ - */ - -/** - * @brief Processing function for the Q31 Biquad cascade filter. - * @param[in] *S points to an instance of the Q31 Biquad cascade structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits and lie in the range [-0.25 +0.25). - * After all 5 multiply-accumulates are performed, the 2.62 accumulator is shifted by postShift bits and the result truncated to - * 1.31 format by discarding the low 32 bits. - * - * \par - * Refer to the function arm_biquad_cascade_df1_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_biquad_cascade_df1_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q63_t acc; /* accumulator */ - uint32_t uShift = ((uint32_t) S->postShift + 1u); - uint32_t lShift = 32u - uShift; /* Shift to be applied to the output */ - q31_t *pIn = pSrc; /* input pointer initialization */ - q31_t *pOut = pDst; /* output pointer initialization */ - q31_t *pState = S->pState; /* pState pointer initialization */ - q31_t *pCoeffs = S->pCoeffs; /* coeff pointer initialization */ - q31_t Xn1, Xn2, Yn1, Yn2; /* Filter state variables */ - q31_t b0, b1, b2, a1, a2; /* Filter coefficients */ - q31_t Xn; /* temporary input */ - uint32_t sample, stage = S->numStages; /* loop counters */ - - -#ifndef ARM_MATH_CM0 - - q31_t acc_l, acc_h; /* temporary output variables */ - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - /* The variable acc hold output values that are being computed: - * - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 , Yn2 variable is reused */ - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - Yn2 = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the second input */ - Xn2 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn2; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn1; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn2; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn1; - - - /* The result is converted to 1.31, Yn1 variable is reused */ - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - - /* Apply shift for lower part of acc and upper part of acc */ - Yn1 = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* Read the third input */ - Xn1 = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn1; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn2; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31, Yn2 variable is reused */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - - /* Apply shift for lower part of acc and upper part of acc */ - Yn2 = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn2; - - /* Read the forth input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn2; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn1; - - /* The result is converted to 1.31, Yn1 variable is reused */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - Yn1 = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - - /* Store the output in the destination buffer. */ - *pOut++ = Yn1; - - /* decrement the loop counter */ - sample--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = (blockSize & 0x3u); - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = acc >> lShift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q31_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /* Reading the state values */ - Xn1 = pState[0]; - Xn2 = pState[1]; - Yn1 = pState[2]; - Yn2 = pState[3]; - - /* The variables acc holds the output value that is computed: - * acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] - */ - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* acc = b0 * x[n] + b1 * x[n-1] + b2 * x[n-2] + a1 * y[n-1] + a2 * y[n-2] */ - /* acc = b0 * x[n] */ - acc = (q63_t) b0 *Xn; - - /* acc += b1 * x[n-1] */ - acc += (q63_t) b1 *Xn1; - /* acc += b[2] * x[n-2] */ - acc += (q63_t) b2 *Xn2; - /* acc += a1 * y[n-1] */ - acc += (q63_t) a1 *Yn1; - /* acc += a2 * y[n-2] */ - acc += (q63_t) a2 *Yn2; - - /* The result is converted to 1.31 */ - acc = acc >> lShift; - - /* Every time after the output is computed state should be updated. */ - /* The states should be updated as: */ - /* Xn2 = Xn1 */ - /* Xn1 = Xn */ - /* Yn2 = Yn1 */ - /* Yn1 = acc */ - Xn2 = Xn1; - Xn1 = Xn; - Yn2 = Yn1; - Yn1 = (q31_t) acc; - - /* Store the output in the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* decrement the loop counter */ - sample--; - } - - /* The first stage goes from the input buffer to the output buffer. */ - /* Subsequent stages occur in-place in the output buffer */ - pIn = pDst; - - /* Reset to destination pointer */ - pOut = pDst; - - /* Store the updated state variables back into the pState array */ - *pState++ = Xn1; - *pState++ = Xn2; - *pState++ = Yn1; - *pState++ = Yn2; - - } while(--stage); - -#endif /* #ifndef ARM_MATH_CM0 */ -} - -/** - * @} end of BiquadCascadeDF1 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c deleted file mode 100644 index a8cb0c98c1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_f32.c +++ /dev/null @@ -1,377 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df2T_f32.c -* -* Description: Processing function for the floating-point transposed -* direct form II Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup BiquadCascadeDF2T Biquad Cascade IIR Filters Using a Direct Form II Transposed Structure - * - * This set of functions implements arbitrary order recursive (IIR) filters using a transposed direct form II structure. - * The filters are implemented as a cascade of second order Biquad sections. - * These functions provide a slight memory savings as compared to the direct form I Biquad filter functions. - * Only floating-point data is supported. - * - * This function operate on blocks of input and output data and each call to the function - * processes blockSize samples through the filter. - * pSrc points to the array of input data and - * pDst points to the array of output data. - * Both arrays contain blockSize values. - * - * \par Algorithm - * Each Biquad stage implements a second order filter using the difference equation: - *
       
- *    y[n] = b0 * x[n] + d1       
- *    d1 = b1 * x[n] + a1 * y[n] + d2       
- *    d2 = b2 * x[n] + a2 * y[n]       
- * 
- * where d1 and d2 represent the two state values. - * - * \par - * A Biquad filter using a transposed Direct Form II structure is shown below. - * \image html BiquadDF2Transposed.gif "Single transposed Direct Form II Biquad" - * Coefficients b0, b1, and b2 multiply the input signal x[n] and are referred to as the feedforward coefficients. - * Coefficients a1 and a2 multiply the output signal y[n] and are referred to as the feedback coefficients. - * Pay careful attention to the sign of the feedback coefficients. - * Some design tools flip the sign of the feedback coefficients: - *
       
- *    y[n] = b0 * x[n] + d1;       
- *    d1 = b1 * x[n] - a1 * y[n] + d2;       
- *    d2 = b2 * x[n] - a2 * y[n];       
- * 
- * In this case the feedback coefficients a1 and a2 must be negated when used with the CMSIS DSP Library. - * - * \par - * Higher order filters are realized as a cascade of second order sections. - * numStages refers to the number of second order stages used. - * For example, an 8th order filter would be realized with numStages=4 second order stages. - * A 9th order filter would be realized with numStages=5 second order stages with the - * coefficients for one of the stages configured as a first order filter (b2=0 and a2=0). - * - * \par - * pState points to the state variable array. - * Each Biquad stage has 2 state variables d1 and d2. - * The state variables are arranged in the pState array as: - *
       
- *     {d11, d12, d21, d22, ...}       
- * 
- * where d1x refers to the state variables for the first Biquad and - * d2x refers to the state variables for the second Biquad. - * The state array has a total length of 2*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * - * \par - * The CMSIS library contains Biquad filters in both Direct Form I and transposed Direct Form II. - * The advantage of the Direct Form I structure is that it is numerically more robust for fixed-point data types. - * That is why the Direct Form I structure supports Q15 and Q31 data types. - * The transposed Direct Form II structure, on the other hand, requires a wide dynamic range for the state variables d1 and d2. - * Because of this, the CMSIS library only has a floating-point version of the Direct Form II Biquad. - * The advantage of the Direct Form II Biquad is that it requires half the number of state variables, 2 rather than 4, per Biquad stage. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * - * \par Init Functions - * There is also an associated initialization function. - * The initialization function performs following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * For example, to statically initialize the instance structure use - *
       
- *     arm_biquad_cascade_df2T_instance_f32 S1 = {numStages, pState, pCoeffs};       
- * 
- * where numStages is the number of Biquad stages in the filter; pState is the address of the state buffer. - * pCoeffs is the address of the coefficient buffer; - * - */ - -/** - * @addtogroup BiquadCascadeDF2T - * @{ - */ - -/** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] *S points to an instance of the filter data structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_biquad_cascade_df2T_f32( - const arm_biquad_cascade_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - - float32_t *pIn = pSrc; /* source pointer */ - float32_t *pOut = pDst; /* destination pointer */ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* coefficient pointer */ - float32_t acc0; /* accumulator */ - float32_t b0, b1, b2, a1, a2; /* Filter coefficients */ - float32_t Xn; /* temporary input */ - float32_t d1, d2; /* state variables */ - uint32_t sample, stage = S->numStages; /* loop counters */ - -#ifndef ARM_MATH_CM0 - - float32_t Xn1, Xn2; /* Input State variables */ - float32_t acc1; /* accumulator */ - - - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /*Reading the state values */ - d1 = pState[0]; - d2 = pState[1]; - - /* Apply loop unrolling and compute 4 output values simultaneously. */ - sample = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(sample > 0u) - { - - /* y[n] = b0 * x[n] + d1 */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - /* d2 = b2 * x[n] + a2 * y[n] */ - - /* Read the first input */ - Xn1 = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn1) + d1; - - /* d1 = b1 * x[n] + d2 */ - d1 = (b1 * Xn1) + d2; - - /* d2 = b2 * x[n] */ - d2 = (b2 * Xn1); - - /* Read the second input */ - Xn2 = *pIn++; - - /* d1 = b1 * x[n] + a1 * y[n] */ - d1 = (a1 * acc0) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - d2 = (a2 * acc0) + d2; - - /* y[n] = b0 * x[n] + d1 */ - acc1 = (b0 * Xn2) + d1; - - /* Read the third input */ - Xn1 = *pIn++; - - d1 = (b1 * Xn2) + d2; - - d2 = (b2 * Xn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc1; - - d1 = (a1 * acc1) + d1; - - d2 = (a2 * acc1) + d2; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn1) + d1; - - d1 = (b1 * Xn1) + d2; - - d2 = (b2 * Xn1); - - /* Read the fourth input */ - Xn2 = *pIn++; - - d1 = (a1 * acc0) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - d2 = (a2 * acc0) + d2; - - /* y[n] = b0 * x[n] + d1 */ - acc1 = (b0 * Xn2) + d1; - - d1 = (b1 * Xn2) + d2; - - d2 = (b2 * Xn2); - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc1; - - d1 = (a1 * acc1) + d1; - - d2 = (a2 * acc1) + d2; - - /* decrement the loop counter */ - sample--; - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - sample = blockSize & 0x3u; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the state array */ - *pState++ = d1; - *pState++ = d2; - - /* The current stage input is given as the output to the next stage */ - pIn = pDst; - - /*Reset the output working pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - do - { - /* Reading the coefficients */ - b0 = *pCoeffs++; - b1 = *pCoeffs++; - b2 = *pCoeffs++; - a1 = *pCoeffs++; - a2 = *pCoeffs++; - - /*Reading the state values */ - d1 = pState[0]; - d2 = pState[1]; - - - sample = blockSize; - - while(sample > 0u) - { - /* Read the input */ - Xn = *pIn++; - - /* y[n] = b0 * x[n] + d1 */ - acc0 = (b0 * Xn) + d1; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - - /* Every time after the output is computed state should be updated. */ - /* d1 = b1 * x[n] + a1 * y[n] + d2 */ - d1 = ((b1 * Xn) + (a1 * acc0)) + d2; - - /* d2 = b2 * x[n] + a2 * y[n] */ - d2 = (b2 * Xn) + (a2 * acc0); - - /* decrement the loop counter */ - sample--; - } - - /* Store the updated state variables back into the state array */ - *pState++ = d1; - *pState++ = d2; - - /* The current stage input is given as the output to the next stage */ - pIn = pDst; - - /*Reset the output working pointer */ - pOut = pDst; - - /* decrement the loop counter */ - stage--; - - } while(stage > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - /** - * @} end of BiquadCascadeDF2T group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c deleted file mode 100644 index e4225d008f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_biquad_cascade_df2T_init_f32.c +++ /dev/null @@ -1,97 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_biquad_cascade_df2T_init_f32.c -* -* Description: Initialization function for the floating-point transposed -* direct form II Biquad cascade filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup BiquadCascadeDF2T - * @{ - */ - -/** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] *S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @return none - * - * Coefficient and State Ordering: - * \par - * The coefficients are stored in the array pCoeffs in the following order: - *
    
- *     {b10, b11, b12, a11, a12, b20, b21, b22, a21, a22, ...}    
- * 
- * - * \par - * where b1x and a1x are the coefficients for the first stage, - * b2x and a2x are the coefficients for the second stage, - * and so on. The pCoeffs array contains a total of 5*numStages values. - * - * \par - * The pState is a pointer to state array. - * Each Biquad stage has 2 state variables d1, and d2. - * The 2 state variables for stage 1 are first, then the 2 state variables for stage 2, and so on. - * The state array has a total length of 2*numStages values. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - */ - -void arm_biquad_cascade_df2T_init_f32( - arm_biquad_cascade_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter stages */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always 2 * numStages */ - memset(pState, 0, (2u * (uint32_t) numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; -} - -/** - * @} end of BiquadCascadeDF2T group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c deleted file mode 100644 index 48dd45f2bd..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_f32.c +++ /dev/null @@ -1,646 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_f32.c -* -* Description: Convolution of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup Conv Convolution - * - * Convolution is a mathematical operation that operates on two finite length vectors to generate a finite length output vector. - * Convolution is similar to correlation and is frequently used in filtering and data analysis. - * The CMSIS DSP library contains functions for convolving Q7, Q15, Q31, and floating-point data types. - * The library also provides fast versions of the Q15 and Q31 functions on Cortex-M4 and Cortex-M3. - * - * \par Algorithm - * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. - * Then the convolution - * - *
    
- *                   c[n] = a[n] * b[n]    
- * 
- * - * \par - * is defined as - * \image html ConvolutionEquation.gif - * \par - * Note that c[n] is of length srcALen + srcBLen - 1 and is defined over the interval n=0, 1, 2, ..., srcALen + srcBLen - 2. - * pSrcA points to the first input vector of length srcALen and - * pSrcB points to the second input vector of length srcBLen. - * The output result is written to pDst and the calling function must allocate srcALen+srcBLen-1 words for the result. - * - * \par - * Conceptually, when two signals a[n] and b[n] are convolved, - * the signal b[n] slides over a[n]. - * For each offset \c n, the overlapping portions of a[n] and b[n] are multiplied and summed together. - * - * \par - * Note that convolution is a commutative operation: - * - *
    
- *                   a[n] * b[n] = b[n] * a[n].    
- * 
- * - * \par - * This means that switching the A and B arguments to the convolution functions has no effect. - * - * Fixed-Point Behavior - * - * \par - * Convolution requires summing up a large number of intermediate products. - * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. - * Refer to the function specific documentation below for further details of the particular algorithm used. - * - * - * Fast Versions - * - * \par - * Fast versions are supported for Q31 and Q15. Cycles for Fast versions are less compared to Q31 and Q15 of conv and the design requires - * the input signals should be scaled down to avoid intermediate overflows. - * - * - * Opt Versions - * - * \par - * Opt versions are supported for Q15 and Q7. Design uses internal scratch buffer for getting good optimisation. - * These versions are optimised in cycles and consumes more memory(Scratch memory) compared to Q15 and Q7 versions - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - */ - -void arm_conv_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1; /* inputA pointer */ - float32_t *pIn2; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counters */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* x[1] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* x[2] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* x[3] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += x0 * c0; - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += x1 * c0; - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += x2 * c0; - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += x3 * c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px + 1u); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += x0 * c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px + 2u); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += x1 * c0; - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px + 3u); - px += 4u; - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - *pOut++ = acc1; - *pOut++ = acc2; - *pOut++ = acc3; - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i < ((srcALen + srcBLen) - 1u); i++) - { - /* Initialize sum with zero to carry out MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[i - j]; - } - } - /* Store the output in the destination buffer */ - pDst[i] = sum; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_opt_q15.c deleted file mode 100644 index 3e85a25ba7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_opt_q15.c +++ /dev/null @@ -1,538 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_fast_opt_q15.c -* -* Description: Fast Q15 Convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return none. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results - * but provides only a single guard bit. There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_conv_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. - */ - -void arm_conv_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2) -{ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x1, x2, x3; /* Temporary variables to hold state and coefficient values */ - q31_t y1, y2; /* State variables */ - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - uint32_t tapCnt; /* loop count */ -#ifdef UNALIGNED_SUPPORT_DISABLE - - q15_t a, b; - -#endif /* #ifdef UNALIGNED_SUPPORT_DISABLE */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - - /* Copy smaller length input sequence in reverse order into second scratch buffer */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Assuming scratch1 buffer is aligned by 32-bit */ - /* Fill (srcBLen - 1u) zeros in scratch1 buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr1, srcALen); - - /* Update pointers */ - pScr1 += srcALen; - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - /* First part of the processing with loop unrolling process 4 data points at a time. - ** a second loop below process for the remaining 1 to 3 samples. */ - - /* Actual convolution process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - /* multiply and accumlate */ - acc0 = __SMLAD(x1, y1, acc0); - acc2 = __SMLAD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLADX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = _SIMD32_OFFSET(pScr1); - - /* multiply and accumlate */ - acc0 = __SMLAD(x2, y2, acc0); - acc2 = __SMLAD(x1, y2, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - acc1 = __SMLADX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr1 + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y2, acc3); - -#else - - /* Read four samples from smaller buffer */ - a = *pIn2; - b = *(pIn2 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - y1 = __PKHBT(a, b, 16); -#else - y1 = __PKHBT(b, a, 16); -#endif - - a = *(pIn2 + 2); - b = *(pIn2 + 3); -#ifndef ARM_MATH_BIG_ENDIAN - y2 = __PKHBT(a, b, 16); -#else - y2 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLAD(x1, y1, acc0); - - acc2 = __SMLAD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLADX(x3, y1, acc1); - - a = *pScr1; - b = *(pScr1 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(a, b, 16); -#else - x1 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLAD(x2, y2, acc0); - - acc2 = __SMLAD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - acc1 = __SMLADX(x3, y2, acc1); - - a = *(pScr1 + 2); - b = *(pScr1 + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - x2 = __PKHBT(a, b, 16); -#else - x2 = __PKHBT(b, a, 16); -#endif - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y2, acc3); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* update scratch pointers */ - pIn2 += 4u; - pScr1 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - - - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - acc0 += (*pScr1++ * *pIn2++); - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c deleted file mode 100644 index e21be35235..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q15.c +++ /dev/null @@ -1,1405 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_fast_q15.c -* -* Description: Fast Q15 Convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results - * but provides only a single guard bit. There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_conv_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. - */ - -void arm_conv_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ -#ifndef UNALIGNED_SUPPORT_DISABLE - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + (count - 1u); - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px+1); - px+= 2u; - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px+1); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px+2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px+3); - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - /* Read y[srcBLen - 7] */ - c0 = *(py-1); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px+2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT((acc0 >> 15), (acc1 >> 15), 16); - *__SIMD32(pOut)++ = __PKHBT((acc2 >> 15), (acc3 >> 15), 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT((acc1 >> 15), (acc0 >> 15), 16); - *__SIMD32(pOut)++ = __PKHBT((acc3 >> 15), (acc2 >> 15), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = blockSize3 >> 2u; - - while((j > 0u) && (blockSize3 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ - q15_t a, b; - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - py++; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + (count - 1u); - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - a = *px++; - b = *px++; - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *px; - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *px; - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - a = *py; - b = *(py+1); - py -= 2; - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x2 = __PKHBT(a, b, 16); - a = *(px + 2); - x3 = __PKHBT(b, a, 16); - -#else - - x2 = __PKHBT(b, a, 16); - a = *(px + 2); - x3 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - a = *py; - b = *(py+1); - py -= 2; - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5], x[6] */ - a = *(px + 2); - b = *(px + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *(px + 4); - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *(px + 4); - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - a = *px; - b = *(px+1); - px++; - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - a = *py; - b = *(py+1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - a = *py; - b = *(py+1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - /* Read y[srcBLen - 7] */ - c0 = *(py-1); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - a = *(px+2); - b = *(px+3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q15_t)(acc0 >> 15); - *pOut++ = (q15_t)(acc1 >> 15); - *pOut++ = (q15_t)(acc2 >> 15); - *pOut++ = (q15_t)(acc3 >> 15); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = blockSize3 >> 2u; - - while((j > 0u) && (blockSize3 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - py++; - - while(k > 0u) - { - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c deleted file mode 100644 index e675c11ced..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_fast_q31.c +++ /dev/null @@ -1,572 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_fast_q31.c -* -* Description: Q31 Convolution (fast version). -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are accumulated in a 32-bit register in 2.30 format. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * - * \par - * See arm_conv_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. - */ - -void arm_conv_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[1] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[2] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[3] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[srcBLen - 3] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[srcBLen - 3] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[srcBLen - 3] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q31_t) (acc0 << 1); - *pOut++ = (q31_t) (acc1 << 1); - *pOut++ = (q31_t) (acc2 << 1); - *pOut++ = (q31_t) (acc3 << 1); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q15.c deleted file mode 100644 index 70b4125d9d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q15.c +++ /dev/null @@ -1,544 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_opt_q15.c -* -* Description: Convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return none. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * - * \par - * Refer to arm_conv_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * - */ - -void arm_conv_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2) -{ - q63_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x1, x2, x3; /* Temporary variables to hold state and coefficient values */ - q31_t y1, y2; /* State variables */ - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - uint32_t tapCnt; /* loop count */ -#ifdef UNALIGNED_SUPPORT_DISABLE - - q15_t a, b; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - /* Copy smaller length input sequence in reverse order into second scratch buffer */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Assuming scratch1 buffer is aligned by 32-bit */ - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr1, srcALen); - - /* Update pointers */ - pScr1 += srcALen; - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - -#endif - - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - -#endif - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - /* First part of the processing with loop unrolling process 4 data points at a time. - ** a second loop below process for the remaining 1 to 3 samples. */ - - /* Actual convolution process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - /* multiply and accumlate */ - acc0 = __SMLALD(x1, y1, acc0); - acc2 = __SMLALD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLALDX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = _SIMD32_OFFSET(pScr1); - - /* multiply and accumlate */ - acc0 = __SMLALD(x2, y2, acc0); - acc2 = __SMLALD(x1, y2, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLALDX(x3, y1, acc3); - acc1 = __SMLALDX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr1 + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLALDX(x3, y2, acc3); - -#else - - /* Read four samples from smaller buffer */ - a = *pIn2; - b = *(pIn2 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - y1 = __PKHBT(a, b, 16); -#else - y1 = __PKHBT(b, a, 16); -#endif - - a = *(pIn2 + 2); - b = *(pIn2 + 3); -#ifndef ARM_MATH_BIG_ENDIAN - y2 = __PKHBT(a, b, 16); -#else - y2 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLALD(x1, y1, acc0); - - acc2 = __SMLALD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLALDX(x3, y1, acc1); - - a = *pScr1; - b = *(pScr1 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(a, b, 16); -#else - x1 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLALD(x2, y2, acc0); - - acc2 = __SMLALD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLALDX(x3, y1, acc3); - - acc1 = __SMLALDX(x3, y2, acc1); - - a = *(pScr1 + 2); - b = *(pScr1 + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - x2 = __PKHBT(a, b, 16); -#else - x2 = __PKHBT(b, a, 16); -#endif - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLALDX(x3, y2, acc3); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - pIn2 += 4u; - pScr1 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - acc0 += (*pScr1++ * *pIn2++); - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - -} - - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q7.c deleted file mode 100644 index 7fe9f55cf7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_opt_q7.c +++ /dev/null @@ -1,434 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_opt_q7.c -* -* Description: Convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return none. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and then saturated to 1.7 format. - * - */ - -void arm_conv_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pScr2, *pScr1; /* Intermediate pointers for scratch pointers */ - q15_t x4; /* Temporary input variable */ - q7_t *pIn1, *pIn2; /* inputA and inputB pointer */ - uint32_t j, k, blkCnt, tapCnt; /* loop counter */ - q7_t *px; /* Temporary input1 pointer */ - q15_t *py; /* Temporary input2 pointer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x1, x2, x3, y1; /* Temporary input variables */ - q7_t *pOut = pDst; /* output pointer */ - q7_t out0, out1, out2, out3; /* temporary variables */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2; - - /* points to smaller length sequence */ - px = pIn2 + srcBLen - 1; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy (srcALen) samples in scratch buffer */ - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - -#endif - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* Initialization of pIn2 pointer */ - pIn2 = (q7_t *) py; - - pScr2 = py; - - /* Actual convolution process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2); - - /* multiply and accumlate */ - acc0 = __SMLAD(x1, y1, acc0); - acc2 = __SMLAD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLADX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2 + 2u); - - acc0 = __SMLAD(x2, y1, acc0); - - acc2 = __SMLAD(x1, y1, acc2); - - acc1 = __SMLADX(x3, y1, acc1); - - x2 = *__SIMD32(pScr1)++; - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - pScr2 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2); - acc1 += (*pScr1++ * *pScr2); - acc2 += (*pScr1++ * *pScr2); - acc3 += (*pScr1++ * *pScr2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - out0 = (q7_t) (__SSAT(acc0 >> 7u, 8)); - out1 = (q7_t) (__SSAT(acc1 >> 7u, 8)); - out2 = (q7_t) (__SSAT(acc2 >> 7u, 8)); - out3 = (q7_t) (__SSAT(acc3 >> 7u, 8)); - - *__SIMD32(pOut)++ = __PACKq7(out0, out1, out2, out3); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - acc0 += (*pScr1++ * *pScr2++); - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 1u; - - } - -} - - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c deleted file mode 100644 index 58f5727353..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_f32.c +++ /dev/null @@ -1,661 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_f32.c -* -* Description: Partial convolution of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup PartialConv Partial Convolution - * - * Partial Convolution is equivalent to Convolution except that a subset of the output samples is generated. - * Each function has two additional arguments. - * firstIndex specifies the starting index of the subset of output samples. - * numPoints is the number of output samples to compute. - * The function computes the output in the range - * [firstIndex, ..., firstIndex+numPoints-1]. - * The output array pDst contains numPoints values. - * - * The allowable range of output indices is [0 srcALen+srcBLen-2]. - * If the requested subset does not fall in this range then the functions return ARM_MATH_ARGUMENT_ERROR. - * Otherwise the functions return ARM_MATH_SUCCESS. - * \note Refer arm_conv_f32() for details on fixed point behavior. - * - * - * Fast Versions - * - * \par - * Fast versions are supported for Q31 and Q15 of partial convolution. Cycles for Fast versions are less compared to Q31 and Q15 of partial conv and the design requires - * the input signals should be scaled down to avoid intermediate overflows. - * - * - * Opt Versions - * - * \par - * Opt versions are supported for Q15 and Q7. Design uses internal scratch buffer for getting good optimisation. - * These versions are optimised in cycles and consumes more memory(Scratch memory) compared to Q15 and Q7 versions of partial convolution - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - -arm_status arm_conv_partial_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1, *pSrc2; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - float32_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count = 0u, blkCnt, check; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = (int32_t) check - (int32_t) srcALen; - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = ((int32_t) srcBLen - 1) - (int32_t) firstIndex; - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = ((int32_t) check - blockSize3) - - (blockSize1 + (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + firstIndex; - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* x[1] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* x[2] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* x[3] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc1; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += x0 * c0; - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += x1 * c0; - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += x2 * c0; - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 += x3 * c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 += x0 * c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 += x1 * c0; - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = acc0; - *pOut++ = acc1; - *pOut++ = acc2; - *pOut++ = acc3; - - /* Increment the pointer pIn1 index, count by 1 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += *px++ * *py--; - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += *px++ * *py--; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB; /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations for inputs */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[i - j]; - } - } - /* Store the output in the destination buffer */ - pDst[i] = sum; - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_opt_q15.c deleted file mode 100644 index 25b3ba8c30..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_opt_q15.c +++ /dev/null @@ -1,763 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_fast_opt_q15.c -* -* Description: Fast Q15 Partial convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * See arm_conv_partial_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - -arm_status arm_conv_partial_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q31_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x1, x2, x3; /* Temporary variables to hold state and coefficient values */ - q31_t y1, y2; /* State variables */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - arm_status status; - - uint32_t tapCnt; /* loop count */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - - /* Copy smaller length input sequence in reverse order into second scratch buffer */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Assuming scratch1 buffer is aligned by 32-bit */ - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr1, srcALen); - - /* Update pointers */ - pScr1 += srcALen; - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - pScratch1 += firstIndex; - - pOut = pDst + firstIndex; - - /* First part of the processing with loop unrolling process 4 data points at a time. - ** a second loop below process for the remaining 1 to 3 samples. */ - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - /* multiply and accumlate */ - acc0 = __SMLAD(x1, y1, acc0); - acc2 = __SMLAD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLADX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = _SIMD32_OFFSET(pScr1); - - /* multiply and accumlate */ - acc0 = __SMLAD(x2, y2, acc0); - - acc2 = __SMLAD(x1, y2, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - acc1 = __SMLADX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr1 + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y2, acc3); - - /* update scratch pointers */ - pIn2 += 4u; - pScr1 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = numPoints & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read two samples from smaller buffer */ - y1 = *__SIMD32(pIn2)++; - - acc0 = __SMLAD(x1, y1, acc0); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -#else - -arm_status arm_conv_partial_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q31_t acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - arm_status status; /* Status variable */ - uint32_t tapCnt; /* loop count */ - q15_t x10, x11, x20, x21; /* Temporary variables to hold srcA buffer */ - q15_t y10, y11; /* Temporary variables to hold srcB buffer */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - pScratch1 += firstIndex; - - pOut = pDst + firstIndex; - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read next two samples from scratch1 buffer */ - x20 = *pScr1++; - x21 = *pScr1++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read two samples from smaller buffer */ - y10 = *pIn2; - y11 = *(pIn2 + 1u); - - /* multiply and accumlate */ - acc0 += (q31_t) x10 *y10; - acc0 += (q31_t) x11 *y11; - acc2 += (q31_t) x20 *y10; - acc2 += (q31_t) x21 *y11; - - /* multiply and accumlate */ - acc1 += (q31_t) x11 *y10; - acc1 += (q31_t) x20 *y11; - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1; - x11 = *(pScr1 + 1u); - - /* multiply and accumlate */ - acc3 += (q31_t) x21 *y10; - acc3 += (q31_t) x10 *y11; - - /* Read next two samples from scratch2 buffer */ - y10 = *(pIn2 + 2u); - y11 = *(pIn2 + 3u); - - /* multiply and accumlate */ - acc0 += (q31_t) x20 *y10; - acc0 += (q31_t) x21 *y11; - acc2 += (q31_t) x10 *y10; - acc2 += (q31_t) x11 *y11; - acc1 += (q31_t) x21 *y10; - acc1 += (q31_t) x10 *y11; - - /* Read next two samples from scratch1 buffer */ - x20 = *(pScr1 + 2); - x21 = *(pScr1 + 3); - - /* multiply and accumlate */ - acc3 += (q31_t) x11 *y10; - acc3 += (q31_t) x20 *y11; - - /* update scratch pointers */ - pIn2 += 4u; - pScr1 += 4u; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = __SSAT((acc0 >> 15), 16); - *pOut++ = __SSAT((acc1 >> 15), 16); - *pOut++ = __SSAT((acc2 >> 15), 16); - *pOut++ = __SSAT((acc3 >> 15), 16); - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = numPoints & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read two samples from smaller buffer */ - y10 = *pIn2++; - y11 = *pIn2++; - - /* multiply and accumlate */ - acc0 += (q31_t) x10 *y10; - acc0 += (q31_t) x11 *y11; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - /* Return to application */ - return (status); -} - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c deleted file mode 100644 index 98216bb6ab..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q15.c +++ /dev/null @@ -1,1473 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_fast_q15.c -* -* Description: Fast Q15 Partial convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * See arm_conv_partial_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - */ - - -arm_status arm_conv_partial_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ -#ifndef UNALIGNED_SUPPORT_DISABLE - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >=srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2 - 1u; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px+1); - px+= 2u; - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px+1); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px+2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px+3); - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - c0 = *(py-1); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px+2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = __PKHBT(acc0 >> 15, acc1 >> 15, 16); - *__SIMD32(pOut)++ = __PKHBT(acc2 >> 15, acc3 >> 15, 16); - -#else - - *__SIMD32(pOut)++ = __PKHBT(acc1 >> 15, acc0 >> 15, 16); - *__SIMD32(pOut)++ = __PKHBT(acc3 >> 15, acc2 >> 15, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = count >> 2u; - - while((j > 0u) && (blockSize3 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLADX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLAD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - q15_t a, b; - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >=srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - py++; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2 - 1u; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - a = *px++; - b = *px++; - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *px; - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *px; - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - a = *py; - b = *(py+1); - py -= 2; - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLADX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLADX(x1, c0, acc1); - - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x2 = __PKHBT(a, b, 16); - a = *(px + 2); - x3 = __PKHBT(b, a, 16); - -#else - - x2 = __PKHBT(b, a, 16); - a = *(px + 2); - x3 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLADX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLADX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - a = *py; - b = *(py+1); - py -= 2; - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLADX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLADX(x3, c0, acc1); - - /* Read x[4], x[5], x[6] */ - a = *(px + 2); - b = *(px + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *(px + 4); - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *(px + 4); - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLADX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLADX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - a = *px; - b = *(px+1); - px++; - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - a = *py; - b = *(py+1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - a = *py; - b = *(py+1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x0, c0, acc0); - acc1 = __SMLADX(x1, c0, acc1); - acc2 = __SMLADX(x3, c0, acc2); - acc3 = __SMLADX(x2, c0, acc3); - - /* Read y[srcBLen - 7] */ - c0 = *(py-1); -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - a = *(px+2); - b = *(px+3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16);; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q15_t)(acc0 >> 15); - *pOut++ = (q15_t)(acc1 >> 15); - *pOut++ = (q15_t)(acc2 >> 15); - *pOut++ = (q15_t)(acc3 >> 15); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = count >> 2u; - - while((j > 0u) && (blockSize3 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - py++; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - sum += ((q31_t) * px++ * *py--); - /* Decrement the loop counter */ - k--; - } - - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (sum >> 15); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c deleted file mode 100644 index 17902f593f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_fast_q31.c +++ /dev/null @@ -1,599 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_fast_q31.c -* -* Description: Fast Q31 Partial convolution. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * \par - * See arm_conv_partial_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. - */ - -arm_status arm_conv_partial_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x0, x1, x2, x3, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[1] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[2] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* x[3] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - - /* acc3 += x[3] * y[srcBLen - 1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py--); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[srcBLen - 2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[srcBLen - 4] sample */ - c0 = *(py--); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[srcBLen - 4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[srcBLen - 4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[srcBLen - 4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[srcBLen - 4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (acc0 << 1); - *pOut++ = (q31_t) (acc1 << 1); - *pOut++ = (q31_t) (acc2 << 1); - *pOut++ = (q31_t) (acc3 << 1); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py--))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = sum << 1; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q15.c deleted file mode 100644 index fe14f9fd3b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q15.c +++ /dev/null @@ -1,764 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_opt_q15.c -* -* Description: Partial convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, state buffers should be aligned by 32-bit - * - * Refer to arm_conv_partial_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * - */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - -arm_status arm_conv_partial_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q63_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x1, x2, x3; /* Temporary variables to hold state and coefficient values */ - q31_t y1, y2; /* State variables */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - arm_status status; /* Status variable */ - uint32_t tapCnt; /* loop count */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr1, srcALen); - - /* Update pointers */ - pScr1 += srcALen; - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - pScratch1 += firstIndex; - - pOut = pDst + firstIndex; - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - /* multiply and accumlate */ - acc0 = __SMLALD(x1, y1, acc0); - acc2 = __SMLALD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLALDX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = _SIMD32_OFFSET(pScr1); - - /* multiply and accumlate */ - acc0 = __SMLALD(x2, y2, acc0); - acc2 = __SMLALD(x1, y2, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLALDX(x3, y1, acc3); - acc1 = __SMLALDX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr1 + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLALDX(x3, y2, acc3); - - /* update scratch pointers */ - pIn2 += 4u; - pScr1 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = numPoints & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read two samples from smaller buffer */ - y1 = *__SIMD32(pIn2)++; - - acc0 = __SMLALD(x1, y1, acc0); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - /* Return to application */ - return (status); -} - -#else - -arm_status arm_conv_partial_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch1 */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch1 */ - q63_t acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - uint32_t j, k, blkCnt; /* loop counter */ - arm_status status; /* Status variable */ - uint32_t tapCnt; /* loop count */ - q15_t x10, x11, x20, x21; /* Temporary variables to hold srcA buffer */ - q15_t y10, y11; /* Temporary variables to hold srcB buffer */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2 + srcBLen - 1; - - /* points to smaller length sequence */ - px = pIn2; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr2-- = *px++; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy bigger length sequence(srcALen) samples in scratch1 buffer */ - - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = *pIn1++; - - /* Decrement the loop counter */ - k--; - } - - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - - /* Initialization of pIn2 pointer */ - pIn2 = py; - - pScratch1 += firstIndex; - - pOut = pDst + firstIndex; - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read next two samples from scratch1 buffer */ - x20 = *pScr1++; - x21 = *pScr1++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read two samples from smaller buffer */ - y10 = *pIn2; - y11 = *(pIn2 + 1u); - - /* multiply and accumlate */ - acc0 += (q63_t) x10 *y10; - acc0 += (q63_t) x11 *y11; - acc2 += (q63_t) x20 *y10; - acc2 += (q63_t) x21 *y11; - - /* multiply and accumlate */ - acc1 += (q63_t) x11 *y10; - acc1 += (q63_t) x20 *y11; - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1; - x11 = *(pScr1 + 1u); - - /* multiply and accumlate */ - acc3 += (q63_t) x21 *y10; - acc3 += (q63_t) x10 *y11; - - /* Read next two samples from scratch2 buffer */ - y10 = *(pIn2 + 2u); - y11 = *(pIn2 + 3u); - - /* multiply and accumlate */ - acc0 += (q63_t) x20 *y10; - acc0 += (q63_t) x21 *y11; - acc2 += (q63_t) x10 *y10; - acc2 += (q63_t) x11 *y11; - acc1 += (q63_t) x21 *y10; - acc1 += (q63_t) x10 *y11; - - /* Read next two samples from scratch1 buffer */ - x20 = *(pScr1 + 2); - x21 = *(pScr1 + 3); - - /* multiply and accumlate */ - acc3 += (q63_t) x11 *y10; - acc3 += (q63_t) x20 *y11; - - /* update scratch pointers */ - pIn2 += 4u; - pScr1 += 4u; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2); - acc1 += (*pScr1++ * *pIn2); - acc2 += (*pScr1++ * *pIn2); - acc3 += (*pScr1++ * *pIn2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = __SSAT((acc0 >> 15), 16); - *pOut++ = __SSAT((acc1 >> 15), 16); - *pOut++ = __SSAT((acc2 >> 15), 16); - *pOut++ = __SSAT((acc3 >> 15), 16); - - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = numPoints & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read two samples from smaller buffer */ - y10 = *pIn2++; - y11 = *pIn2++; - - /* multiply and accumlate */ - acc0 += (q63_t) x10 *y10; - acc0 += (q63_t) x11 *y11; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch1 += 1u; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - /* Return to application */ - return (status); -} - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q7.c deleted file mode 100644 index 513d89d877..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_opt_q7.c +++ /dev/null @@ -1,806 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_opt_q7.c -* -* Description: Partial convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - * - * - */ - - -#ifndef UNALIGNED_SUPPORT_DISABLE - -arm_status arm_conv_partial_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pScr2, *pScr1; /* Intermediate pointers for scratch pointers */ - q15_t x4; /* Temporary input variable */ - q7_t *pIn1, *pIn2; /* inputA and inputB pointer */ - uint32_t j, k, blkCnt, tapCnt; /* loop counter */ - q7_t *px; /* Temporary input1 pointer */ - q15_t *py; /* Temporary input2 pointer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t x1, x2, x3, y1; /* Temporary input variables */ - arm_status status; - q7_t *pOut = pDst; /* output pointer */ - q7_t out0, out1, out2, out3; /* temporary variables */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2; - - /* points to smaller length sequence */ - px = pIn2 + srcBLen - 1; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy (srcALen) samples in scratch buffer */ - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* Initialization of pIn2 pointer */ - pIn2 = (q7_t *) py; - - pScr2 = py; - - pOut = pDst + firstIndex; - - pScratch1 += firstIndex; - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2); - - /* multiply and accumlate */ - acc0 = __SMLAD(x1, y1, acc0); - acc2 = __SMLAD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLADX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2 + 2u); - - acc0 = __SMLAD(x2, y1, acc0); - - acc2 = __SMLAD(x1, y1, acc2); - - acc1 = __SMLADX(x3, y1, acc1); - - x2 = *__SIMD32(pScr1)++; - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - pScr2 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2); - acc1 += (*pScr1++ * *pScr2); - acc2 += (*pScr1++ * *pScr2); - acc3 += (*pScr1++ * *pScr2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - out0 = (q7_t) (__SSAT(acc0 >> 7u, 8)); - out1 = (q7_t) (__SSAT(acc1 >> 7u, 8)); - out2 = (q7_t) (__SSAT(acc2 >> 7u, 8)); - out3 = (q7_t) (__SSAT(acc3 >> 7u, 8)); - - *__SIMD32(pOut)++ = __PACKq7(out0, out1, out2, out3); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 4u; - - } - - blkCnt = (numPoints) & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read two samples from smaller buffer */ - y1 = *__SIMD32(pScr2)++; - - acc0 = __SMLAD(x1, y1, acc0); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 1u; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - - } - - return (status); - -} - -#else - -arm_status arm_conv_partial_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2) -{ - - q15_t *pScr2, *pScr1; /* Intermediate pointers for scratch pointers */ - q15_t x4; /* Temporary input variable */ - q7_t *pIn1, *pIn2; /* inputA and inputB pointer */ - uint32_t j, k, blkCnt, tapCnt; /* loop counter */ - q7_t *px; /* Temporary input1 pointer */ - q15_t *py; /* Temporary input2 pointer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulator */ - arm_status status; - q7_t *pOut = pDst; /* output pointer */ - q15_t x10, x11, x20, x21; /* Temporary input variables */ - q15_t y10, y11; /* Temporary input variables */ - q7_t out0, out1, out2, out3; /* temporary variables */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* pointer to take end of scratch2 buffer */ - pScr2 = pScratch2; - - /* points to smaller length sequence */ - px = pIn2 + srcBLen - 1; - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * px--; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Initialze temporary scratch pointer */ - pScr1 = pScratch1; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy (srcALen) samples in scratch buffer */ - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - - /* Temporary pointer for scratch2 */ - py = pScratch2; - - /* Initialization of pIn2 pointer */ - pIn2 = (q7_t *) py; - - pScr2 = py; - - pOut = pDst + firstIndex; - - pScratch1 += firstIndex; - - /* Actual convolution process starts here */ - blkCnt = (numPoints) >> 2; - - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read next two samples from scratch1 buffer */ - x20 = *pScr1++; - x21 = *pScr1++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y10 = *pScr2; - y11 = *(pScr2 + 1u); - - /* multiply and accumlate */ - acc0 += (q31_t) x10 *y10; - acc0 += (q31_t) x11 *y11; - acc2 += (q31_t) x20 *y10; - acc2 += (q31_t) x21 *y11; - - - acc1 += (q31_t) x11 *y10; - acc1 += (q31_t) x20 *y11; - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1; - x11 = *(pScr1 + 1u); - - /* multiply and accumlate */ - acc3 += (q31_t) x21 *y10; - acc3 += (q31_t) x10 *y11; - - /* Read next two samples from scratch2 buffer */ - y10 = *(pScr2 + 2u); - y11 = *(pScr2 + 3u); - - /* multiply and accumlate */ - acc0 += (q31_t) x20 *y10; - acc0 += (q31_t) x21 *y11; - acc2 += (q31_t) x10 *y10; - acc2 += (q31_t) x11 *y11; - acc1 += (q31_t) x21 *y10; - acc1 += (q31_t) x10 *y11; - - /* Read next two samples from scratch1 buffer */ - x20 = *(pScr1 + 2); - x21 = *(pScr1 + 3); - - /* multiply and accumlate */ - acc3 += (q31_t) x11 *y10; - acc3 += (q31_t) x20 *y11; - - /* update scratch pointers */ - - pScr1 += 4u; - pScr2 += 4u; - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2); - acc1 += (*pScr1++ * *pScr2); - acc2 += (*pScr1++ * *pScr2); - acc3 += (*pScr1++ * *pScr2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - out0 = (q7_t) (__SSAT(acc0 >> 7u, 8)); - out1 = (q7_t) (__SSAT(acc1 >> 7u, 8)); - out2 = (q7_t) (__SSAT(acc2 >> 7u, 8)); - out3 = (q7_t) (__SSAT(acc3 >> 7u, 8)); - - - *__SIMD32(pOut)++ = __PACKq7(out0, out1, out2, out3); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 4u; - - } - - blkCnt = (numPoints) & 0x3; - - /* Calculate convolution for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - /* Read next two samples from scratch1 buffer */ - x10 = *pScr1++; - x11 = *pScr1++; - - /* Read two samples from smaller buffer */ - y10 = *pScr2++; - y11 = *pScr2++; - - /* multiply and accumlate */ - acc0 += (q31_t) x10 *y10; - acc0 += (q31_t) x11 *y11; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 1u; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - return (status); - -} - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c deleted file mode 100644 index 8c7ed5f861..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q15.c +++ /dev/null @@ -1,778 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q15.c -* -* Description: Partial convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * Refer to arm_conv_partial_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * \par - * Refer the function arm_conv_partial_opt_q15() for a faster implementation of this function using scratch buffers. - * - */ - - -arm_status arm_conv_partial_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - -#if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE) - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary input variables */ - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2 - 1u; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px+1); - px+= 2u; - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLALDX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px+1); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLALDX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLALDX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLALDX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLALDX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px+2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px+3); - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLALDX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLALDX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - - c0 = *(py-1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px+2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = count >> 2u; - - while((j > 0u) && (blockSize3 > 0)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* inputA pointer */ - q15_t *pIn2 = pSrcB; /* inputB pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q31_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE) */ - -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c deleted file mode 100644 index 16a0606488..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q31.c +++ /dev/null @@ -1,599 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q31.c -* -* Description: Partial convolution of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * See arm_conv_partial_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -arm_status arm_conv_partial_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q63_t sum, acc0, acc1, acc2; /* Accumulator */ - q31_t x0, x1, x2, c0; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; /* status of Partial convolution */ - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* x[1] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* x[2] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* x[3] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blkCnt */ - - blkCnt = blockSize2 / 3; - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - - /* read x[0], x[1] samples */ - x0 = *(px++); - x1 = *(px++); - - /* Apply loop unrolling and compute 3 MACs simultaneously. */ - k = srcBLen / 3; - - /* First part of the processing with loop unrolling. Compute 3 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 2 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py); - - /* Read x[2] sample */ - x2 = *(px); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += (q63_t) x0 *c0; - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += (q63_t) x1 *c0; - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += (q63_t) x2 *c0; - - /* Read y[srcBLen - 2] sample */ - c0 = *(py - 1u); - - /* Read x[3] sample */ - x0 = *(px + 1u); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += (q63_t) x1 *c0; - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += (q63_t) x2 *c0; - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += (q63_t) x0 *c0; - - /* Read y[srcBLen - 3] sample */ - c0 = *(py - 2u); - - /* Read x[4] sample */ - x1 = *(px + 2u); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += (q63_t) x2 *c0; - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += (q63_t) x0 *c0; - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += (q63_t) x1 *c0; - - - px += 3u; - - py -= 3u; - - } while(--k); - - /* If the srcBLen is not a multiple of 3, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen - (3 * (srcBLen / 3)); - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += (q63_t) x0 *c0; - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += (q63_t) x1 *c0; - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += (q63_t) x2 *c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (acc0 >> 31); - *pOut++ = (q31_t) (acc1 >> 31); - *pOut++ = (q31_t) (acc2 >> 31); - - /* Increment the pointer pIn1 index, count by 3 */ - count += 3u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 3, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 - 3 * (blockSize2 / 3); - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* inputA pointer */ - q31_t *pIn2 = pSrcB; /* inputB pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q31_t) (sum >> 31u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c deleted file mode 100644 index ed205838ed..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_partial_q7.c +++ /dev/null @@ -1,733 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_partial_q7.c -* -* Description: Partial convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup PartialConv - * @{ - */ - -/** - * @brief Partial convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - * - * \par - * Refer the function arm_conv_partial_opt_q7() for a faster implementation of this function. - * - */ - -arm_status arm_conv_partial_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t input1, input2; - q15_t in1, in2; - q7_t x0, x1, x2, x3, c0, c1; - uint32_t j, k, count, check, blkCnt; - int32_t blockSize1, blockSize2, blockSize3; /* loop counter */ - arm_status status; - - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_MATH_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* Conditions to check which loopCounter holds - * the first and last indices of the output samples to be calculated. */ - check = firstIndex + numPoints; - blockSize3 = ((int32_t) check - (int32_t) srcALen); - blockSize3 = (blockSize3 > 0) ? blockSize3 : 0; - blockSize1 = (((int32_t) srcBLen - 1) - (int32_t) firstIndex); - blockSize1 = (blockSize1 > 0) ? ((check > (srcBLen - 1u)) ? blockSize1 : - (int32_t) numPoints) : 0; - blockSize2 = (int32_t) check - ((blockSize3 + blockSize1) + - (int32_t) firstIndex); - blockSize2 = (blockSize2 > 0) ? blockSize2 : 0; - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* Set the output pointer to point to the firstIndex - * of the output sample to be calculated. */ - pOut = pDst + firstIndex; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed. - Since the partial convolution starts from from firstIndex - Number of Macs to be performed is firstIndex + 1 */ - count = 1u + firstIndex; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + firstIndex; - py = pSrc2; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 1] , y[srcBLen - 2] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[0] * y[srcBLen - 1] */ - /* x[1] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 3] , y[srcBLen - 4] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[2] * y[srcBLen - 3] */ - /* x[3] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = ++pSrc2; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = ((uint32_t) blockSize2 >> 2u); - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - /* Read y[srcBLen - 2] sample */ - c1 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - /* Read y[srcBLen - 4] sample */ - c1 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *(px++); - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q31_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q31_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q31_t) x2 * c0); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += ((q31_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc1 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc2 >> 7, 8)); - *pOut++ = (q7_t) (__SSAT(acc3 >> 7, 8)); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = (uint32_t) blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum += ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* inputA pointer */ - q7_t *pIn2 = pSrcB; /* inputB pointer */ - q31_t sum; /* Accumulator */ - uint32_t i, j; /* loop counters */ - arm_status status; /* status of Partial convolution */ - - /* Check for range of output samples to be calculated */ - if((firstIndex + numPoints) > ((srcALen + (srcBLen - 1u)))) - { - /* Set status as ARM_ARGUMENT_ERROR */ - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Loop to calculate convolution for output length number of values */ - for (i = firstIndex; i <= (firstIndex + numPoints - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q15_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); - } - /* set status as ARM_SUCCESS as there are no argument errors */ - status = ARM_MATH_SUCCESS; - } - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of PartialConv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c deleted file mode 100644 index 1907719e74..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q15.c +++ /dev/null @@ -1,733 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q15.c -* -* Description: Convolution of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * \par - * Refer to arm_conv_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * \par - * Refer the function arm_conv_opt_q15() for a faster implementation of this function using scratch buffers. - * - */ - -void arm_conv_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - -#if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE) - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t blockSize1, blockSize2, blockSize3, j, k, count, blkCnt; /* loop counter */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations less than 4 */ - /* Second part of this stage computes the MAC operations greater than or equal to 4 */ - - /* The first part of the stage starts here */ - while((count < 4u) && (blockSize1 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over number of MAC operations between - * inputA samples and inputB samples */ - k = count; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* The second part of the stage starts here */ - /* The internal loop, over count, is unrolled by 4 */ - /* To, read the last two inputB samples using SIMD: - * y[srcBLen] and y[srcBLen-1] coefficients, py is decremented by 1 */ - py = py - 1; - - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0], x[1] are multiplied with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[2], x[3] are multiplied with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + (count - 1u); - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is the index by which the pointer pIn1 to be incremented */ - count = 0u; - - - /* -------------------- - * Stage2 process - * -------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - py = py - 1u; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px+1); - px+= 2u; - - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the last two inputB samples using SIMD: - * y[srcBLen - 1] and y[srcBLen - 2] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLALDX(x0, c0, acc0); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px+1); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLALDX(x2, c0, acc2); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLALDX(x3, c0, acc3); - - /* Read y[srcBLen - 3] and y[srcBLen - 4] */ - c0 = *__SIMD32(py)--; - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLALDX(x2, c0, acc0); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLALDX(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px+2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px+3); - px += 4u; - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLALDX(x0, c0, acc2); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLALDX(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[srcBLen - 5] */ - c0 = *(py+1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[srcBLen - 5], y[srcBLen - 6] */ - c0 = _SIMD32_OFFSET(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px+1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x0, c0, acc0); - acc1 = __SMLALDX(x1, c0, acc1); - acc2 = __SMLALDX(x3, c0, acc2); - acc3 = __SMLALDX(x2, c0, acc3); - - c0 = *(py-1); - -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px+2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - - /* Store the results in the accumulators in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pOut)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) ((q31_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT(sum >> 15, 16)); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - blockSize3 = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - pIn2 = pSrc2 - 1u; - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - /* For loop unrolling by 4, this stage is divided into two. */ - /* First part of this stage computes the MAC operations greater than 4 */ - /* Second part of this stage computes the MAC operations less than or equal to 4 */ - - /* The first part of the stage starts here */ - j = blockSize3 >> 2u; - - while((j > 0u) && (blockSize3 > 0u)) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1], x[srcALen - srcBLen + 2] are multiplied - * with y[srcBLen - 1], y[srcBLen - 2] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - /* x[srcALen - srcBLen + 3], x[srcALen - srcBLen + 4] are multiplied - * with y[srcBLen - 3], y[srcBLen - 4] respectively */ - sum = __SMLALDX(*__SIMD32(px)++, *__SIMD32(py)--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* For the next MAC operations, the pointer py is used without SIMD - * So, py is incremented by 1 */ - py = py + 1u; - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 5] * y[srcBLen - 5] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the loop counter */ - blockSize3--; - - j--; - } - - /* The second part of the stage starts here */ - /* SIMD is not used for the next MAC operations, - * so pointer py is updated to read only one sample at a time */ - py = py + 1u; - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen-1] * y[srcBLen-1] */ - sum = __SMLALD(*px++, *py--, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* input pointer */ - q15_t *pIn2 = pSrcB; /* coefficient pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += (q31_t) pIn1[j] * (pIn2[i - j]); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q15_t) __SSAT((sum >> 15u), 16u); - } - -#endif /* #if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE)*/ - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c deleted file mode 100644 index 769b95abb0..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q31.c +++ /dev/null @@ -1,564 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q31.c -* -* Description: Convolution of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down the inputs by log2(min(srcALen, srcBLen)) (log2 is read as log to the base 2) times to avoid overflows, - * as maximum of min(srcALen, srcBLen) number of additions are carried internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_conv_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_conv_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q63_t sum; /* Accumulator */ - q63_t acc0, acc1, acc2; /* Accumulator */ - q31_t x0, x1, x2, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (q31_t *) pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = (q31_t *) pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* x[1] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* x[2] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* x[3] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll by 3 */ - blkCnt = blockSize2 / 3; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - - /* Apply loop unrolling and compute 3 MACs simultaneously. */ - k = srcBLen / 3; - - /* First part of the processing with loop unrolling. Compute 3 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 2 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py); - - /* Read x[3] sample */ - x2 = *(px); - - /* Perform the multiply-accumulates */ - /* acc0 += x[0] * y[srcBLen - 1] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[1] * y[srcBLen - 1] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[2] * y[srcBLen - 1] */ - acc2 += ((q63_t) x2 * c0); - - /* Read y[srcBLen - 2] sample */ - c0 = *(py - 1u); - - /* Read x[4] sample */ - x0 = *(px + 1u); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[srcBLen - 2] */ - acc0 += ((q63_t) x1 * c0); - /* acc1 += x[2] * y[srcBLen - 2] */ - acc1 += ((q63_t) x2 * c0); - /* acc2 += x[3] * y[srcBLen - 2] */ - acc2 += ((q63_t) x0 * c0); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py - 2u); - - /* Read x[5] sample */ - x1 = *(px + 2u); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[srcBLen - 3] */ - acc0 += ((q63_t) x2 * c0); - /* acc1 += x[3] * y[srcBLen - 2] */ - acc1 += ((q63_t) x0 * c0); - /* acc2 += x[4] * y[srcBLen - 2] */ - acc2 += ((q63_t) x1 * c0); - - /* update scratch pointers */ - px += 3u; - py -= 3u; - - } while(--k); - - /* If the srcBLen is not a multiple of 3, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen - (3 * (srcBLen / 3)); - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q63_t) x2 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - - /* Decrement the loop counter */ - k--; - } - - /* Store the results in the accumulators in the destination buffer. */ - *pOut++ = (q31_t) (acc0 >> 31); - *pOut++ = (q31_t) (acc1 >> 31); - *pOut++ = (q31_t) (acc2 >> 31); - - /* Increment the pointer pIn1 index, count by 3 */ - count += 3u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 3, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 - 3 * (blockSize2 / 3); - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py--); - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q31_t) (sum >> 31); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* input pointer */ - q31_t *pIn2 = pSrcB; /* coefficient pointer */ - q63_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * (pIn2[i - j])); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q31_t) (sum >> 31u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c deleted file mode 100644 index eb78fd5333..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_conv_q7.c +++ /dev/null @@ -1,689 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_conv_q7.c -* -* Description: Convolution of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Conv - * @{ - */ - -/** - * @brief Convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and then saturated to 1.7 format. - * - * \par - * Refer the function arm_conv_opt_q7() for a faster implementation of this function. - * - */ - -void arm_conv_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1, *pSrc2; /* Intermediate pointers */ - q7_t x0, x1, x2, x3, c0, c1; /* Temporary variables to hold state and coefficient values */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulator */ - q31_t input1, input2; /* Temporary input variables */ - q15_t in1, in2; /* Temporary input variables */ - uint32_t j, k, count, blkCnt, blockSize1, blockSize2, blockSize3; /* loop counter */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - } - - /* conv(x,y) at n = x[n] * y[0] + x[n-1] * y[1] + x[n-2] * y[2] + ...+ x[n-N+1] * y[N -1] */ - /* The function is internally - * divided into three stages according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first stage of the - * algorithm, the multiplications increase by one for every iteration. - * In the second stage of the algorithm, srcBLen number of multiplications are done. - * In the third stage of the algorithm, the multiplications decrease by one - * for every iteration. */ - - /* The algorithm is implemented in three stages. - The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = (srcALen - srcBLen) + 1u; - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[0] - * sum = x[0] * y[1] + x[1] * y[0] - * .... - * sum = x[0] * y[srcBlen - 1] + x[1] * y[srcBlen - 2] +...+ x[srcBLen - 1] * y[0] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 1] , y[srcBLen - 2] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* x[0] * y[srcBLen - 1] */ - /* x[1] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 3] , y[srcBLen - 4] */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* x[2] * y[srcBLen - 3] */ - /* x[3] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pIn2 + count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[srcBLen-1] + x[1] * y[srcBLen-2] +...+ x[srcBLen-1] * y[0] - * sum = x[1] * y[srcBLen-1] + x[2] * y[srcBLen-2] +...+ x[srcBLen] * y[0] - * .... - * sum = x[srcALen-srcBLen-2] * y[srcBLen-1] + x[srcALen] * y[srcBLen-2] +...+ x[srcALen-1] * y[0] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[srcBLen - 1] sample */ - c0 = *(py--); - /* Read y[srcBLen - 2] sample */ - c1 = *(py--); - - /* Read x[3] sample */ - x3 = *(px++); - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 1] and y[srcBLen - 2] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc0 += x[0] * y[srcBLen - 1] + x[1] * y[srcBLen - 2] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc1 += x[1] * y[srcBLen - 1] + x[2] * y[srcBLen - 2] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc2 += x[2] * y[srcBLen - 1] + x[3] * y[srcBLen - 2] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc3 += x[3] * y[srcBLen - 1] + x[4] * y[srcBLen - 2] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[srcBLen - 3] sample */ - c0 = *(py--); - /* Read y[srcBLen - 4] sample */ - c1 = *(py--); - - /* Read x[5] sample */ - x1 = *(px++); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* y[srcBLen - 3] and y[srcBLen - 4] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc0 += x[2] * y[srcBLen - 3] + x[3] * y[srcBLen - 4] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc1 += x[3] * y[srcBLen - 3] + x[4] * y[srcBLen - 4] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc2 += x[4] * y[srcBLen - 3] + x[5] * y[srcBLen - 4] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *(px++); - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* acc3 += x[5] * y[srcBLen - 3] + x[6] * y[srcBLen - 4] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[srcBLen - 5] sample */ - c0 = *(py--); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[srcBLen - 5] */ - acc0 += ((q15_t) x0 * c0); - /* acc1 += x[5] * y[srcBLen - 5] */ - acc1 += ((q15_t) x1 * c0); - /* acc2 += x[6] * y[srcBLen - 5] */ - acc2 += ((q15_t) x2 * c0); - /* acc3 += x[7] * y[srcBLen - 5] */ - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(acc0 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc1 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc2 >> 7u, 8)); - *pOut++ = (q7_t) (__SSAT(acc3 >> 7u, 8)); - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* srcBLen number of MACS should be performed */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pSrc2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[srcBLen-1] + x[srcALen-srcBLen+2] * y[srcBLen-2] +...+ x[srcALen-1] * y[1] - * sum += x[srcALen-srcBLen+2] * y[srcBLen-1] + x[srcALen-srcBLen+3] * y[srcBLen-2] +...+ x[srcALen-1] * y[2] - * .... - * sum += x[srcALen-2] * y[srcBLen-1] + x[srcALen-1] * y[srcBLen-2] - * sum += x[srcALen-1] * y[srcBLen-1] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The blockSize3 variable holds the number of MAC operations performed */ - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - pSrc2 = pIn2 + (srcBLen - 1u); - py = pSrc2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = blockSize3 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs, x[srcALen - srcBLen + 1] and x[srcALen - srcBLen + 2] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs, y[srcBLen - 1] and y[srcBLen - 2] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* sum += x[srcALen - srcBLen + 1] * y[srcBLen - 1] */ - /* sum += x[srcALen - srcBLen + 2] * y[srcBLen - 2] */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs, x[srcALen - srcBLen + 3] and x[srcALen - srcBLen + 4] of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* Reading two inputs, y[srcBLen - 3] and y[srcBLen - 4] of SrcB buffer and packing */ - in1 = (q15_t) * py--; - in2 = (q15_t) * py--; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16u); - - /* sum += x[srcALen - srcBLen + 3] * y[srcBLen - 3] */ - /* sum += x[srcALen - srcBLen + 4] * y[srcBLen - 4] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the blockSize3 is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = blockSize3 % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py--); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut++ = (q7_t) (__SSAT(sum >> 7u, 8)); - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pSrc2; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* input pointer */ - q7_t *pIn2 = pSrcB; /* coefficient pointer */ - q31_t sum; /* Accumulator */ - uint32_t i, j; /* loop counter */ - - /* Loop to calculate output of convolution for output length number of times */ - for (i = 0; i < (srcALen + srcBLen - 1); i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0; j <= i; j++) - { - /* Check the array limitations */ - if(((i - j) < srcBLen) && (j < srcALen)) - { - /* z[i] += x[i-j] * y[j] */ - sum += (q15_t) pIn1[j] * (pIn2[i - j]); - } - } - - /* Store the output in the destination buffer */ - pDst[i] = (q7_t) __SSAT((sum >> 7u), 8u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Conv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c deleted file mode 100644 index 6a99eafc15..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_f32.c +++ /dev/null @@ -1,738 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_f32.c -* -* Description: Correlation of floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup Corr Correlation - * - * Correlation is a mathematical operation that is similar to convolution. - * As with convolution, correlation uses two signals to produce a third signal. - * The underlying algorithms in correlation and convolution are identical except that one of the inputs is flipped in convolution. - * Correlation is commonly used to measure the similarity between two signals. - * It has applications in pattern recognition, cryptanalysis, and searching. - * The CMSIS library provides correlation functions for Q7, Q15, Q31 and floating-point data types. - * Fast versions of the Q15 and Q31 functions are also provided. - * - * \par Algorithm - * Let a[n] and b[n] be sequences of length srcALen and srcBLen samples respectively. - * The convolution of the two signals is denoted by - *
    
- *                   c[n] = a[n] * b[n]    
- * 
- * In correlation, one of the signals is flipped in time - *
    
- *                   c[n] = a[n] * b[-n]    
- * 
- * - * \par - * and this is mathematically defined as - * \image html CorrelateEquation.gif - * \par - * The pSrcA points to the first input vector of length srcALen and pSrcB points to the second input vector of length srcBLen. - * The result c[n] is of length 2 * max(srcALen, srcBLen) - 1 and is defined over the interval n=0, 1, 2, ..., (2 * max(srcALen, srcBLen) - 2). - * The output result is written to pDst and the calling function must allocate 2 * max(srcALen, srcBLen) - 1 words for the result. - * - * Note - * \par - * The pDst should be initialized to all zeros before being used. - * - * Fixed-Point Behavior - * \par - * Correlation requires summing up a large number of intermediate products. - * As such, the Q7, Q15, and Q31 functions run a risk of overflow and saturation. - * Refer to the function specific documentation below for further details of the particular algorithm used. - * - * - * Fast Versions - * - * \par - * Fast versions are supported for Q31 and Q15. Cycles for Fast versions are less compared to Q31 and Q15 of correlate and the design requires - * the input signals should be scaled down to avoid intermediate overflows. - * - * - * Opt Versions - * - * \par - * Opt versions are supported for Q15 and Q7. Design uses internal scratch buffer for getting good optimisation. - * These versions are optimised in cycles and consumes more memory(Scratch memory) compared to Q15 and Q7 versions of correlate - */ - -/** - * @addtogroup Corr - * @{ - */ -/** - * @brief Correlation of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - */ - -void arm_correlate_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t *pIn1; /* inputA pointer */ - float32_t *pIn2; /* inputB pointer */ - float32_t *pOut = pDst; /* output pointer */ - float32_t *px; /* Intermediate inputA pointer */ - float32_t *py; /* Intermediate inputB pointer */ - float32_t *pSrc1; /* Intermediate pointers */ - float32_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - float32_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counters */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = pSrcA; - - /* Initialization of inputB pointer */ - pIn2 = pSrcB; - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding has to be done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - //while(j > 0u) - //{ - // /* Zero is stored in the destination buffer */ - // *pOut++ = 0.0f; - - // /* Decrement the loop counter */ - // j--; - //} - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = pSrcB; - - /* Initialization of inputB pointer */ - pIn2 = pSrcA; - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen-2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum += *px++ * *py++; - /* x[1] * y[srcBLen - 3] */ - sum += *px++ * *py++; - /* x[2] * y[srcBLen - 2] */ - sum += *px++ * *py++; - /* x[3] * y[srcBLen - 1] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - /* x[0] * y[srcBLen - 1] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py++); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 += x0 * c0; - /* acc1 += x[1] * y[0] */ - acc1 += x1 * c0; - /* acc2 += x[2] * y[0] */ - acc2 += x2 * c0; - /* acc3 += x[3] * y[0] */ - acc3 += x3 * c0; - - /* Read y[1] sample */ - c0 = *(py++); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[1] * y[1] */ - acc0 += x1 * c0; - /* acc1 += x[2] * y[1] */ - acc1 += x2 * c0; - /* acc2 += x[3] * y[1] */ - acc2 += x3 * c0; - /* acc3 += x[4] * y[1] */ - acc3 += x0 * c0; - - /* Read y[2] sample */ - c0 = *(py++); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 += x2 * c0; - /* acc1 += x[3] * y[2] */ - acc1 += x3 * c0; - /* acc2 += x[4] * y[2] */ - acc2 += x0 * c0; - /* acc3 += x[5] * y[2] */ - acc3 += x1 * c0; - - /* Read y[3] sample */ - c0 = *(py++); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[3] */ - acc0 += x3 * c0; - /* acc1 += x[4] * y[3] */ - acc1 += x0 * c0; - /* acc2 += x[5] * y[3] */ - acc2 += x1 * c0; - /* acc3 += x[6] * y[3] */ - acc3 += x2 * c0; - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += x0 * c0; - /* acc1 += x[5] * y[4] */ - acc1 += x1 * c0; - /* acc2 += x[6] * y[4] */ - acc2 += x2 * c0; - /* acc3 += x[7] * y[4] */ - acc3 += x3 * c0; - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = acc0; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = acc1; - pOut += inc; - - *pOut = acc2; - pOut += inc; - - *pOut = acc3; - pOut += inc; - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py++; - sum += *px++ * *py++; - sum += *px++ * *py++; - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0.0f; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum += *px++ * *py++; - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += *px++ * *py++; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pIn1 = pSrcA; /* inputA pointer */ - float32_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - float32_t sum; /* Accumulator */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0.0f; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += pIn1[j] * pIn2[-((int32_t) i - j)]; - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = sum; - else - *pDst++ = sum; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_opt_q15.c deleted file mode 100644 index a99225a2f5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_opt_q15.c +++ /dev/null @@ -1,507 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_fast_opt_q15.c -* -* Description: Fast Q15 Correlation. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @return none. - * - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch buffers should be aligned by 32-bit - * - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen) to avoid overflow since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_correlate_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - */ - -void arm_correlate_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch) -{ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *py; /* Intermediate inputB pointer */ - q31_t x1, x2, x3; /* temporary variables for holding input and coefficient values */ - uint32_t j, blkCnt, outBlockSize; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - uint32_t tapCnt; - q31_t y1, y2; - q15_t *pScr; /* Intermediate pointers */ - q15_t *pOut = pDst; /* output pointer */ -#ifdef UNALIGNED_SUPPORT_DISABLE - - q15_t a, b; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - pScr = pScratch; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr += (srcBLen - 1u); - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr, srcALen); - - /* Update pointers */ - pScr += srcALen; - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - j = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(j > 0u) - { - /* copy second buffer in reversal manner */ - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - - /* Decrement the loop counter */ - j--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - j = srcALen % 0x4u; - - while(j > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr++ = *pIn1++; - - /* Decrement the loop counter */ - j--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr, (srcBLen - 1u)); - - /* Update pointer */ - pScr += (srcBLen - 1u); - -#else - -/* Apply loop unrolling and do 4 Copies simultaneously. */ - j = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(j > 0u) - { - /* copy second buffer in reversal manner */ - *pScr++ = 0; - *pScr++ = 0; - *pScr++ = 0; - *pScr++ = 0; - - /* Decrement the loop counter */ - j--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - j = (srcBLen - 1u) % 0x4u; - - while(j > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr++ = 0; - - /* Decrement the loop counter */ - j--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Temporary pointer for scratch2 */ - py = pIn2; - - - /* Actual correlation process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr = pScratch; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read four samples from scratch1 buffer */ - x1 = *__SIMD32(pScr)++; - - /* Read next four samples from scratch1 buffer */ - x2 = *__SIMD32(pScr)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - acc0 = __SMLAD(x1, y1, acc0); - - acc2 = __SMLAD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLADX(x3, y1, acc1); - - x1 = _SIMD32_OFFSET(pScr); - - acc0 = __SMLAD(x2, y2, acc0); - - acc2 = __SMLAD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - acc1 = __SMLADX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y2, acc3); -#else - - /* Read four samples from smaller buffer */ - a = *pIn2; - b = *(pIn2 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - y1 = __PKHBT(a, b, 16); -#else - y1 = __PKHBT(b, a, 16); -#endif - - a = *(pIn2 + 2); - b = *(pIn2 + 3); -#ifndef ARM_MATH_BIG_ENDIAN - y2 = __PKHBT(a, b, 16); -#else - y2 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLAD(x1, y1, acc0); - - acc2 = __SMLAD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLADX(x3, y1, acc1); - - a = *pScr; - b = *(pScr + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(a, b, 16); -#else - x1 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLAD(x2, y2, acc0); - - acc2 = __SMLAD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - acc1 = __SMLADX(x3, y2, acc1); - - a = *(pScr + 2); - b = *(pScr + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - x2 = __PKHBT(a, b, 16); -#else - x2 = __PKHBT(b, a, 16); -#endif - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y2, acc3); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - pIn2 += 4u; - - pScr += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr++ * *pIn2); - acc1 += (*pScr++ * *pIn2); - acc2 += (*pScr++ * *pIn2); - acc3 += (*pScr++ * *pIn2++); - - pScr -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - *pOut = (__SSAT(acc0 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc1 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc2 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc3 >> 15u, 16)); - pOut += inc; - - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate correlation for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr = pScratch; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - acc0 += (*pScr++ * *pIn2++); - acc0 += (*pScr++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - - *pOut = (q15_t) (__SSAT((acc0 >> 15), 16)); - - pOut += inc; - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch += 1u; - - } -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c deleted file mode 100644 index 0c79bc8968..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q15.c +++ /dev/null @@ -1,1314 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_fast_q15.c -* -* Description: Fast Q15 Correlation. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen) to avoid overflow since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * The 2.30 accumulator is right shifted by 15 bits and then saturated to 1.15 format to yield the final result. - * - * \par - * See arm_correlate_q15() for a slower implementation of this function which uses a 64-bit accumulator to avoid wrap around distortion. - */ - -void arm_correlate_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ -#ifndef UNALIGNED_SUPPORT_DISABLE - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = __SMLAD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px + 1); - px += 2u; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the first two inputB samples using SIMD: - * y[0] and y[1] */ - c0 = *__SIMD32(py)++; - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLAD(x0, c0, acc0); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLAD(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px + 1); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLAD(x2, c0, acc2); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLAD(x3, c0, acc3); - - /* Read y[2] and y[3] */ - c0 = *__SIMD32(py)++; - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLAD(x2, c0, acc0); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLAD(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px + 2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px + 3); - px += 4u; - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLAD(x0, c0, acc2); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLAD(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[4] */ - c0 = *py; -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[4], y[5] */ - c0 = *__SIMD32(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px + 1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[4], y[5] */ - c0 = *__SIMD32(py)++; - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px + 1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - - c0 = (*py); - /* Read y[6] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px + 2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (acc0 >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q15_t) (acc1 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc2 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc3 >> 15); - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = __SMLAD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLAD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - q15_t a, b; - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *(px + 2); - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *(px + 2); - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 2u; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the first two inputB samples using SIMD: - * y[0] and y[1] */ - a = *py; - b = *(py + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLAD(x0, c0, acc0); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLAD(x1, c0, acc1); - - /* Read x[2], x[3], x[4] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x2 = __PKHBT(a, b, 16); - a = *(px + 2); - x3 = __PKHBT(b, a, 16); - -#else - - x2 = __PKHBT(b, a, 16); - a = *(px + 2); - x3 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLAD(x2, c0, acc2); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLAD(x3, c0, acc3); - - /* Read y[2] and y[3] */ - a = *(py + 2); - b = *(py + 3); - - py += 4u; - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLAD(x2, c0, acc0); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLAD(x3, c0, acc1); - - /* Read x[4], x[5], x[6] */ - a = *(px + 2); - b = *(px + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x0 = __PKHBT(a, b, 16); - a = *(px + 4); - x1 = __PKHBT(b, a, 16); - -#else - - x0 = __PKHBT(b, a, 16); - a = *(px + 4); - x1 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 4u; - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLAD(x0, c0, acc2); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLAD(x1, c0, acc3); - - } while(--k); - - /* For the next MAC operations, SIMD is not used - * So, the 16 bit pointer if inputB, py is updated */ - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[4] */ - c0 = *py; -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7] */ - a = *px; - b = *(px + 1); - - px++;; - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLADX(x1, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[4], y[5] */ - a = *py; - b = *(py + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[4], y[5] */ - a = *py; - b = *(py + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - c0 = __PKHBT(a, b, 16); - -#else - - c0 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - py += 2u; - - /* Read x[7], x[8], x[9] */ - a = *px; - b = *(px + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - a = *(px + 2); - x2 = __PKHBT(b, a, 16); - -#else - - x3 = __PKHBT(b, a, 16); - a = *(px + 2); - x2 = __PKHBT(a, b, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - acc2 = __SMLAD(x3, c0, acc2); - acc3 = __SMLAD(x2, c0, acc3); - - c0 = (*py); - /* Read y[6] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - - /* Read x[10] */ - b = *(px + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - - x3 = __PKHBT(a, b, 16); - -#else - - x3 = __PKHBT(b, a, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLADX(x1, c0, acc0); - acc1 = __SMLAD(x2, c0, acc1); - acc2 = __SMLADX(x2, c0, acc2); - acc3 = __SMLADX(x3, c0, acc3); - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (acc0 >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q15_t) (acc1 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc2 >> 15); - pOut += inc; - - *pOut = (q15_t) (acc3 >> 15); - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q31_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (sum >> 15); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c deleted file mode 100644 index 628fd3ea55..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_fast_q31.c +++ /dev/null @@ -1,607 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_fast_q31.c -* -* Description: Fast Q31 Correlation. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are accumulated in a 32-bit register in 2.30 format. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * - * \par - * See arm_correlate_q31() for a slower implementation of this function which uses 64-bit accumulation to provide higher precision. - */ - -void arm_correlate_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[1] * y[srcBLen - 3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[2] * y[srcBLen - 2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* x[3] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py++); - - /* Read x[3] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[1] * y[0] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[2] * y[0] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[3] * y[0] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read y[1] sample */ - c0 = *(py++); - - /* Read x[4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[1] * y[1] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc1 += x[2] * y[1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc2 += x[3] * y[1] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc3 += x[4] * y[1] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read y[2] sample */ - c0 = *(py++); - - /* Read x[5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc1 += x[3] * y[2] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc2 += x[4] * y[2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc3 += x[5] * y[2] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read y[3] sample */ - c0 = *(py++); - - /* Read x[6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[3] * y[3] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - /* acc1 += x[4] * y[3] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc2 += x[5] * y[3] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc3 += x[6] * y[3] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - /* acc1 += x[5] * y[4] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - /* acc2 += x[6] * y[4] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - /* acc3 += x[7] * y[4] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (acc0 << 1); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q31_t) (acc1 << 1); - pOut += inc; - - *pOut = (q31_t) (acc2 << 1); - pOut += inc; - - *pOut = (q31_t) (acc3 << 1); - pOut += inc; - - /* Increment the pointer pIn1 index, count by 4 */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = ((pIn1 + srcALen) - srcBLen) + 1u; - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * px++ * (*py++))) >> 32); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = sum << 1; - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q15.c deleted file mode 100644 index cc33b54f5a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q15.c +++ /dev/null @@ -1,512 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_opt_q15.c -* -* Description: Correlation of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @return none. - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch buffers should be aligned by 32-bit - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * \par - * Refer to arm_correlate_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * - */ - - -void arm_correlate_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch) -{ - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *py; /* Intermediate inputB pointer */ - q31_t x1, x2, x3; /* temporary variables for holding input1 and input2 values */ - uint32_t j, blkCnt, outBlockSize; /* loop counter */ - int32_t inc = 1; /* output pointer increment */ - uint32_t tapCnt; - q31_t y1, y2; - q15_t *pScr; /* Intermediate pointers */ - q15_t *pOut = pDst; /* output pointer */ -#ifdef UNALIGNED_SUPPORT_DISABLE - - q15_t a, b; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - pScr = pScratch; - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr += (srcBLen - 1u); - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Copy (srcALen) samples in scratch buffer */ - arm_copy_q15(pIn1, pScr, srcALen); - - /* Update pointers */ - //pIn1 += srcALen; - pScr += srcALen; - -#else - - /* Apply loop unrolling and do 4 Copies simultaneously. */ - j = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(j > 0u) - { - /* copy second buffer in reversal manner */ - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - *pScr++ = *pIn1++; - - /* Decrement the loop counter */ - j--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - j = srcALen % 0x4u; - - while(j > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr++ = *pIn1++; - - /* Decrement the loop counter */ - j--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr, (srcBLen - 1u)); - - /* Update pointer */ - pScr += (srcBLen - 1u); - -#else - -/* Apply loop unrolling and do 4 Copies simultaneously. */ - j = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(j > 0u) - { - /* copy second buffer in reversal manner */ - *pScr++ = 0; - *pScr++ = 0; - *pScr++ = 0; - *pScr++ = 0; - - /* Decrement the loop counter */ - j--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - j = (srcBLen - 1u) % 0x4u; - - while(j > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr++ = 0; - - /* Decrement the loop counter */ - j--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Temporary pointer for scratch2 */ - py = pIn2; - - - /* Actual correlation process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr = pScratch; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read four samples from scratch1 buffer */ - x1 = *__SIMD32(pScr)++; - - /* Read next four samples from scratch1 buffer */ - x2 = *__SIMD32(pScr)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pIn2); - y2 = _SIMD32_OFFSET(pIn2 + 2u); - - acc0 = __SMLALD(x1, y1, acc0); - - acc2 = __SMLALD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLALDX(x3, y1, acc1); - - x1 = _SIMD32_OFFSET(pScr); - - acc0 = __SMLALD(x2, y2, acc0); - - acc2 = __SMLALD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLALDX(x3, y1, acc3); - - acc1 = __SMLALDX(x3, y2, acc1); - - x2 = _SIMD32_OFFSET(pScr + 2u); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLALDX(x3, y2, acc3); - -#else - - /* Read four samples from smaller buffer */ - a = *pIn2; - b = *(pIn2 + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - y1 = __PKHBT(a, b, 16); -#else - y1 = __PKHBT(b, a, 16); -#endif - - a = *(pIn2 + 2); - b = *(pIn2 + 3); -#ifndef ARM_MATH_BIG_ENDIAN - y2 = __PKHBT(a, b, 16); -#else - y2 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLALD(x1, y1, acc0); - - acc2 = __SMLALD(x2, y1, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc1 = __SMLALDX(x3, y1, acc1); - - a = *pScr; - b = *(pScr + 1); - -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(a, b, 16); -#else - x1 = __PKHBT(b, a, 16); -#endif - - acc0 = __SMLALD(x2, y2, acc0); - - acc2 = __SMLALD(x1, y2, acc2); - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLALDX(x3, y1, acc3); - - acc1 = __SMLALDX(x3, y2, acc1); - - a = *(pScr + 2); - b = *(pScr + 3); - -#ifndef ARM_MATH_BIG_ENDIAN - x2 = __PKHBT(a, b, 16); -#else - x2 = __PKHBT(b, a, 16); -#endif - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLALDX(x3, y2, acc3); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - pIn2 += 4u; - - pScr += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr++ * *pIn2); - acc1 += (*pScr++ * *pIn2); - acc2 += (*pScr++ * *pIn2); - acc3 += (*pScr++ * *pIn2++); - - pScr -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - - /* Store the results in the accumulators in the destination buffer. */ - *pOut = (__SSAT(acc0 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc1 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc2 >> 15u, 16)); - pOut += inc; - *pOut = (__SSAT(acc3 >> 15u, 16)); - pOut += inc; - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate correlation for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr = pScratch; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - - acc0 += (*pScr++ * *pIn2++); - acc0 += (*pScr++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr++ * *pIn2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT((acc0 >> 15), 16)); - - pOut += inc; - - /* Initialization of inputB pointer */ - pIn2 = py; - - pScratch += 1u; - - } - - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q7.c deleted file mode 100644 index 6749b01b38..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_opt_q7.c +++ /dev/null @@ -1,463 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_opt_q7.c -* -* Description: Correlation of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return none. - * - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, scratch1 and scratch2 buffers should be aligned by 32-bit - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and saturated to 1.7 format. - * - * - */ - - - -void arm_correlate_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2) -{ - q7_t *pOut = pDst; /* output pointer */ - q15_t *pScr1 = pScratch1; /* Temporary pointer for scratch */ - q15_t *pScr2 = pScratch2; /* Temporary pointer for scratch */ - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t j, k = 0u, blkCnt; /* loop counter */ - int32_t inc = 1; /* output pointer increment */ - uint32_t outBlockSize; /* loop counter */ - q15_t x4; /* Temporary input variable */ - uint32_t tapCnt; /* loop counter */ - q31_t x1, x2, x3, y1; /* Temporary input variables */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - - /* Copy (srcBLen) samples in scratch buffer */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * pIn2++; - *pScr2++ = x4; - x4 = (q15_t) * pIn2++; - *pScr2++ = x4; - x4 = (q15_t) * pIn2++; - *pScr2++ = x4; - x4 = (q15_t) * pIn2++; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * pIn2++; - *pScr2++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* Fill (srcBLen - 1u) zeros in scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update temporary scratch pointer */ - pScr1 += (srcBLen - 1u); - - /* Copy (srcALen) samples in scratch buffer */ - k = srcALen >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = srcALen % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - x4 = (q15_t) * pIn1++; - *pScr1++ = x4; - - /* Decrement the loop counter */ - k--; - } - -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Fill (srcBLen - 1u) zeros at end of scratch buffer */ - arm_fill_q15(0, pScr1, (srcBLen - 1u)); - - /* Update pointer */ - pScr1 += (srcBLen - 1u); - -#else - -/* Apply loop unrolling and do 4 Copies simultaneously. */ - k = (srcBLen - 1u) >> 2u; - - /* First part of the processing with loop unrolling copies 4 data points at a time. - ** a second loop below copies for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* copy second buffer in reversal manner */ - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, copy remaining samples here. - ** No loop unrolling is used. */ - k = (srcBLen - 1u) % 0x4u; - - while(k > 0u) - { - /* copy second buffer in reversal manner for remaining samples */ - *pScr1++ = 0; - - /* Decrement the loop counter */ - k--; - } - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Temporary pointer for second sequence */ - py = pScratch2; - - /* Initialization of pScr2 pointer */ - pScr2 = pScratch2; - - /* Actual correlation process starts here */ - blkCnt = (srcALen + srcBLen - 1u) >> 2; - - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Read two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* Read next two samples from scratch1 buffer */ - x2 = *__SIMD32(pScr1)++; - - tapCnt = (srcBLen) >> 2u; - - while(tapCnt > 0u) - { - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2); - - /* multiply and accumlate */ - acc0 = __SMLAD(x1, y1, acc0); - acc2 = __SMLAD(x2, y1, acc2); - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - /* multiply and accumlate */ - acc1 = __SMLADX(x3, y1, acc1); - - /* Read next two samples from scratch1 buffer */ - x1 = *__SIMD32(pScr1)++; - - /* pack input data */ -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x1, x2, 0); -#else - x3 = __PKHBT(x2, x1, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - /* Read four samples from smaller buffer */ - y1 = _SIMD32_OFFSET(pScr2 + 2u); - - acc0 = __SMLAD(x2, y1, acc0); - - acc2 = __SMLAD(x1, y1, acc2); - - acc1 = __SMLADX(x3, y1, acc1); - - x2 = *__SIMD32(pScr1)++; - -#ifndef ARM_MATH_BIG_ENDIAN - x3 = __PKHBT(x2, x1, 0); -#else - x3 = __PKHBT(x1, x2, 0); -#endif - - acc3 = __SMLADX(x3, y1, acc3); - - pScr2 += 4u; - - - /* Decrement the loop counter */ - tapCnt--; - } - - - - /* Update scratch pointer for remaining samples of smaller length sequence */ - pScr1 -= 4u; - - - /* apply same above for remaining samples of smaller length sequence */ - tapCnt = (srcBLen) & 3u; - - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2); - acc1 += (*pScr1++ * *pScr2); - acc2 += (*pScr1++ * *pScr2); - acc3 += (*pScr1++ * *pScr2++); - - pScr1 -= 3u; - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(acc0 >> 7u, 8)); - pOut += inc; - *pOut = (q7_t) (__SSAT(acc1 >> 7u, 8)); - pOut += inc; - *pOut = (q7_t) (__SSAT(acc2 >> 7u, 8)); - pOut += inc; - *pOut = (q7_t) (__SSAT(acc3 >> 7u, 8)); - pOut += inc; - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 4u; - - } - - - blkCnt = (srcALen + srcBLen - 1u) & 0x3; - - /* Calculate correlation for remaining samples of Bigger length sequence */ - while(blkCnt > 0) - { - /* Initialze temporary scratch pointer as scratch1 */ - pScr1 = pScratch1; - - /* Clear Accumlators */ - acc0 = 0; - - tapCnt = (srcBLen) >> 1u; - - while(tapCnt > 0u) - { - acc0 += (*pScr1++ * *pScr2++); - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (srcBLen) & 1u; - - /* apply same above for remaining samples of smaller length sequence */ - while(tapCnt > 0u) - { - - /* accumlate the results */ - acc0 += (*pScr1++ * *pScr2++); - - /* Decrement the loop counter */ - tapCnt--; - } - - blkCnt--; - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(acc0 >> 7u, 8)); - - pOut += inc; - - /* Initialization of inputB pointer */ - pScr2 = py; - - pScratch1 += 1u; - - } - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c deleted file mode 100644 index fc4134b7b8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q15.c +++ /dev/null @@ -1,718 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q15.c -* -* Description: Correlation of Q15 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both inputs are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * This approach provides 33 guard bits and there is no risk of overflow. - * The 34.30 result is then truncated to 34.15 format by discarding the low 15 bits and then saturated to 1.15 format. - * - * \par - * Refer to arm_correlate_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - * \par - * Refer the function arm_correlate_opt_q15() for a faster implementation of this function using scratch buffers. - * - */ - -void arm_correlate_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst) -{ - -#if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE) - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pIn1; /* inputA pointer */ - q15_t *pIn2; /* inputB pointer */ - q15_t *pOut = pDst; /* output pointer */ - q63_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *px; /* Intermediate inputA pointer */ - q15_t *py; /* Intermediate inputB pointer */ - q15_t *pSrc1; /* Intermediate pointers */ - q31_t x0, x1, x2, x3, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first loop starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] , x[1] * y[srcBLen - 3] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* x[3] * y[srcBLen - 1] , x[2] * y[srcBLen - 2] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum = __SMLALD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT((sum >> 15), 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4, to loop unroll the srcBLen loop */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1] samples */ - x0 = *__SIMD32(px); - /* read x[1], x[2] samples */ - x1 = _SIMD32_OFFSET(px + 1); - px += 2u; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read the first two inputB samples using SIMD: - * y[0] and y[1] */ - c0 = *__SIMD32(py)++; - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLALD(x0, c0, acc0); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLALD(x1, c0, acc1); - - /* Read x[2], x[3] */ - x2 = *__SIMD32(px); - - /* Read x[3], x[4] */ - x3 = _SIMD32_OFFSET(px + 1); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLALD(x2, c0, acc2); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLALD(x3, c0, acc3); - - /* Read y[2] and y[3] */ - c0 = *__SIMD32(py)++; - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLALD(x2, c0, acc0); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLALD(x3, c0, acc1); - - /* Read x[4], x[5] */ - x0 = _SIMD32_OFFSET(px + 2); - - /* Read x[5], x[6] */ - x1 = _SIMD32_OFFSET(px + 3); - - px += 4u; - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLALD(x0, c0, acc2); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLALD(x1, c0, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - if(k == 1u) - { - /* Read y[4] */ - c0 = *py; -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; - -#else - - c0 = c0 & 0x0000FFFF; - -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[7] */ - x3 = *__SIMD32(px); - px++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALDX(x1, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - if(k == 2u) - { - /* Read y[4], y[5] */ - c0 = *__SIMD32(py); - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px + 1); - px += 2u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x3, c0, acc2); - acc3 = __SMLALD(x2, c0, acc3); - } - - if(k == 3u) - { - /* Read y[4], y[5] */ - c0 = *__SIMD32(py)++; - - /* Read x[7], x[8] */ - x3 = *__SIMD32(px); - - /* Read x[9] */ - x2 = _SIMD32_OFFSET(px + 1); - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x3, c0, acc2); - acc3 = __SMLALD(x2, c0, acc3); - - c0 = (*py); - - /* Read y[6] */ -#ifdef ARM_MATH_BIG_ENDIAN - - c0 = c0 << 16u; -#else - - c0 = c0 & 0x0000FFFF; -#endif /* #ifdef ARM_MATH_BIG_ENDIAN */ - /* Read x[10] */ - x3 = _SIMD32_OFFSET(px + 2); - px += 3u; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALDX(x1, c0, acc0); - acc1 = __SMLALD(x2, c0, acc1); - acc2 = __SMLALDX(x2, c0, acc2); - acc3 = __SMLALDX(x3, c0, acc3); - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(acc0 >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc1 >> 15, 16)); - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc2 >> 15, 16)); - pOut += inc; - - *pOut = (q15_t) (__SSAT(acc3 >> 15, 16)); - pOut += inc; - - /* Increment the count by 4 as 4 output values are computed */ - count += 4u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(sum >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment count by 1, as one output value is computed */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q63_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT(sum >> 15, 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = (pIn1 + srcALen) - (srcBLen - 1u); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] , sum += x[srcALen - srcBLen + 3] * y[2] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - /* sum += x[srcALen - srcBLen + 2] * y[1] , sum += x[srcALen - srcBLen + 1] * y[0] */ - sum = __SMLALD(*__SIMD32(px)++, *__SIMD32(py)++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum = __SMLALD(*px++, *py++, sum); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q15_t) (__SSAT((sum >> 15), 16)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA; /* inputA pointer */ - q15_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q63_t sum; /* Accumulators */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q31_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q15_t) __SSAT((sum >> 15u), 16u); - else - *pDst++ = (q15_t) __SSAT((sum >> 15u), 16u); - } - -#endif /*#if (defined(ARM_MATH_CM4) || defined(ARM_MATH_CM3)) && !defined(UNALIGNED_SUPPORT_DISABLE) */ - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c deleted file mode 100644 index c81f8600dc..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q31.c +++ /dev/null @@ -1,664 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q31.c -* -* Description: Correlation of Q31 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q31 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * There is no saturation on intermediate additions. - * Thus, if the accumulator overflows it wraps around and distorts the result. - * The input signals should be scaled down to avoid intermediate overflows. - * Scale down one of the inputs by 1/min(srcALen, srcBLen)to avoid overflows since a - * maximum of min(srcALen, srcBLen) number of additions is carried internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_correlate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_correlate_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t *pIn1; /* inputA pointer */ - q31_t *pIn2; /* inputB pointer */ - q31_t *pOut = pDst; /* output pointer */ - q31_t *px; /* Intermediate inputA pointer */ - q31_t *py; /* Intermediate inputB pointer */ - q31_t *pSrc1; /* Intermediate pointers */ - q63_t sum, acc0, acc1, acc2; /* Accumulators */ - q31_t x0, x1, x2, c0; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; /* Destination address modifier */ - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] * y[srcBLen - 4] */ - sum += (q63_t) * px++ * (*py++); - /* x[1] * y[srcBLen - 3] */ - sum += (q63_t) * px++ * (*py++); - /* x[2] * y[srcBLen - 2] */ - sum += (q63_t) * px++ * (*py++); - /* x[3] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll by 3 */ - blkCnt = blockSize2 / 3; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - - /* read x[0], x[1] samples */ - x0 = *(px++); - x1 = *(px++); - - /* Apply loop unrolling and compute 3 MACs simultaneously. */ - k = srcBLen / 3; - - /* First part of the processing with loop unrolling. Compute 3 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 2 samples. */ - do - { - /* Read y[0] sample */ - c0 = *(py); - - /* Read x[2] sample */ - x2 = *(px); - - /* Perform the multiply-accumulate */ - /* acc0 += x[0] * y[0] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[1] * y[0] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[2] * y[0] */ - acc2 += ((q63_t) x2 * c0); - - /* Read y[1] sample */ - c0 = *(py + 1u); - - /* Read x[3] sample */ - x0 = *(px + 1u); - - /* Perform the multiply-accumulates */ - /* acc0 += x[1] * y[1] */ - acc0 += ((q63_t) x1 * c0); - /* acc1 += x[2] * y[1] */ - acc1 += ((q63_t) x2 * c0); - /* acc2 += x[3] * y[1] */ - acc2 += ((q63_t) x0 * c0); - - /* Read y[2] sample */ - c0 = *(py + 2u); - - /* Read x[4] sample */ - x1 = *(px + 2u); - - /* Perform the multiply-accumulates */ - /* acc0 += x[2] * y[2] */ - acc0 += ((q63_t) x2 * c0); - /* acc1 += x[3] * y[2] */ - acc1 += ((q63_t) x0 * c0); - /* acc2 += x[4] * y[2] */ - acc2 += ((q63_t) x1 * c0); - - /* update scratch pointers */ - px += 3u; - py += 3u; - - } while(--k); - - /* If the srcBLen is not a multiple of 3, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen - (3 * (srcBLen / 3)); - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *(py++); - - /* Read x[7] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += ((q63_t) x0 * c0); - /* acc1 += x[5] * y[4] */ - acc1 += ((q63_t) x1 * c0); - /* acc2 += x[6] * y[4] */ - acc2 += ((q63_t) x2 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (acc0 >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q31_t) (acc1 >> 31); - pOut += inc; - - *pOut = (q31_t) (acc2 >> 31); - pOut += inc; - - /* Increment the pointer pIn1 index, count by 3 */ - count += 3u; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 3, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 - 3 * (blockSize2 / 3); - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum += (q63_t) * px++ * (*py++); - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += (q63_t) * px++ * (*py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q31_t) (sum >> 31); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pIn1 = pSrcA; /* inputA pointer */ - q31_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q63_t sum; /* Accumulators */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using correlation but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate correlation for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to correlation equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q63_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q31_t) (sum >> 31u); - else - *pDst++ = (q31_t) (sum >> 31u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c deleted file mode 100644 index e03e4997b6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_correlate_q7.c +++ /dev/null @@ -1,789 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_correlate_q7.c -* -* Description: Correlation of Q7 sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.11 2011/10/18 -* Bug Fix in conv, correlation, partial convolution. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup Corr - * @{ - */ - -/** - * @brief Correlation of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length 2 * max(srcALen, srcBLen) - 1. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both the inputs are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * This approach provides 17 guard bits and there is no risk of overflow as long as max(srcALen, srcBLen)<131072. - * The 18.14 result is then truncated to 18.7 format by discarding the low 7 bits and saturated to 1.7 format. - * - * \par - * Refer the function arm_correlate_opt_q7() for a faster implementation of this function. - * - */ - -void arm_correlate_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pIn1; /* inputA pointer */ - q7_t *pIn2; /* inputB pointer */ - q7_t *pOut = pDst; /* output pointer */ - q7_t *px; /* Intermediate inputA pointer */ - q7_t *py; /* Intermediate inputB pointer */ - q7_t *pSrc1; /* Intermediate pointers */ - q31_t sum, acc0, acc1, acc2, acc3; /* Accumulators */ - q31_t input1, input2; /* temporary variables */ - q15_t in1, in2; /* temporary variables */ - q7_t x0, x1, x2, x3, c0, c1; /* temporary variables for holding input and coefficient values */ - uint32_t j, k = 0u, count, blkCnt, outBlockSize, blockSize1, blockSize2, blockSize3; /* loop counter */ - int32_t inc = 1; - - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and the destination pointer modifier, inc is set to -1 */ - /* If srcALen > srcBLen, zero pad has to be done to srcB to make the two inputs of same length */ - /* But to improve the performance, - * we include zeroes in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, - * (srcALen - srcBLen) zeroes has to included in the starting of the output buffer */ - /* If srcALen < srcBLen, - * (srcALen - srcBLen) zeroes has to included in the ending of the output buffer */ - if(srcALen >= srcBLen) - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcA); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcB); - - /* Number of output samples is calculated */ - outBlockSize = (2u * srcALen) - 1u; - - /* When srcALen > srcBLen, zero padding is done to srcB - * to make their lengths equal. - * Instead, (outBlockSize - (srcALen + srcBLen - 1)) - * number of output samples are made zero */ - j = outBlockSize - (srcALen + (srcBLen - 1u)); - - /* Updating the pointer position to non zero value */ - pOut += j; - - } - else - { - /* Initialization of inputA pointer */ - pIn1 = (pSrcB); - - /* Initialization of inputB pointer */ - pIn2 = (pSrcA); - - /* srcBLen is always considered as shorter or equal to srcALen */ - j = srcBLen; - srcBLen = srcALen; - srcALen = j; - - /* CORR(x, y) = Reverse order(CORR(y, x)) */ - /* Hence set the destination pointer to point to the last output sample */ - pOut = pDst + ((srcALen + srcBLen) - 2u); - - /* Destination address modifier is set to -1 */ - inc = -1; - - } - - /* The function is internally - * divided into three parts according to the number of multiplications that has to be - * taken place between inputA samples and inputB samples. In the first part of the - * algorithm, the multiplications increase by one for every iteration. - * In the second part of the algorithm, srcBLen number of multiplications are done. - * In the third part of the algorithm, the multiplications decrease by one - * for every iteration.*/ - /* The algorithm is implemented in three stages. - * The loop counters of each stage is initiated here. */ - blockSize1 = srcBLen - 1u; - blockSize2 = srcALen - (srcBLen - 1u); - blockSize3 = blockSize1; - - /* -------------------------- - * Initializations of stage1 - * -------------------------*/ - - /* sum = x[0] * y[srcBlen - 1] - * sum = x[0] * y[srcBlen - 2] + x[1] * y[srcBlen - 1] - * .... - * sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen - 1] * y[srcBLen - 1] - */ - - /* In this stage the MAC operations are increased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = 1u; - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - pSrc1 = pIn2 + (srcBLen - 1u); - py = pSrc1; - - /* ------------------------ - * Stage1 process - * ----------------------*/ - - /* The first stage starts here */ - while(blockSize1 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[0] , x[1] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 4] , y[srcBLen - 3] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[0] * y[srcBLen - 4] */ - /* x[1] * y[srcBLen - 3] */ - sum = __SMLAD(input1, input2, sum); - - /* x[2] , x[3] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[srcBLen - 2] , y[srcBLen - 1] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* x[2] * y[srcBLen - 2] */ - /* x[3] * y[srcBLen - 1] */ - sum = __SMLAD(input1, input2, sum); - - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - /* x[0] * y[srcBLen - 1] */ - sum += (q31_t) ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - py = pSrc1 - count; - px = pIn1; - - /* Increment the MAC count */ - count++; - - /* Decrement the loop counter */ - blockSize1--; - } - - /* -------------------------- - * Initializations of stage2 - * ------------------------*/ - - /* sum = x[0] * y[0] + x[1] * y[1] +...+ x[srcBLen-1] * y[srcBLen-1] - * sum = x[1] * y[0] + x[2] * y[1] +...+ x[srcBLen] * y[srcBLen-1] - * .... - * sum = x[srcALen-srcBLen-2] * y[0] + x[srcALen-srcBLen-1] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - */ - - /* Working pointer of inputA */ - px = pIn1; - - /* Working pointer of inputB */ - py = pIn2; - - /* count is index by which the pointer pIn1 to be incremented */ - count = 0u; - - /* ------------------- - * Stage2 process - * ------------------*/ - - /* Stage2 depends on srcBLen as in this stage srcBLen number of MACS are performed. - * So, to loop unroll over blockSize2, - * srcBLen should be greater than or equal to 4 */ - if(srcBLen >= 4u) - { - /* Loop unroll over blockSize2, by 4 */ - blkCnt = blockSize2 >> 2u; - - while(blkCnt > 0u) - { - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* read x[0], x[1], x[2] samples */ - x0 = *px++; - x1 = *px++; - x2 = *px++; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - do - { - /* Read y[0] sample */ - c0 = *py++; - /* Read y[1] sample */ - c1 = *py++; - - /* Read x[3] sample */ - x3 = *px++; - - /* x[0] and x[1] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[0] and y[1] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[0] * y[0] + x[1] * y[1] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[1] and x[2] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[1] * y[0] + x[2] * y[1] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[2] * y[0] + x[3] * y[1] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[4] sample */ - x0 = *(px++); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[3] * y[0] + x[4] * y[1] */ - acc3 = __SMLAD(input1, input2, acc3); - - /* Read y[2] sample */ - c0 = *py++; - /* Read y[3] sample */ - c1 = *py++; - - /* Read x[5] sample */ - x1 = *px++; - - /* x[2] and x[3] are packed */ - in1 = (q15_t) x2; - in2 = (q15_t) x3; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[2] and y[3] are packed */ - in1 = (q15_t) c0; - in2 = (q15_t) c1; - - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc0 += x[2] * y[2] + x[3] * y[3] */ - acc0 = __SMLAD(input1, input2, acc0); - - /* x[3] and x[4] are packed */ - in1 = (q15_t) x3; - in2 = (q15_t) x0; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc1 += x[3] * y[2] + x[4] * y[3] */ - acc1 = __SMLAD(input1, input2, acc1); - - /* x[4] and x[5] are packed */ - in1 = (q15_t) x0; - in2 = (q15_t) x1; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc2 += x[4] * y[2] + x[5] * y[3] */ - acc2 = __SMLAD(input1, input2, acc2); - - /* Read x[6] sample */ - x2 = *px++; - - /* x[5] and x[6] are packed */ - in1 = (q15_t) x1; - in2 = (q15_t) x2; - - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* acc3 += x[5] * y[2] + x[6] * y[3] */ - acc3 = __SMLAD(input1, input2, acc3); - - } while(--k); - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Read y[4] sample */ - c0 = *py++; - - /* Read x[7] sample */ - x3 = *px++; - - /* Perform the multiply-accumulates */ - /* acc0 += x[4] * y[4] */ - acc0 += ((q15_t) x0 * c0); - /* acc1 += x[5] * y[4] */ - acc1 += ((q15_t) x1 * c0); - /* acc2 += x[6] * y[4] */ - acc2 += ((q15_t) x2 * c0); - /* acc3 += x[7] * y[4] */ - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present samples for the next MAC */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(acc0 >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc1 >> 7, 8)); - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc2 >> 7, 8)); - pOut += inc; - - *pOut = (q7_t) (__SSAT(acc3 >> 7, 8)); - pOut += inc; - - count += 4u; - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize2 is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize2 % 0x4u; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = srcBLen >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Reading two inputs of SrcA buffer and packing */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Reading two inputs of SrcB buffer and packing */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* Perform the multiply-accumulates */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the srcBLen is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = srcBLen % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the pointer pIn1 index, count by 1 */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - /* Decrement the loop counter */ - blkCnt--; - } - } - else - { - /* If the srcBLen is not a multiple of 4, - * the blockSize2 loop cannot be unrolled by 4 */ - blkCnt = blockSize2; - - while(blkCnt > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Loop over srcBLen */ - k = srcBLen; - - while(k > 0u) - { - /* Perform the multiply-accumulate */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Increment the MAC count */ - count++; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = pIn1 + count; - py = pIn2; - - - /* Decrement the loop counter */ - blkCnt--; - } - } - - /* -------------------------- - * Initializations of stage3 - * -------------------------*/ - - /* sum += x[srcALen-srcBLen+1] * y[0] + x[srcALen-srcBLen+2] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * sum += x[srcALen-srcBLen+2] * y[0] + x[srcALen-srcBLen+3] * y[1] +...+ x[srcALen-1] * y[srcBLen-1] - * .... - * sum += x[srcALen-2] * y[0] + x[srcALen-1] * y[1] - * sum += x[srcALen-1] * y[0] - */ - - /* In this stage the MAC operations are decreased by 1 for every iteration. - The count variable holds the number of MAC operations performed */ - count = srcBLen - 1u; - - /* Working pointer of inputA */ - pSrc1 = pIn1 + (srcALen - (srcBLen - 1u)); - px = pSrc1; - - /* Working pointer of inputB */ - py = pIn2; - - /* ------------------- - * Stage3 process - * ------------------*/ - - while(blockSize3 > 0u) - { - /* Accumulator is made zero for every iteration */ - sum = 0; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - k = count >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 MACs at a time. - ** a second loop below computes MACs for the remaining 1 to 3 samples. */ - while(k > 0u) - { - /* x[srcALen - srcBLen + 1] , x[srcALen - srcBLen + 2] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[0] , y[1] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 1] * y[0] */ - /* sum += x[srcALen - srcBLen + 2] * y[1] */ - sum = __SMLAD(input1, input2, sum); - - /* x[srcALen - srcBLen + 3] , x[srcALen - srcBLen + 4] */ - in1 = (q15_t) * px++; - in2 = (q15_t) * px++; - input1 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* y[2] , y[3] */ - in1 = (q15_t) * py++; - in2 = (q15_t) * py++; - input2 = ((q31_t) in1 & 0x0000FFFF) | ((q31_t) in2 << 16); - - /* sum += x[srcALen - srcBLen + 3] * y[2] */ - /* sum += x[srcALen - srcBLen + 4] * y[3] */ - sum = __SMLAD(input1, input2, sum); - - /* Decrement the loop counter */ - k--; - } - - /* If the count is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - k = count % 0x4u; - - while(k > 0u) - { - /* Perform the multiply-accumulates */ - sum += ((q15_t) * px++ * *py++); - - /* Decrement the loop counter */ - k--; - } - - /* Store the result in the accumulator in the destination buffer. */ - *pOut = (q7_t) (__SSAT(sum >> 7, 8)); - /* Destination pointer is updated according to the address modifier, inc */ - pOut += inc; - - /* Update the inputA and inputB pointers for next MAC calculation */ - px = ++pSrc1; - py = pIn2; - - /* Decrement the MAC count */ - count--; - - /* Decrement the loop counter */ - blockSize3--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q7_t *pIn1 = pSrcA; /* inputA pointer */ - q7_t *pIn2 = pSrcB + (srcBLen - 1u); /* inputB pointer */ - q31_t sum; /* Accumulator */ - uint32_t i = 0u, j; /* loop counters */ - uint32_t inv = 0u; /* Reverse order flag */ - uint32_t tot = 0u; /* Length */ - - /* The algorithm implementation is based on the lengths of the inputs. */ - /* srcB is always made to slide across srcA. */ - /* So srcBLen is always considered as shorter or equal to srcALen */ - /* But CORR(x, y) is reverse of CORR(y, x) */ - /* So, when srcBLen > srcALen, output pointer is made to point to the end of the output buffer */ - /* and a varaible, inv is set to 1 */ - /* If lengths are not equal then zero pad has to be done to make the two - * inputs of same length. But to improve the performance, we include zeroes - * in the output instead of zero padding either of the the inputs*/ - /* If srcALen > srcBLen, (srcALen - srcBLen) zeroes has to included in the - * starting of the output buffer */ - /* If srcALen < srcBLen, (srcALen - srcBLen) zeroes has to included in the - * ending of the output buffer */ - /* Once the zero padding is done the remaining of the output is calcualted - * using convolution but with the shorter signal time shifted. */ - - /* Calculate the length of the remaining sequence */ - tot = ((srcALen + srcBLen) - 2u); - - if(srcALen > srcBLen) - { - /* Calculating the number of zeros to be padded to the output */ - j = srcALen - srcBLen; - - /* Initialise the pointer after zero padding */ - pDst += j; - } - - else if(srcALen < srcBLen) - { - /* Initialization to inputB pointer */ - pIn1 = pSrcB; - - /* Initialization to the end of inputA pointer */ - pIn2 = pSrcA + (srcALen - 1u); - - /* Initialisation of the pointer after zero padding */ - pDst = pDst + tot; - - /* Swapping the lengths */ - j = srcALen; - srcALen = srcBLen; - srcBLen = j; - - /* Setting the reverse flag */ - inv = 1; - - } - - /* Loop to calculate convolution for output length number of times */ - for (i = 0u; i <= tot; i++) - { - /* Initialize sum with zero to carry on MAC operations */ - sum = 0; - - /* Loop to perform MAC operations according to convolution equation */ - for (j = 0u; j <= i; j++) - { - /* Check the array limitations */ - if((((i - j) < srcBLen) && (j < srcALen))) - { - /* z[i] += x[i-j] * y[j] */ - sum += ((q15_t) pIn1[j] * pIn2[-((int32_t) i - j)]); - } - } - /* Store the output in the destination buffer */ - if(inv == 1) - *pDst-- = (q7_t) __SSAT((sum >> 7u), 8u); - else - *pDst++ = (q7_t) __SSAT((sum >> 7u), 8u); - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of Corr group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c deleted file mode 100644 index 1546f407dd..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_f32.c +++ /dev/null @@ -1,518 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_f32.c -* -* Description: FIR decimation for floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_decimate Finite Impulse Response (FIR) Decimator - * - * These functions combine an FIR filter together with a decimator. - * They are used in multirate systems for reducing the sample rate of a signal without introducing aliasing distortion. - * Conceptually, the functions are equivalent to the block diagram below: - * \image html FIRDecimator.gif "Components included in the FIR Decimator functions" - * When decimating by a factor of M, the signal should be prefiltered by a lowpass filter with a normalized - * cutoff frequency of 1/M in order to prevent aliasing distortion. - * The user of the function is responsible for providing the filter coefficients. - * - * The FIR decimator functions provided in the CMSIS DSP Library combine the FIR filter and the decimator in an efficient manner. - * Instead of calculating all of the FIR filter outputs and discarding M-1 out of every M, only the - * samples output by the decimator are computed. - * The functions operate on blocks of input and output data. - * pSrc points to an array of blockSize input values and - * pDst points to an array of blockSize/M output values. - * In order to have an integer number of output samples blockSize - * must always be a multiple of the decimation factor M. - * - * The library provides separate functions for Q15, Q31 and floating-point data types. - * - * \par Algorithm: - * The FIR portion of the algorithm uses the standard form filter: - *
    
- *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]    
- * 
- * where, b[n] are the filter coefficients. - * \par - * The pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
    
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}    
- * 
- * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - Checks to make sure that the size of the input is a multiple of the decimation factor. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * The code below statically initializes each of the 3 different data type filter instance structures - *
    
- *arm_fir_decimate_instance_f32 S = {M, numTaps, pCoeffs, pState};    
- *arm_fir_decimate_instance_q31 S = {M, numTaps, pCoeffs, pState};    
- *arm_fir_decimate_instance_q15 S = {M, numTaps, pCoeffs, pState};    
- * 
- * where M is the decimation factor; numTaps is the number of filter coefficients in the filter; - * pCoeffs is the address of the coefficient buffer; - * pState is the address of the state buffer. - * Be sure to set the values in the state buffer to zeros when doing static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR decimate filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - - /** - * @brief Processing function for the floating-point FIR decimator. - * @param[in] *S points to an instance of the floating-point FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ - -void arm_fir_decimate_f32( - const arm_fir_decimate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t sum0; /* Accumulator */ - float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - -#ifndef ARM_MATH_CM0 - - uint32_t blkCntN4; - float32_t *px0, *px1, *px2, *px3; - float32_t acc0, acc1, acc2, acc3; - float32_t x1, x2, x3; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize / 4; - blkCntN4 = outBlockSize - (4 * blkCnt); - - while(blkCnt > 0u) - { - /* Copy 4 * decimation factor number of new input samples into the state buffer */ - i = 4 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* Initialize state pointer for all the samples */ - px0 = pState; - px1 = pState + S->M; - px2 = pState + 2 * S->M; - px3 = pState + 3 * S->M; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample for acc0 */ - x0 = *(px0++); - /* Read x[n-numTaps-1] sample for acc1 */ - x1 = *(px1++); - /* Read x[n-numTaps-1] sample for acc2 */ - x2 = *(px2++); - /* Read x[n-numTaps-1] sample for acc3 */ - x3 = *(px3++); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample for acc0, acc1, acc2, acc3 */ - x0 = *(px0++); - x1 = *(px1++); - x2 = *(px2++); - x3 = *(px3++); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample acc0, acc1, acc2, acc3 */ - x0 = *(px0++); - x1 = *(px1++); - x2 = *(px2++); - x3 = *(px3++); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample acc0, acc1, acc2, acc3 */ - x0 = *(px0++); - x1 = *(px1++); - x2 = *(px2++); - x3 = *(px3++); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch state variables for acc0, acc1, acc2, acc3 */ - x0 = *(px0++); - x1 = *(px1++); - x2 = *(px2++); - x3 = *(px3++); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + 4 * S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = acc0; - *pDst++ = acc1; - *pDst++ = acc2; - *pDst++ = acc3; - - /* Decrement the loop counter */ - blkCnt--; - } - - while(blkCntN4 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Decrement the loop counter */ - blkCntN4--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - i = (numTaps - 1u); - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c deleted file mode 100644 index 96f50e6f2b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q15.c +++ /dev/null @@ -1,590 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_fast_q15.c -* -* Description: Fast Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, state buffers should be aligned by 32-bit - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (log2 is read as log to the base 2). - * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. - * - * \par - * Refer to the function arm_fir_decimate_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. - * Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_decimate_init_q15() to initialize the filter structure. - */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - -void arm_fir_decimate_fast_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q31_t x0, x1, c0, c1; /* Temporary variables to hold state and coefficient values */ - q31_t sum0; /* Accumulators */ - q31_t acc0, acc1; - q15_t *px0, *px1; - uint32_t blkCntN3; - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize / 2; - blkCntN3 = outBlockSize - (2 * blkCnt); - - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = 2 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - px0 = pState; - - px1 = pState + S->M; - - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px0)++; - - x1 = *__SIMD32(px1)++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLAD(x0, c0, acc0); - - acc1 = __SMLAD(x1, c0, acc1); - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px0)++; - - x1 = *__SIMD32(px1)++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLAD(x0, c0, acc0); - - acc1 = __SMLAD(x1, c0, acc1); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px0++; - - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLAD(x0, c0, acc0); - acc1 = __SMLAD(x1, c0, acc1); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M * 2; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - *pDst++ = (q15_t) (__SSAT((acc1 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - - - while(blkCntN3 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px)++; - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c1 = *__SIMD32(pb)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c0, sum0); - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c1, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLAD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCntN3--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -#else - - -void arm_fir_decimate_fast_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q15_t x0, x1, c0; /* Temporary variables to hold state and coefficient values */ - q31_t sum0; /* Accumulators */ - q31_t acc0, acc1; - q15_t *px0, *px1; - uint32_t blkCntN3; - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize / 2; - blkCntN3 = outBlockSize - (2 * blkCnt); - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = 2 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - px0 = pState; - - px1 = pState + S->M; - - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-1] for sample 0 and for sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-2] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-3] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-3] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-4] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M * 2; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - *pDst++ = (q15_t) (__SSAT((acc1 >> 15), 16)); - - - /* Decrement the loop counter */ - blkCnt--; - } - - while(blkCntN3 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-1] and sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-2] and sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-3] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-3] sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-4] sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCntN3--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c deleted file mode 100644 index a43fd0b4c9..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_fast_q31.c +++ /dev/null @@ -1,343 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_fast_q31.c -* -* Description: Fast Q31 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). - * - * \par - * Refer to the function arm_fir_decimate_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. - * Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_decimate_init_q31() to initialize the filter structure. - */ - -void arm_fir_decimate_fast_q31( - arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q31_t *px; /* Temporary pointers for state buffer */ - q31_t *pb; /* Temporary pointers for coefficient buffer */ - q31_t sum0; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - uint32_t blkCntN2; - q31_t x1; - q31_t acc0, acc1; - q31_t *px0, *px1; - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - - blkCnt = outBlockSize / 2; - blkCntN2 = outBlockSize - (2 * blkCnt); - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = 2 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - px0 = pState; - px1 = pState + S->M; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb); - - /* Read x[n-numTaps-1] for sample 0 sample 1 */ - x0 = *(px0); - x1 = *(px1); - - /* Perform the multiply-accumulate */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb + 1u); - - /* Read x[n-numTaps-2] for sample 0 sample 1 */ - x0 = *(px0 + 1u); - x1 = *(px1 + 1u); - - /* Perform the multiply-accumulate */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb + 2u); - - /* Read x[n-numTaps-3] for sample 0 sample 1 */ - x0 = *(px0 + 2u); - x1 = *(px1 + 2u); - pb += 4u; - - /* Perform the multiply-accumulate */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb - 1u); - - /* Read x[n-numTaps-4] for sample 0 sample 1 */ - x0 = *(px0 + 3u); - x1 = *(px1 + 3u); - - - /* Perform the multiply-accumulate */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* update state pointers */ - px0 += 4u; - px1 += 4u; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px0++); - x1 = *(px1++); - - /* Perform the multiply-accumulate */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M * 2; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (acc0 << 1); - *pDst++ = (q31_t) (acc1 << 1); - - /* Decrement the loop counter */ - blkCnt--; - } - - while(blkCntN2 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) sum0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) sum0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) sum0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) sum0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 = (q31_t) ((((q63_t) sum0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 << 1); - - /* Decrement the loop counter */ - blkCntN2--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c deleted file mode 100644 index b655a6be6d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_f32.c +++ /dev/null @@ -1,112 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_f32.c -* -* Description: Floating-point FIR Decimator initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR decimator. - * @param[in,out] *S points to an instance of the floating-point FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_f32(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_f32( - arm_fir_decimate_instance_f32 * S, - uint16_t numTaps, - uint8_t M, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation Factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c deleted file mode 100644 index 1a1fee8a2e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q15.c +++ /dev/null @@ -1,114 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_q15.c -* -* Description: Initialization function for the Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the Q15 FIR decimator. - * @param[in,out] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples - * to the call arm_fir_decimate_q15(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_q15( - arm_fir_decimate_instance_q15 * S, - uint16_t numTaps, - uint8_t M, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size of buffer is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c deleted file mode 100644 index e2ac8165e6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_init_q31.c +++ /dev/null @@ -1,112 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_init_q31.c -* -* Description: Initialization function for Q31 FIR Decimation filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Initialization function for the Q31 FIR decimator. - * @param[in,out] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] *pCoeffs points to the filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 words where blockSize is the number of input samples passed to arm_fir_decimate_q31(). - * M is the decimation factor. - */ - -arm_status arm_fir_decimate_init_q31( - arm_fir_decimate_instance_q31 * S, - uint16_t numTaps, - uint8_t M, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The size of the input block must be a multiple of the decimation factor */ - if((blockSize % M) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Decimation factor */ - S->M = M; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c deleted file mode 100644 index 28b5f13dd6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q15.c +++ /dev/null @@ -1,691 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_q15.c -* -* Description: Q15 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR decimator. - * @param[in] *S points to an instance of the Q15 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the location where the output result is written. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * Refer to the function arm_fir_decimate_fast_q15() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -#ifndef ARM_MATH_CM0 - -#ifndef UNALIGNED_SUPPORT_DISABLE - -void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q31_t x0, x1, c0, c1; /* Temporary variables to hold state and coefficient values */ - q63_t sum0; /* Accumulators */ - q63_t acc0, acc1; - q15_t *px0, *px1; - uint32_t blkCntN3; - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize / 2; - blkCntN3 = outBlockSize - (2 * blkCnt); - - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = 2 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - px0 = pState; - - px1 = pState + S->M; - - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px0)++; - - x1 = *__SIMD32(px1)++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLALD(x0, c0, acc0); - - acc1 = __SMLALD(x1, c0, acc1); - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px0)++; - - x1 = *__SIMD32(px1)++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLALD(x0, c0, acc0); - - acc1 = __SMLALD(x1, c0, acc1); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px0++; - - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 = __SMLALD(x0, c0, acc0); - acc1 = __SMLALD(x1, c0, acc1); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M * 2; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - *pDst++ = (q15_t) (__SSAT((acc1 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - - - while(blkCntN3 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] and b[numTaps-2] coefficients */ - c0 = *__SIMD32(pb)++; - - /* Read x[n-numTaps-1] and x[n-numTaps-2]sample */ - x0 = *__SIMD32(px)++; - - /* Read the b[numTaps-3] and b[numTaps-4] coefficient */ - c1 = *__SIMD32(pb)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Read x[n-numTaps-2] and x[n-numTaps-3] sample */ - x0 = *__SIMD32(px)++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c1, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 = __SMLALD(x0, c0, sum0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCntN3--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -#else - - -void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q15_t x0, x1, c0; /* Temporary variables to hold state and coefficient values */ - q63_t sum0; /* Accumulators */ - q63_t acc0, acc1; - q15_t *px0, *px1; - uint32_t blkCntN3; - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize / 2; - blkCntN3 = outBlockSize - (2 * blkCnt); - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = 2 * S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - px0 = pState; - - px1 = pState + S->M; - - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-1] for sample 0 and for sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-2] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-3] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-3] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-4] for sample 0 and sample 1 */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px0++; - x1 = *px1++; - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M * 2; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - *pDst++ = (q15_t) (__SSAT((acc1 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - while(blkCntN3 > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the Read b[numTaps-1] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-1] and sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-2] and sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-3] coefficients */ - c0 = *pb++; - - /* Read x[n-numTaps-3] sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *pb++; - - /* Read x[n-numTaps-4] sample */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* Store filter output, smlad returns the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCntN3--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#else - - -void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer coefficient buffer */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q63_t sum0; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, blkCnt, tapCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /*Set sum to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += (q31_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /*Store filter output , smlad will return the values in 2.14 format */ - /* so downsacle by 15 to get output in 1.15 */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = numTaps - 1u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - -} -#endif /* #ifndef ARM_MATH_CM0 */ - - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c deleted file mode 100644 index 59c0fed7f8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_decimate_q31.c +++ /dev/null @@ -1,306 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_decimate_q31.c -* -* Description: Q31 FIR Decimator. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_decimate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR decimator. - * @param[in] *S points to an instance of the Q31 FIR decimator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - * @return none - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits (where log2 is read as log to the base 2). - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - * - * \par - * Refer to the function arm_fir_decimate_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_decimate_q31( - const arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - q31_t *px; /* Temporary pointers for state buffer */ - q31_t *pb; /* Temporary pointers for coefficient buffer */ - q63_t sum0; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of taps */ - uint32_t i, tapCnt, blkCnt, outBlockSize = blockSize / S->M; /* Loop counters */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-1] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-2] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (numTaps - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - - i = (numTaps - 1u) % 0x04u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Total number of output samples to be computed */ - blkCnt = outBlockSize; - - while(blkCnt > 0u) - { - /* Copy decimation factor number of new input samples into the state buffer */ - i = S->M; - - do - { - *pStateCurnt++ = *pSrc++; - - } while(--i); - - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *pb++; - - /* Fetch 1 state variable */ - x0 = *px++; - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by the decimation factor - * to process the next group of decimation factor number samples */ - pState = pState + S->M; - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = numTaps - 1u; - - /* copy data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_decimate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c deleted file mode 100644 index 7f951f86bc..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_f32.c +++ /dev/null @@ -1,554 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_f32.c -* -* Description: Floating-point FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR Finite Impulse Response (FIR) Filters - * - * This set of functions implements Finite Impulse Response (FIR) filters - * for Q7, Q15, Q31, and floating-point data types. Fast versions of Q15 and Q31 are also provided. - * The functions operate on blocks of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst points to input and output arrays containing blockSize values. - * - * \par Algorithm: - * The FIR filter algorithm is based upon a sequence of multiply-accumulate (MAC) operations. - * Each filter coefficient b[n] is multiplied by a state variable which equals a previous input sample x[n]. - *
  
- *    y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]  
- * 
- * \par - * \image html FIR.gif "Finite Impulse Response filter" - * \par - * pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
  
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}  
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the following order. - * \par - *
  
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}  
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1. - * The increased state buffer length allows circular addressing, which is traditionally used in the FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 4 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 4 different data type filter instance structures - *
  
- *arm_fir_instance_f32 S = {numTaps, pState, pCoeffs};  
- *arm_fir_instance_q31 S = {numTaps, pState, pCoeffs};  
- *arm_fir_instance_q15 S = {numTaps, pState, pCoeffs};  
- *arm_fir_instance_q7 S =  {numTaps, pState, pCoeffs};  
- * 
- * - * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * - * @param[in] *S points to an instance of the floating-point FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_fir_f32( - const arm_fir_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t acc0, acc1, acc2, acc3, acc4, acc5, acc6, acc7; /* Accumulators */ - float32_t x0, x1, x2, x3, x4, x5, x6, x7, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 3; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - acc4 = 0.0f; - acc5 = 0.0f; - acc6 = 0.0f; - acc7 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the first three samples from the state buffer: x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *px++; - x1 = *px++; - x2 = *px++; - x3 = *px++; - x4 = *px++; - x5 = *px++; - x6 = *px++; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 3u; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - while(tapCnt > 0u) - { - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x7 = *(px++); - - /* acc0 += b[numTaps-1] * x[n-numTaps] */ - acc0 += x0 * c0; - - /* acc1 += b[numTaps-1] * x[n-numTaps-1] */ - acc1 += x1 * c0; - - /* acc2 += b[numTaps-1] * x[n-numTaps-2] */ - acc2 += x2 * c0; - - /* acc3 += b[numTaps-1] * x[n-numTaps-3] */ - acc3 += x3 * c0; - - /* acc4 += b[numTaps-1] * x[n-numTaps-4] */ - acc4 += x4 * c0; - - /* acc1 += b[numTaps-1] * x[n-numTaps-5] */ - acc5 += x5 * c0; - - /* acc2 += b[numTaps-1] * x[n-numTaps-6] */ - acc6 += x6 * c0; - - /* acc3 += b[numTaps-1] * x[n-numTaps-7] */ - acc7 += x7 * c0; - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulate */ - acc0 += x1 * c0; - acc1 += x2 * c0; - acc2 += x3 * c0; - acc3 += x4 * c0; - acc4 += x5 * c0; - acc5 += x6 * c0; - acc6 += x7 * c0; - acc7 += x0 * c0; - - /* Read the b[numTaps-3] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x2 * c0; - acc1 += x3 * c0; - acc2 += x4 * c0; - acc3 += x5 * c0; - acc4 += x6 * c0; - acc5 += x7 * c0; - acc6 += x0 * c0; - acc7 += x1 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x3 * c0; - acc1 += x4 * c0; - acc2 += x5 * c0; - acc3 += x6 * c0; - acc4 += x7 * c0; - acc5 += x0 * c0; - acc6 += x1 * c0; - acc7 += x2 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x4 * c0; - acc1 += x5 * c0; - acc2 += x6 * c0; - acc3 += x7 * c0; - acc4 += x0 * c0; - acc5 += x1 * c0; - acc6 += x2 * c0; - acc7 += x3 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x4 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x5 * c0; - acc1 += x6 * c0; - acc2 += x7 * c0; - acc3 += x0 * c0; - acc4 += x1 * c0; - acc5 += x2 * c0; - acc6 += x3 * c0; - acc7 += x4 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x5 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x6 * c0; - acc1 += x7 * c0; - acc2 += x0 * c0; - acc3 += x1 * c0; - acc4 += x2 * c0; - acc5 += x3 * c0; - acc6 += x4 * c0; - acc7 += x5 * c0; - - /* Read the b[numTaps-4] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x6 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x7 * c0; - acc1 += x0 * c0; - acc2 += x1 * c0; - acc3 += x2 * c0; - acc4 += x3 * c0; - acc5 += x4 * c0; - acc6 += x5 * c0; - acc7 += x6 * c0; - - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x8u; - - while(tapCnt > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x7 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - acc4 += x4 * c0; - acc5 += x5 * c0; - acc6 += x6 * c0; - acc7 += x7 * c0; - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - x3 = x4; - x4 = x5; - x5 = x6; - x6 = x7; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 8; - - /* The results in the 4 accumulators, store in the destination buffer. */ - *pDst++ = acc0; - *pDst++ = acc1; - *pDst++ = acc2; - *pDst++ = acc3; - *pDst++ = acc4; - *pDst++ = acc5; - *pDst++ = acc6; - *pDst++ = acc7; - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x8u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += *px++ * *pb++; - i--; - - } while(i > 0u); - - /* The result is store in the destination buffer. */ - *pDst++ = acc0; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - -#else - -void arm_fir_f32( - const arm_fir_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* Run the below code for Cortex-M0 */ - - float32_t acc; - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0.0f; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += *px++ * *pb++; - i--; - - } while(i > 0u); - - /* The result is store in the destination buffer. */ - *pDst++ = acc; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the starting of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = numTaps - 1u; - - /* Copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c deleted file mode 100644 index 59abff2f55..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q15.c +++ /dev/null @@ -1,341 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_fast_q15.c -* -* Description: Q15 Fast FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/16 -* Initial version -* -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q15 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * This fast version uses a 32-bit accumulator with 2.30 format. - * The accumulator maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * The 2.30 accumulator is then truncated to 2.15 format and saturated to yield the 1.15 result. - * - * \par - * Refer to the function arm_fir_q15() for a slower implementation of this function which uses 64-bit accumulation to avoid wrap around distortion. Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_init_q15() to initialize the filter structure. - */ - -void arm_fir_fast_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - q15_t *px; /* Temporary q31 pointer for SIMD state buffer accesses */ - q31_t x0, x1, x2, c0; /* Temporary variables to hold SIMD state and coefficient values */ - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer. - ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Typecast q15_t pointer to q31_t pointer for state reading in q31_t */ - px = pState; - - /* Typecast q15_t pointer to q31_t pointer for coefficient reading in q31_t */ - pb = pCoeffs; - - /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ - x0 = *__SIMD32(px)++; - - /* Read the third and forth samples from the state buffer: x[n-N-2], x[n-N-3] */ - x2 = *__SIMD32(px)++; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(numTaps%4) coefficients. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0) - { - /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - acc0 = __SMLAD(x0, c0, acc0); - - /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ - acc2 = __SMLAD(x2, c0, acc2); - - /* pack x[n-N-1] and x[n-N-2] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* Read state x[n-N-4], x[n-N-5] */ - x0 = _SIMD32_OFFSET(px); - - /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* pack x[n-N-3] and x[n-N-4] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x0, x2, 0); -#else - x1 = __PKHBT(x2, x0, 0); -#endif - - /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ - acc3 = __SMLADX(x1, c0, acc3); - - /* Read coefficients b[N-2], b[N-3] */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ - acc0 = __SMLAD(x2, c0, acc0); - - /* Read state x[n-N-6], x[n-N-7] with offset */ - x2 = _SIMD32_OFFSET(px + 2u); - - /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ - acc2 = __SMLAD(x0, c0, acc2); - - /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ - acc1 = __SMLADX(x1, c0, acc1); - - /* pack x[n-N-5] and x[n-N-6] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ - acc3 = __SMLADX(x1, c0, acc3); - - /* Update state pointer for next state reading */ - px += 4u; - - /* Decrement tap count */ - tapCnt--; - - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps. - ** This is always be 2 taps since the filter length is even. */ - if((numTaps & 0x3u) != 0u) - { - - /* Read last two coefficients */ - c0 = *__SIMD32(pb)++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLAD(x0, c0, acc0); - acc2 = __SMLAD(x2, c0, acc2); - - /* pack state variables */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* Read last state variables */ - x0 = *__SIMD32(px); - - /* Perform the multiply-accumulates */ - acc1 = __SMLADX(x1, c0, acc1); - - /* pack state variables */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x0, x2, 0); -#else - x1 = __PKHBT(x2, x0, 0); -#endif - - /* Perform the multiply-accumulates */ - acc3 = __SMLADX(x1, c0, acc3); - } - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. - ** Then store the 4 outputs in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - while(blkCnt > 0u) - { - /* Copy two samples into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Use SIMD to hold states and coefficients */ - px = pState; - pb = pCoeffs; - - tapCnt = numTaps >> 1u; - - do - { - - acc0 += (q31_t) * px++ * *pb++; - acc0 += (q31_t) * px++ * *pb++; - - tapCnt--; - } - while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy remaining data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c deleted file mode 100644 index e384ff9732..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_fast_q31.c +++ /dev/null @@ -1,309 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_fast_q31.c -* -* Description: Processing function for the Q31 Fast FIR filter. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.9 2010/08/27 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q31 structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * - * \par - * This function is optimized for speed at the expense of fixed-point precision and overflow protection. - * The result of each 1.31 x 1.31 multiplication is truncated to 2.30 format. - * These intermediate results are added to a 2.30 accumulator. - * Finally, the accumulator is saturated and converted to a 1.31 result. - * The fast version has the same overflow behavior as the standard version and provides less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * - * \par - * Refer to the function arm_fir_q31() for a slower implementation of this function which uses a 64-bit accumulator to provide higher precision. Both the slow and the fast versions use the same instance structure. - * Use the function arm_fir_init_q31() to initialize the filter structure. - */ - -void arm_fir_fast_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t x0, x1, x2, x3; /* Temporary variables to hold state */ - q31_t c0; /* Temporary variable to hold coefficient value */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first three samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps] * x[n-numTaps] */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* acc1 += b[numTaps] * x[n-numTaps-1] */ - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* acc2 += b[numTaps] * x[n-numTaps-2] */ - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - - /* acc3 += b[numTaps] * x[n-numTaps-3] */ - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x1 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x2 * c0)) >> 32); - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x3 * c0)) >> 32); - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x0 * c0)) >> 32); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x2 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x3 * c0)) >> 32); - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x0 * c0)) >> 32); - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x1 * c0)) >> 32); - - /* Read the b[numTaps-3] coefficients */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x3 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x0 * c0)) >> 32); - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x1 * c0)) >> 32); - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x2 * c0)) >> 32); - i--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - - i = numTaps - (tapCnt * 4u); - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 = (q31_t) ((((q63_t) acc0 << 32) + ((q63_t) x0 * c0)) >> 32); - acc1 = (q31_t) ((((q63_t) acc1 << 32) + ((q63_t) x1 * c0)) >> 32); - acc2 = (q31_t) ((((q63_t) acc2 << 32) + ((q63_t) x2 * c0)) >> 32); - acc3 = (q31_t) ((((q63_t) acc3 << 32) + ((q63_t) x3 * c0)) >> 32); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.31 - ** Then store the 4 outputs in the destination buffer. */ - *pDst++ = (q31_t) (acc0 << 1); - *pDst++ = (q31_t) (acc1 << 1); - *pDst++ = (q31_t) (acc2 << 1); - *pDst++ = (q31_t) (acc3 << 1); - - /* Decrement the samples loop counter */ - blkCnt--; - } - - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 = - (q31_t) ((((q63_t) acc0 << 32) + - ((q63_t) (*px++) * (*(pb++)))) >> 32); - i--; - } while(i > 0u); - - /* The result is in 2.30 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc0 << 1); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c deleted file mode 100644 index aaeddf5f6b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_f32.c +++ /dev/null @@ -1,94 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_f32.c -* -* Description: Floating-point FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the floating-point FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_f32(). - */ - -void arm_fir_init_f32( - arm_fir_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and the size of state buffer is (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c deleted file mode 100644 index 02bb336235..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q15.c +++ /dev/null @@ -1,152 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q15.c -* -* Description: Q15 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in,out] *S points to an instance of the Q15 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize is number of samples processed per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if - * numTaps is not greater than or equal to 4 and even. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * Note that numTaps must be even and greater than or equal to 4. - * To implement an odd length filter simply increase numTaps by 1 and set the last coefficient to zero. - * For example, to implement a filter with numTaps=3 and coefficients - *
    
- *     {0.3, -0.8, 0.3}    
- * 
- * set numTaps=4 and use the coefficients: - *
    
- *     {0.3, -0.8, 0.3, 0}.    
- * 
- * Similarly, to implement a two point filter - *
    
- *     {0.3, -0.3}    
- * 
- * set numTaps=4 and use the coefficients: - *
    
- *     {0.3, -0.3, 0, 0}.    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize, when running on Cortex-M4 and Cortex-M3 and is of length numTaps+blockSize-1, when running on Cortex-M0 where blockSize is the number of input samples processed by each call to arm_fir_q15(). - */ - -arm_status arm_fir_init_q15( - arm_fir_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - arm_status status; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* The Number of filter coefficients in the filter must be even and at least 4 */ - if(numTaps & 0x1u) - { - status = ARM_MATH_ARGUMENT_ERROR; - } - else - { - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps ) */ - memset(pState, 0, (numTaps + (blockSize)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - - return (status); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c deleted file mode 100644 index 997a78427f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q31.c +++ /dev/null @@ -1,94 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q31.c -* -* Description: Q31 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @details - * - * @param[in,out] *S points to an instance of the Q31 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q31(). - */ - -void arm_fir_init_q31( - arm_fir_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and state array size is (blockSize + numTaps - 1) */ - memset(pState, 0, (blockSize + ((uint32_t) numTaps - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c deleted file mode 100644 index 65a49a823e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_init_q7.c +++ /dev/null @@ -1,92 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_init_q7.c -* -* Description: Q7 FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* ------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ -/** - * @param[in,out] *S points to an instance of the Q7 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficients buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of samples that are processed per call. - * @return none - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to the array of state variables. - * pState is of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_fir_q7(). - */ - -void arm_fir_init_q7( - arm_fir_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - uint32_t blockSize) -{ - - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear the state buffer. The size is always (blockSize + numTaps - 1) */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q7_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c deleted file mode 100644 index c966a0ced7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_f32.c +++ /dev/null @@ -1,574 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_f32.c -* -* Description: FIR interpolation for floating-point sequences. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @defgroup FIR_Interpolate Finite Impulse Response (FIR) Interpolator - * - * These functions combine an upsampler (zero stuffer) and an FIR filter. - * They are used in multirate systems for increasing the sample rate of a signal without introducing high frequency images. - * Conceptually, the functions are equivalent to the block diagram below: - * \image html FIRInterpolator.gif "Components included in the FIR Interpolator functions" - * After upsampling by a factor of L, the signal should be filtered by a lowpass filter with a normalized - * cutoff frequency of 1/L in order to eliminate high frequency copies of the spectrum. - * The user of the function is responsible for providing the filter coefficients. - * - * The FIR interpolator functions provided in the CMSIS DSP Library combine the upsampler and FIR filter in an efficient manner. - * The upsampler inserts L-1 zeros between each sample. - * Instead of multiplying by these zero values, the FIR filter is designed to skip them. - * This leads to an efficient implementation without any wasted effort. - * The functions operate on blocks of input and output data. - * pSrc points to an array of blockSize input values and - * pDst points to an array of blockSize*L output values. - * - * The library provides separate functions for Q15, Q31, and floating-point data types. - * - * \par Algorithm: - * The functions use a polyphase filter structure: - *
    
- *    y[n] = b[0] * x[n] + b[L]   * x[n-1] + ... + b[L*(phaseLength-1)] * x[n-phaseLength+1]    
- *    y[n+1] = b[1] * x[n] + b[L+1] * x[n-1] + ... + b[L*(phaseLength-1)+1] * x[n-phaseLength+1]    
- *    ...    
- *    y[n+(L-1)] = b[L-1] * x[n] + b[2*L-1] * x[n-1] + ....+ b[L*(phaseLength-1)+(L-1)] * x[n-phaseLength+1]    
- * 
- * This approach is more efficient than straightforward upsample-then-filter algorithms. - * With this method the computation is reduced by a factor of 1/L when compared to using a standard FIR filter. - * \par - * pCoeffs points to a coefficient array of size numTaps. - * numTaps must be a multiple of the interpolation factor L and this is checked by the - * initialization functions. - * Internally, the function divides the FIR filter's impulse response into shorter filters of length - * phaseLength=numTaps/L. - * Coefficients are stored in time reversed order. - * \par - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to a state array of size blockSize + phaseLength - 1. - * Samples in the state buffer are stored in the order: - * \par - *
    
- *    {x[n-phaseLength+1], x[n-phaseLength], x[n-phaseLength-1], x[n-phaseLength-2]....x[0], x[1], ..., x[blockSize-1]}    
- * 
- * The state variables are updated after each block of data is processed, the coefficients are untouched. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable array should be allocated separately. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - Checks to make sure that the length of the filter is a multiple of the interpolation factor. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * The code below statically initializes each of the 3 different data type filter instance structures - *
    
- * arm_fir_interpolate_instance_f32 S = {L, phaseLength, pCoeffs, pState};    
- * arm_fir_interpolate_instance_q31 S = {L, phaseLength, pCoeffs, pState};    
- * arm_fir_interpolate_instance_q15 S = {L, phaseLength, pCoeffs, pState};    
- * 
- * where L is the interpolation factor; phaseLength=numTaps/L is the - * length of each of the shorter FIR filters used internally, - * pCoeffs is the address of the coefficient buffer; - * pState is the address of the state buffer. - * Be sure to set the values in the state buffer to zeros when doing static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR interpolate filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the floating-point FIR interpolator. - * @param[in] *S points to an instance of the floating-point FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_fir_interpolate_f32( - const arm_fir_interpolate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - float32_t sum0; /* Accumulators */ - float32_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, j; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - float32_t acc0, acc1, acc2, acc3; - float32_t x1, x2, x3; - uint32_t blkCntN4; - float32_t c1, c2, c3; - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Initialise blkCnt */ - blkCnt = blockSize / 4; - blkCntN4 = blockSize - (4 * blkCnt); - - /* Samples loop unrolled by 4 */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = (S->L); - - while(i > 0u) - { - /* Set accumulator to zero */ - acc0 = 0.0f; - acc1 = 0.0f; - acc2 = 0.0f; - acc3 = 0.0f; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2u; - - x0 = *(ptr1++); - x1 = *(ptr1++); - x2 = *(ptr1++); - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x3 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Read the coefficient */ - c1 = *(ptr2 + S->L); - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += x1 * c1; - acc1 += x2 * c1; - acc2 += x3 * c1; - acc3 += x0 * c1; - - /* Read the coefficient */ - c2 = *(ptr2 + S->L * 2); - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += x2 * c2; - acc1 += x3 * c2; - acc2 += x0 * c2; - acc3 += x1 * c2; - - /* Read the coefficient */ - c3 = *(ptr2 + S->L * 3); - - /* Read the input sample */ - x2 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += x3 * c3; - acc1 += x0 * c3; - acc2 += x1 * c3; - acc3 += x2 * c3; - - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += 4 * S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen % 0x4u; - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x3 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += x0 * c0; - acc1 += x1 * c0; - acc2 += x2 * c0; - acc3 += x3 * c0; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* update states for next sample processing */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst = acc0; - *(pDst + S->L) = acc1; - *(pDst + 2 * S->L) = acc2; - *(pDst + 3 * S->L) = acc3; - - pDst++; - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 4; - - pDst += S->L * 3; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - - while(blkCntN4 > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0.0f; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2u; - while(tapCnt > 0u) - { - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += x0 * c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum0 += *(ptr1++) * (*ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum0; - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCntN4--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (phaseLen - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (phaseLen - 1u) % 0x04u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - -#else - - /* Run the below code for Cortex-M0 */ - -void arm_fir_interpolate_f32( - const arm_fir_interpolate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - - - float32_t sum; /* Accumulator */ - uint32_t i, blkCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0.0f; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - /* Loop over the polyPhase length */ - tapCnt = phaseLen; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += *ptr1++ * *ptr2; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = sum; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = phaseLen - 1u; - - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c deleted file mode 100644 index b193472647..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_f32.c +++ /dev/null @@ -1,116 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_f32.c -* -* Description: Floating-point FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR interpolator. - * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}    
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_f32(). - */ - -arm_status arm_fir_interpolate_init_f32( - arm_fir_interpolate_instance_f32 * S, - uint8_t L, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of state array is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + - ((uint32_t) S->phaseLength - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c deleted file mode 100644 index b344fc785a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q15.c +++ /dev/null @@ -1,115 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_q15.c -* -* Description: Q15 FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Initialization function for the Q15 FIR interpolator. - * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}    
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q15(). - */ - -arm_status arm_fir_interpolate_init_q15( - arm_fir_interpolate_instance_q15 * S, - uint8_t L, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c deleted file mode 100644 index f0383b8e9b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_init_q31.c +++ /dev/null @@ -1,116 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_init_q31.c -* -* Description: Q31 FIR interpolator initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - - -/** - * @brief Initialization function for the Q31 FIR interpolator. - * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] *pCoeffs points to the filter coefficient buffer. - * @param[in] *pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[numTaps-2], ..., b[1], b[0]}    
- * 
- * The length of the filter numTaps must be a multiple of the interpolation factor L. - * \par - * pState points to the array of state variables. - * pState is of length (numTaps/L)+blockSize-1 words - * where blockSize is the number of input samples processed by each call to arm_fir_interpolate_q31(). - */ - -arm_status arm_fir_interpolate_init_q31( - arm_fir_interpolate_instance_q31 * S, - uint8_t L, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - arm_status status; - - /* The filter length must be a multiple of the interpolation factor */ - if((numTaps % L) != 0u) - { - /* Set status as ARM_MATH_LENGTH_ERROR */ - status = ARM_MATH_LENGTH_ERROR; - } - else - { - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign Interpolation factor */ - S->L = L; - - /* Assign polyPhaseLength */ - S->phaseLength = numTaps / L; - - /* Clear state buffer and size of buffer is always phaseLength + blockSize - 1 */ - memset(pState, 0, - (blockSize + ((uint32_t) S->phaseLength - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - status = ARM_MATH_SUCCESS; - } - - return (status); - -} - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c deleted file mode 100644 index d17d8d8037..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q15.c +++ /dev/null @@ -1,503 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_q15.c -* -* Description: Q15 FIR interpolation. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR interpolator. - * @param[in] *S points to an instance of the Q15 FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_fir_interpolate_q15( - const arm_fir_interpolate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - q63_t sum0; /* Accumulators */ - q15_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, j, tapCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ - uint32_t blkCntN2; - q63_t acc0, acc1; - q15_t x1; - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + ((q31_t) phaseLen - 1); - - /* Initialise blkCnt */ - blkCnt = blockSize / 2; - blkCntN2 = blockSize - (2 * blkCnt); - - /* Samples loop unrolled by 2 */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = (S->L); - - while(i > 0u) - { - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2u; - - x0 = *(ptr1++); - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - - /* Read the coefficient */ - c0 = *(ptr2 + S->L); - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x1 *c0; - acc1 += (q63_t) x0 *c0; - - - /* Read the coefficient */ - c0 = *(ptr2 + S->L * 2); - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - /* Read the coefficient */ - c0 = *(ptr2 + S->L * 3); - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x1 *c0; - acc1 += (q63_t) x0 *c0; - - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += 4 * S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen % 0x4u; - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* update states for next sample processing */ - x0 = x1; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst = (q15_t) (__SSAT((acc0 >> 15), 16)); - *(pDst + S->L) = (q15_t) (__SSAT((acc1 >> 15), 16)); - - pDst++; - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 2; - - pDst += S->L; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blkCntN2; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2; - while(tapCnt > 0u) - { - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen & 0x3u; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((sum0 >> 15), 16)); - - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = ((uint32_t) phaseLen - 1u) >> 2u; - - /* copy data */ - while(i > 0u) - { -#ifndef UNALIGNED_SUPPORT_DISABLE - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - -#else - - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - i--; - } - - i = ((uint32_t) phaseLen - 1u) % 0x04u; - - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } -} - -#else - - /* Run the below code for Cortex-M0 */ - -void arm_fir_interpolate_q15( - const arm_fir_interpolate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - q63_t sum; /* Accumulator */ - q15_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, tapCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (phaseLen - 1u); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - /* Loop over the polyPhase length */ - tapCnt = (uint32_t) phaseLen; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *ptr2; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *ptr1++; - - /* Perform the multiply-accumulate */ - sum += ((q31_t) x0 * c0); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Store the result after converting to 1.15 format in the destination buffer */ - *pDst++ = (q15_t) (__SSAT((sum >> 15), 16)); - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the start of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - i = (uint32_t) phaseLen - 1u; - - while(i > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - i--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c deleted file mode 100644 index 689b4d3372..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_interpolate_q31.c +++ /dev/null @@ -1,499 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_interpolate_q31.c -* -* Description: Q31 FIR interpolation. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Interpolate - * @{ - */ - -/** - * @brief Processing function for the Q31 FIR interpolator. - * @param[in] *S points to an instance of the Q31 FIR interpolator structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 1/(numTaps/L). - * since numTaps/L additions occur per output sample. - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_fir_interpolate_q31( - const arm_fir_interpolate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - q63_t sum0; /* Accumulators */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt, j; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - uint32_t blkCntN2; - q63_t acc0, acc1; - q31_t x1; - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + ((q31_t) phaseLen - 1); - - /* Initialise blkCnt */ - blkCnt = blockSize / 2; - blkCntN2 = blockSize - (2 * blkCnt); - - /* Samples loop unrolled by 2 */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = (S->L); - - while(i > 0u) - { - /* Set accumulator to zero */ - acc0 = 0; - acc1 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2u; - - x0 = *(ptr1++); - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - - /* Read the coefficient */ - c0 = *(ptr2 + S->L); - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x1 *c0; - acc1 += (q63_t) x0 *c0; - - - /* Read the coefficient */ - c0 = *(ptr2 + S->L * 2); - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - /* Read the coefficient */ - c0 = *(ptr2 + S->L * 3); - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x1 *c0; - acc1 += (q63_t) x0 *c0; - - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += 4 * S->L; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen % 0x4u; - - while(tapCnt > 0u) - { - - /* Read the input sample */ - x1 = *(ptr1++); - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Perform the multiply-accumulate */ - acc0 += (q63_t) x0 *c0; - acc1 += (q63_t) x1 *c0; - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* update states for next sample processing */ - x0 = x1; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst = (q31_t) (acc0 >> 31); - *(pDst + S->L) = (q31_t) (acc1 >> 31); - - - pDst++; - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 2; - - pDst += S->L; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 2, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blkCntN2; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Address modifier index of coefficient buffer */ - j = 1u; - - /* Loop over the Interpolation factor. */ - i = S->L; - while(i > 0u) - { - /* Set accumulator to zero */ - sum0 = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (S->L - j); - - /* Loop over the polyPhase length. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(4*S->L) coefficients. */ - tapCnt = phaseLen >> 2; - while(tapCnt > 0u) - { - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Upsampling is done by stuffing L-1 zeros between each sample. - * So instead of multiplying zeros with coefficients, - * Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the polyPhase length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = phaseLen & 0x3u; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *(ptr1++); - - /* Perform the multiply-accumulate */ - sum0 += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum0 >> 31); - - /* Increment the address modifier index of coefficient buffer */ - j++; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (phaseLen - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - tapCnt = (phaseLen - 1u) % 0x04u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - - -#else - -void arm_fir_interpolate_q31( - const arm_fir_interpolate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t *ptr1, *ptr2; /* Temporary pointers for state and coefficient buffers */ - - /* Run the below code for Cortex-M0 */ - - q63_t sum; /* Accumulator */ - q31_t x0, c0; /* Temporary variables to hold state and coefficient values */ - uint32_t i, blkCnt; /* Loop counters */ - uint16_t phaseLen = S->phaseLength, tapCnt; /* Length of each polyphase filter component */ - - - /* S->pState buffer contains previous frame (phaseLen - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + ((q31_t) phaseLen - 1); - - /* Total number of intput samples */ - blkCnt = blockSize; - - /* Loop over the blockSize. */ - while(blkCnt > 0u) - { - /* Copy new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Loop over the Interpolation factor. */ - i = S->L; - - while(i > 0u) - { - /* Set accumulator to zero */ - sum = 0; - - /* Initialize state pointer */ - ptr1 = pState; - - /* Initialize coefficient pointer */ - ptr2 = pCoeffs + (i - 1u); - - tapCnt = phaseLen; - - while(tapCnt > 0u) - { - /* Read the coefficient */ - c0 = *(ptr2); - - /* Increment the coefficient pointer by interpolation factor times. */ - ptr2 += S->L; - - /* Read the input sample */ - x0 = *ptr1++; - - /* Perform the multiply-accumulate */ - sum += (q63_t) x0 *c0; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is in the accumulator, store in the destination buffer. */ - *pDst++ = (q31_t) (sum >> 31); - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 1 - * to process the next group of interpolation factor number samples */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last phaseLen - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = phaseLen - 1u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - /** - * @} end of FIR_Interpolate group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c deleted file mode 100644 index 3745ffb6a2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_f32.c +++ /dev/null @@ -1,499 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_f32.c -* -* Description: Processing function for the floating-point FIR Lattice filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_Lattice Finite Impulse Response (FIR) Lattice Filters - * - * This set of functions implements Finite Impulse Response (FIR) lattice filters - * for Q15, Q31 and floating-point data types. Lattice filters are used in a - * variety of adaptive filter applications. The filter structure is feedforward and - * the net impulse response is finite length. - * The functions operate on blocks - * of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst point to input and output arrays containing blockSize values. - * - * \par Algorithm: - * \image html FIRLattice.gif "Finite Impulse Response Lattice filter" - * The following difference equation is implemented: - *
    
- *    f0[n] = g0[n] = x[n]    
- *    fm[n] = fm-1[n] + km * gm-1[n-1] for m = 1, 2, ...M    
- *    gm[n] = km * fm-1[n] + gm-1[n-1] for m = 1, 2, ...M    
- *    y[n] = fM[n]    
- * 
- * \par - * pCoeffs points to tha array of reflection coefficients of size numStages. - * Reflection Coefficients are stored in the following order. - * \par - *
    
- *    {k1, k2, ..., kM}    
- * 
- * where M is number of stages - * \par - * pState points to a state array of size numStages. - * The state variables (g values) hold previous inputs and are stored in the following order. - *
    
- *    {g0[n], g1[n], g2[n] ...gM-1[n]}    
- * 
- * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: - *
    
- *arm_fir_lattice_instance_f32 S = {numStages, pState, pCoeffs};    
- *arm_fir_lattice_instance_q31 S = {numStages, pState, pCoeffs};    
- *arm_fir_lattice_instance_q15 S = {numStages, pState, pCoeffs};    
- * 
- * \par - * where numStages is the number of stages in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer. - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the FIR Lattice filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - - /** - * @brief Processing function for the floating-point FIR lattice filter. - * @param[in] *S points to an instance of the floating-point FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_fir_lattice_f32( - const arm_fir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t *pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *px; /* temporary state pointer */ - float32_t *pk; /* temporary coefficient pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t fcurr1, fnext1, gcurr1, gnext1; /* temporary variables for first sample in loop unrolling */ - float32_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - float32_t fcurr3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ - float32_t fcurr4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Number of stages in the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - gcurr1 = 0.0f; - pState = &S->pState[0]; - - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - - /* Read two samples from input buffer */ - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - fcurr2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* Read g0(n-1) from state */ - gcurr1 = *px; - - /* Process first sample for first tap */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (fcurr1 * (*pk)) + gcurr1; - - /* Process second sample for first tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * fcurr1); - gnext2 = (fcurr2 * (*pk)) + fcurr1; - - /* Read next two samples from input buffer */ - /* f0(n+2) = x(n+2) */ - fcurr3 = *pSrc++; - fcurr4 = *pSrc++; - - /* Copy only last input samples into the state buffer - which will be used for next four samples processing */ - *px++ = fcurr4; - - /* Process third sample for first tap */ - fnext3 = fcurr3 + ((*pk) * fcurr2); - gnext3 = (fcurr3 * (*pk)) + fcurr2; - - /* Process fourth sample for first tap */ - fnext4 = fcurr4 + ((*pk) * fcurr3); - gnext4 = (fcurr4 * (*pk++)) + fcurr3; - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - /* Loop unrolling. Process 4 taps at a time . */ - stageCnt = (numStages - 1u) >> 2u; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numStages-3 coefficients. */ - - /* Process 2nd, 3rd, 4th and 5th taps ... here */ - while(stageCnt > 0u) - { - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext4; - - /* Process first sample for 2nd, 6th .. tap */ - /* Sample processing for K2, K6.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* Process second sample for 2nd, 6th .. tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * gnext1); - /* Process third sample for 2nd, 6th .. tap */ - fnext3 = fcurr3 + ((*pk) * gnext2); - /* Process fourth sample for 2nd, 6th .. tap */ - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g2(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K3, K7.... */ - /* Process first sample for 3rd, 7th .. tap */ - /* f3(n) = f2(n) + K3 * g2(n-1) */ - fcurr1 = fnext1 + ((*pk) * gcurr1); - /* Process second sample for 3rd, 7th .. tap */ - fcurr2 = fnext2 + ((*pk) * gnext1); - /* Process third sample for 3rd, 7th .. tap */ - fcurr3 = fnext3 + ((*pk) * gnext2); - /* Process fourth sample for 3rd, 7th .. tap */ - fcurr4 = fnext4 + ((*pk) * gnext3); - - /* Calculation of state values for next stage */ - /* g3(n) = f2(n) * K3 + g2(n-1) */ - gnext4 = (fnext4 * (*pk)) + gnext3; - gnext3 = (fnext3 * (*pk)) + gnext2; - gnext2 = (fnext2 * (*pk)) + gnext1; - gnext1 = (fnext1 * (*pk++)) + gcurr1; - - - /* Read g1(n-1), g3(n-1) .... from state */ - gcurr1 = *px; - - /* save g3(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K4, K8.... */ - /* Process first sample for 4th, 8th .. tap */ - /* f4(n) = f3(n) + K4 * g3(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* Process second sample for 4th, 8th .. tap */ - /* for sample 2 processing */ - fnext2 = fcurr2 + ((*pk) * gnext1); - /* Process third sample for 4th, 8th .. tap */ - fnext3 = fcurr3 + ((*pk) * gnext2); - /* Process fourth sample for 4th, 8th .. tap */ - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g4(n) = f3(n) * K4 + g3(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurr1 = *px; - - /* save g4(n) in state buffer */ - *px++ = gnext4; - - /* Sample processing for K5, K9.... */ - /* Process first sample for 5th, 9th .. tap */ - /* f5(n) = f4(n) + K5 * g4(n-1) */ - fcurr1 = fnext1 + ((*pk) * gcurr1); - /* Process second sample for 5th, 9th .. tap */ - fcurr2 = fnext2 + ((*pk) * gnext1); - /* Process third sample for 5th, 9th .. tap */ - fcurr3 = fnext3 + ((*pk) * gnext2); - /* Process fourth sample for 5th, 9th .. tap */ - fcurr4 = fnext4 + ((*pk) * gnext3); - - /* Calculation of state values for next stage */ - /* g5(n) = f4(n) * K5 + g4(n-1) */ - gnext4 = (fnext4 * (*pk)) + gnext3; - gnext3 = (fnext3 * (*pk)) + gnext2; - gnext2 = (fnext2 * (*pk)) + gnext1; - gnext1 = (fnext1 * (*pk++)) + gcurr1; - - stageCnt--; - } - - /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ - stageCnt = (numStages - 1u) % 0x4u; - - while(stageCnt > 0u) - { - gcurr1 = *px; - - /* save g value in state buffer */ - *px++ = gnext4; - - /* Process four samples for last three taps here */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - fnext2 = fcurr2 + ((*pk) * gnext1); - fnext3 = fcurr3 + ((*pk) * gnext2); - fnext4 = fcurr4 + ((*pk) * gnext3); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext4 = (fcurr4 * (*pk)) + gnext3; - gnext3 = (fcurr3 * (*pk)) + gnext2; - gnext2 = (fcurr2 * (*pk)) + gnext1; - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* Update of f values for next coefficient set processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - fcurr3 = fnext3; - fcurr4 = fnext4; - - stageCnt--; - - } - - /* The results in the 4 accumulators, store in the destination buffer. */ - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - *pDst++ = fcurr2; - *pDst++ = fcurr3; - *pDst++ = fcurr4; - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* save g1(n) in state buffer */ - *px++ = fcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = fcurr1 + ((*pk) * gcurr1); - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (fcurr1 * (*pk++)) + gcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - - blkCnt--; - - } - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t fcurr, fnext, gcurr, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize coeff pointer */ - pk = pCoeffs; - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurr = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = fcurr + ((*pk) * gcurr); - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - - /* save f0(n) in state buffer */ - *px++ = fcurr; - - /* f1(n) is saved in fcurr - for next stage processing */ - fcurr = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = fcurr + ((*pk) * gcurr); - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = (fcurr * (*pk++)) + gcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr; - - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c deleted file mode 100644 index a53ae92e2f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_f32.c +++ /dev/null @@ -1,78 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_f32.c -* -* Description: Floating-point FIR Lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - -/** - * @brief Initialization function for the floating-point FIR lattice filter. - * @param[in] *S points to an instance of the floating-point FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_f32( - arm_fir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pCoeffs, - float32_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c deleted file mode 100644 index 8db4985090..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q15.c +++ /dev/null @@ -1,78 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_q15.c -* -* Description: Q15 FIR Lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q15 FIR lattice filter. - * @param[in] *S points to an instance of the Q15 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_q15( - arm_fir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pCoeffs, - q15_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c deleted file mode 100644 index 035c5e056a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_init_q31.c +++ /dev/null @@ -1,78 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_init_q31.c -* -* Description: Q31 FIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q31 FIR lattice filter. - * @param[in] *S points to an instance of the Q31 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. - * @return none. - */ - -void arm_fir_lattice_init_q31( - arm_fir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pCoeffs, - q31_t * pState) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always numStages */ - memset(pState, 0, (numStages) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c deleted file mode 100644 index abfb33cf24..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q15.c +++ /dev/null @@ -1,531 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_q15.c -* -* Description: Q15 FIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - -/** - * @brief Processing function for the Q15 FIR lattice filter. - * @param[in] *S points to an instance of the Q15 FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_fir_lattice_q15( - const arm_fir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *px; /* temporary state pointer */ - q15_t *pk; /* temporary coefficient pointer */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t fcurnt1, fnext1, gcurnt1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ - q31_t fcurnt2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - q31_t fcurnt3, fnext3, gnext3; /* temporary variables for third sample in loop unrolling */ - q31_t fcurnt4, fnext4, gnext4; /* temporary variables for fourth sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Number of stages in the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - - /* Read two samples from input buffer */ - /* f0(n) = x(n) */ - fcurnt1 = *pSrc++; - fcurnt2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* Read g0(n-1) from state */ - gcurnt1 = *px; - - /* Process first sample for first tap */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Process second sample for first tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((fcurnt1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt1; - gnext2 = __SSAT(gnext2, 16); - - - /* Read next two samples from input buffer */ - /* f0(n+2) = x(n+2) */ - fcurnt3 = *pSrc++; - fcurnt4 = *pSrc++; - - /* Copy only last input samples into the state buffer - which is used for next four samples processing */ - *px++ = (q15_t) fcurnt4; - - /* Process third sample for first tap */ - fnext3 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt2; - gnext3 = __SSAT(gnext3, 16); - - /* Process fourth sample for first tap */ - fnext4 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - gnext4 = (q31_t) ((fcurnt4 * (*pk++)) >> 15u) + fcurnt3; - gnext4 = __SSAT(gnext4, 16); - - /* Update of f values for next coefficient set processing */ - fcurnt1 = fnext1; - fcurnt2 = fnext2; - fcurnt3 = fnext3; - fcurnt4 = fnext4; - - - /* Loop unrolling. Process 4 taps at a time . */ - stageCnt = (numStages - 1u) >> 2; - - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numStages-3 coefficients. */ - - /* Process 2nd, 3rd, 4th and 5th taps ... here */ - while(stageCnt > 0u) - { - /* Read g1(n-1), g3(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Process first sample for 2nd, 6th .. tap */ - /* Sample processing for K2, K6.... */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - - /* Process second sample for 2nd, 6th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - /* Process third sample for 2nd, 6th .. tap */ - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - /* Process fourth sample for 2nd, 6th .. tap */ - /* fnext4 = fcurnt4 + (*pk) * gnext3; */ - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K3, K7.... */ - /* Process first sample for 3rd, 7th .. tap */ - /* f3(n) = f2(n) + K3 * g2(n-1) */ - fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; - fcurnt1 = __SSAT(fcurnt1, 16); - - /* Process second sample for 3rd, 7th .. tap */ - fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; - fcurnt2 = __SSAT(fcurnt2, 16); - - /* Process third sample for 3rd, 7th .. tap */ - fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; - fcurnt3 = __SSAT(fcurnt3, 16); - - /* Process fourth sample for 3rd, 7th .. tap */ - fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; - fcurnt4 = __SSAT(fcurnt4, 16); - - /* Calculation of state values for next stage */ - /* g3(n) = f2(n) * K3 + g2(n-1) */ - gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - - gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - - gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Read g1(n-1), g3(n-1) .... from state */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K4, K8.... */ - /* Process first sample for 4th, 8th .. tap */ - /* f4(n) = f3(n) + K4 * g3(n-1) */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* Process second sample for 4th, 8th .. tap */ - /* for sample 2 processing */ - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - /* Process third sample for 4th, 8th .. tap */ - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - - /* Process fourth sample for 4th, 8th .. tap */ - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g4(n) = f3(n) * K4 + g3(n-1) */ - /* Calculation of state values for next stage */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* Read g2(n-1), g4(n-1) .... from state */ - gcurnt1 = *px; - - /* save g4(n) in state buffer */ - *px++ = (q15_t) gnext4; - - /* Sample processing for K5, K9.... */ - /* Process first sample for 5th, 9th .. tap */ - /* f5(n) = f4(n) + K5 * g4(n-1) */ - fcurnt1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fnext1; - fcurnt1 = __SSAT(fcurnt1, 16); - - /* Process second sample for 5th, 9th .. tap */ - fcurnt2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fnext2; - fcurnt2 = __SSAT(fcurnt2, 16); - - /* Process third sample for 5th, 9th .. tap */ - fcurnt3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fnext3; - fcurnt3 = __SSAT(fcurnt3, 16); - - /* Process fourth sample for 5th, 9th .. tap */ - fcurnt4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fnext4; - fcurnt4 = __SSAT(fcurnt4, 16); - - /* Calculation of state values for next stage */ - /* g5(n) = f4(n) * K5 + g4(n-1) */ - gnext4 = (q31_t) ((fnext4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fnext3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - gnext2 = (q31_t) ((fnext2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fnext1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - stageCnt--; - } - - /* If the (filter length -1) is not a multiple of 4, compute the remaining filter taps */ - stageCnt = (numStages - 1u) % 0x4u; - - while(stageCnt > 0u) - { - gcurnt1 = *px; - - /* save g value in state buffer */ - *px++ = (q15_t) gnext4; - - /* Process four samples for last three taps here */ - fnext1 = (q31_t) ((gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - fnext2 = (q31_t) ((gnext1 * (*pk)) >> 15u) + fcurnt2; - fnext2 = __SSAT(fnext2, 16); - - fnext3 = (q31_t) ((gnext2 * (*pk)) >> 15u) + fcurnt3; - fnext3 = __SSAT(fnext3, 16); - - fnext4 = (q31_t) ((gnext3 * (*pk)) >> 15u) + fcurnt4; - fnext4 = __SSAT(fnext4, 16); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext4 = (q31_t) ((fcurnt4 * (*pk)) >> 15u) + gnext3; - gnext4 = __SSAT(gnext4, 16); - gnext3 = (q31_t) ((fcurnt3 * (*pk)) >> 15u) + gnext2; - gnext3 = __SSAT(gnext3, 16); - gnext2 = (q31_t) ((fcurnt2 * (*pk)) >> 15u) + gnext1; - gnext2 = __SSAT(gnext2, 16); - gnext1 = (q31_t) ((fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* Update of f values for next coefficient set processing */ - fcurnt1 = fnext1; - fcurnt2 = fnext2; - fcurnt3 = fnext3; - fcurnt4 = fnext4; - - stageCnt--; - - } - - /* The results in the 4 accumulators, store in the destination buffer. */ - /* y(n) = fN(n) */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = __PKHBT(fcurnt1, fcurnt2, 16); - *__SIMD32(pDst)++ = __PKHBT(fcurnt3, fcurnt4, 16); - -#else - - *__SIMD32(pDst)++ = __PKHBT(fcurnt2, fcurnt1, 16); - *__SIMD32(pDst)++ = __PKHBT(fcurnt4, fcurnt3, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurnt1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g2(n) from state buffer */ - gcurnt1 = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - /* save g1(n) in state buffer */ - *px++ = (q15_t) fcurnt1; - - /* f1(n) is saved in fcurnt1 - for next stage processing */ - fcurnt1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurnt1 = *px; - - /* save g1(n) in state buffer */ - *px++ = (q15_t) gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (((q31_t) gcurnt1 * (*pk)) >> 15u) + fcurnt1; - fnext1 = __SSAT(fnext1, 16); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (((q31_t) fcurnt1 * (*pk++)) >> 15u) + gcurnt1; - gnext1 = __SSAT(gnext1, 16); - - - /* f1(n) is saved in fcurnt1 - for next stage processing */ - fcurnt1 = fnext1; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = __SSAT(fcurnt1, 16); - - - blkCnt--; - - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t fcurnt, fnext, gcurnt, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurnt = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurnt = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; - fnext = __SSAT(fnext, 16); - - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; - gnext = __SSAT(gnext, 16); - - /* save f0(n) in state buffer */ - *px++ = (q15_t) fcurnt; - - /* f1(n) is saved in fcurnt - for next stage processing */ - fcurnt = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g1(n-1) from state buffer */ - gcurnt = *px; - - /* save g0(n-1) in state buffer */ - *px++ = (q15_t) gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = ((gcurnt * (*pk)) >> 15u) + fcurnt; - fnext = __SSAT(fnext, 16); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = ((fcurnt * (*pk++)) >> 15u) + gcurnt; - gnext = __SSAT(gnext, 16); - - - /* f1(n) is saved in fcurnt - for next stage processing */ - fcurnt = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = __SSAT(fcurnt, 16); - - - blkCnt--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c deleted file mode 100644 index 9fb46459dc..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_lattice_q31.c +++ /dev/null @@ -1,348 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_lattice_q31.c -* -* Description: Q31 FIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Lattice - * @{ - */ - - -/** - * @brief Processing function for the Q31 FIR lattice filter. - * @param[in] *S points to an instance of the Q31 FIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * In order to avoid overflows the input signal must be scaled down by 2*log2(numStages) bits. - */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_fir_lattice_q31( - const arm_fir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *px; /* temporary state pointer */ - q31_t *pk; /* temporary coefficient pointer */ - q31_t fcurr1, fnext1, gcurr1 = 0, gnext1; /* temporary variables for first sample in loop unrolling */ - q31_t fcurr2, fnext2, gnext2; /* temporary variables for second sample in loop unrolling */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - q31_t k; - - pState = &S->pState[0]; - - blkCnt = blockSize >> 1u; - - /* First part of the processing with loop unrolling. Compute 2 outputs at a time. - a second loop below computes the remaining 1 sample. */ - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - - /* f0(n) = x(n) */ - fcurr2 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n - 1) from state buffer */ - gcurr1 = *px; - - /* Read the reflection coefficient */ - k = *pk++; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * k) >> 32); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (k)) >> 32); - fnext1 = fcurr1 + (fnext1 << 1u); - gnext1 = gcurr1 + (gnext1 << 1u); - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext2 = (q31_t) (((q63_t) fcurr1 * k) >> 32); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext2 = (q31_t) (((q63_t) fcurr2 * (k)) >> 32); - fnext2 = fcurr2 + (fnext2 << 1u); - gnext2 = fcurr1 + (gnext2 << 1u); - - /* save g1(n) in state buffer */ - *px++ = fcurr2; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - - /* Read the reflection coefficient */ - k = *pk++; - - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext2; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * k) >> 32); - fnext2 = (q31_t) (((q63_t) gnext1 * k) >> 32); - - fnext1 = fcurr1 + (fnext1 << 1u); - fnext2 = fcurr2 + (fnext2 << 1u); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext2 = (q31_t) (((q63_t) fcurr2 * (k)) >> 32); - gnext2 = gnext1 + (gnext2 << 1u); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (k)) >> 32); - gnext1 = gcurr1 + (gnext1 << 1u); - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - fcurr2 = fnext2; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - *pDst++ = fcurr2; - - blkCnt--; - - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x2u; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr1 = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n - 1) from state buffer */ - gcurr1 = *px; - - /* Read the reflection coefficient */ - k = *pk++; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * k) >> 32); - fnext1 = fcurr1 + (fnext1 << 1u); - - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (k)) >> 32); - gnext1 = gcurr1 + (gnext1 << 1u); - - /* save g1(n) in state buffer */ - *px++ = fcurr1; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* Read the reflection coefficient */ - k = *pk++; - - /* read g2(n) from state buffer */ - gcurr1 = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext1; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext1 = (q31_t) (((q63_t) gcurr1 * k) >> 32); - fnext1 = fcurr1 + (fnext1 << 1u); - - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext1 = (q31_t) (((q63_t) fcurr1 * (k)) >> 32); - gnext1 = gcurr1 + (gnext1 << 1u); - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr1 = fnext1; - - stageCnt--; - - } - - - /* y(n) = fN(n) */ - *pDst++ = fcurr1; - - blkCnt--; - - } - - -} - - -#else - -/* Run the below code for Cortex-M0 */ - -void arm_fir_lattice_q31( - const arm_fir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *px; /* temporary state pointer */ - q31_t *pk; /* temporary coefficient pointer */ - q31_t fcurr, fnext, gcurr, gnext; /* temporary variables */ - uint32_t numStages = S->numStages; /* Length of the filter */ - uint32_t blkCnt, stageCnt; /* temporary variables for counts */ - - pState = &S->pState[0]; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* f0(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize coeff pointer */ - pk = (pCoeffs); - - /* Initialize state pointer */ - px = pState; - - /* read g0(n-1) from state buffer */ - gcurr = *px; - - /* for sample 1 processing */ - /* f1(n) = f0(n) + K1 * g0(n-1) */ - fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; - /* g1(n) = f0(n) * K1 + g0(n-1) */ - gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; - /* save g1(n) in state buffer */ - *px++ = fcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt = (numStages - 1u); - - /* stage loop */ - while(stageCnt > 0u) - { - /* read g2(n) from state buffer */ - gcurr = *px; - - /* save g1(n) in state buffer */ - *px++ = gnext; - - /* Sample processing for K2, K3.... */ - /* f2(n) = f1(n) + K2 * g1(n-1) */ - fnext = (q31_t) (((q63_t) gcurr * (*pk)) >> 31) + fcurr; - /* g2(n) = f1(n) * K2 + g1(n-1) */ - gnext = (q31_t) (((q63_t) fcurr * (*pk++)) >> 31) + gcurr; - - /* f1(n) is saved in fcurr1 - for next stage processing */ - fcurr = fnext; - - stageCnt--; - - } - - /* y(n) = fN(n) */ - *pDst++ = fcurr; - - blkCnt--; - - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - -/** - * @} end of FIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c deleted file mode 100644 index 368014f435..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q15.c +++ /dev/null @@ -1,689 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q15.c -* -* Description: Q15 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @brief Processing function for the Q15 FIR filter. - * @param[in] *S points to an instance of the Q15 FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * - * \par Restrictions - * If the silicon does not support unaligned memory access enable the macro UNALIGNED_SUPPORT_DISABLE - * In this case input, output, state buffers should be aligned by 32-bit - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * Refer to the function arm_fir_fast_q15() for a faster but less precise implementation of this function. - */ - -#ifndef ARM_MATH_CM0 - -/* Run the below code for Cortex-M4 and Cortex-M3 */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - -void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px1; /* Temporary q15 pointer for state buffer */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t x0, x1, x2, x3, c0; /* Temporary variables to hold SIMD state and coefficient values */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer. - ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pSrc)++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer of type q15 */ - px1 = pState; - - /* Initialize coeff pointer of type q31 */ - pb = pCoeffs; - - /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ - x0 = _SIMD32_OFFSET(px1); - - /* Read the third and forth samples from the state buffer: x[n-N-1], x[n-N-2] */ - x1 = _SIMD32_OFFSET(px1 + 1u); - - px1 += 2u; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-4 coefficients. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - acc0 = __SMLALD(x0, c0, acc0); - - /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ - acc1 = __SMLALD(x1, c0, acc1); - - /* Read state x[n-N-2], x[n-N-3] */ - x2 = _SIMD32_OFFSET(px1); - - /* Read state x[n-N-3], x[n-N-4] */ - x3 = _SIMD32_OFFSET(px1 + 1u); - - /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ - acc2 = __SMLALD(x2, c0, acc2); - - /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ - acc3 = __SMLALD(x3, c0, acc3); - - /* Read coefficients b[N-2], b[N-3] */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ - acc0 = __SMLALD(x2, c0, acc0); - - /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ - acc1 = __SMLALD(x3, c0, acc1); - - /* Read state x[n-N-4], x[n-N-5] */ - x0 = _SIMD32_OFFSET(px1 + 2u); - - /* Read state x[n-N-5], x[n-N-6] */ - x1 = _SIMD32_OFFSET(px1 + 3u); - - /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ - acc2 = __SMLALD(x0, c0, acc2); - - /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ - acc3 = __SMLALD(x1, c0, acc3); - - px1 += 4u; - - tapCnt--; - - } - - - /* If the filter length is not a multiple of 4, compute the remaining filter taps. - ** This is always be 2 taps since the filter length is even. */ - if((numTaps & 0x3u) != 0u) - { - /* Read 2 coefficients */ - c0 = *__SIMD32(pb)++; - - /* Fetch 4 state variables */ - x2 = _SIMD32_OFFSET(px1); - - x3 = _SIMD32_OFFSET(px1 + 1u); - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - - px1 += 2u; - - acc1 = __SMLALD(x1, c0, acc1); - acc2 = __SMLALD(x2, c0, acc2); - acc3 = __SMLALD(x3, c0, acc3); - } - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. - ** Then store the 4 outputs in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - while(blkCnt > 0u) - { - /* Copy two samples into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer of type q15 */ - px1 = pState; - - /* Initialize coeff pointer of type q31 */ - pb = pCoeffs; - - tapCnt = numTaps >> 1; - - do - { - - c0 = *__SIMD32(pb)++; - x0 = *__SIMD32(px1)++; - - acc0 = __SMLALD(x0, c0, acc0); - tapCnt--; - } - while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - - /* Copy state values to start of state buffer */ - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy remaining data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - -#else /* UNALIGNED_SUPPORT_DISABLE */ - -void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q63_t acc0, acc1, acc2, acc3; /* Accumulators */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - q15_t *px; /* Temporary q31 pointer for SIMD state buffer accesses */ - q31_t x0, x1, x2, c0; /* Temporary variables to hold SIMD state and coefficient values */ - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer. - ** Use 32-bit SIMD to move the 16-bit data. Only requires two copies. */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Typecast q15_t pointer to q31_t pointer for state reading in q31_t */ - px = pState; - - /* Typecast q15_t pointer to q31_t pointer for coefficient reading in q31_t */ - pb = pCoeffs; - - /* Read the first two samples from the state buffer: x[n-N], x[n-N-1] */ - x0 = *__SIMD32(px)++; - - /* Read the third and forth samples from the state buffer: x[n-N-2], x[n-N-3] */ - x2 = *__SIMD32(px)++; - - /* Loop over the number of taps. Unroll by a factor of 4. - ** Repeat until we've computed numTaps-(numTaps%4) coefficients. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0) - { - /* Read the first two coefficients using SIMD: b[N] and b[N-1] coefficients */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - acc0 = __SMLALD(x0, c0, acc0); - - /* acc2 += b[N] * x[n-N-2] + b[N-1] * x[n-N-3] */ - acc2 = __SMLALD(x2, c0, acc2); - - /* pack x[n-N-1] and x[n-N-2] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* Read state x[n-N-4], x[n-N-5] */ - x0 = _SIMD32_OFFSET(px); - - /* acc1 += b[N] * x[n-N-1] + b[N-1] * x[n-N-2] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* pack x[n-N-3] and x[n-N-4] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x0, x2, 0); -#else - x1 = __PKHBT(x2, x0, 0); -#endif - - /* acc3 += b[N] * x[n-N-3] + b[N-1] * x[n-N-4] */ - acc3 = __SMLALDX(x1, c0, acc3); - - /* Read coefficients b[N-2], b[N-3] */ - c0 = *__SIMD32(pb)++; - - /* acc0 += b[N-2] * x[n-N-2] + b[N-3] * x[n-N-3] */ - acc0 = __SMLALD(x2, c0, acc0); - - /* Read state x[n-N-6], x[n-N-7] with offset */ - x2 = _SIMD32_OFFSET(px + 2u); - - /* acc2 += b[N-2] * x[n-N-4] + b[N-3] * x[n-N-5] */ - acc2 = __SMLALD(x0, c0, acc2); - - /* acc1 += b[N-2] * x[n-N-3] + b[N-3] * x[n-N-4] */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* pack x[n-N-5] and x[n-N-6] */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* acc3 += b[N-2] * x[n-N-5] + b[N-3] * x[n-N-6] */ - acc3 = __SMLALDX(x1, c0, acc3); - - /* Update state pointer for next state reading */ - px += 4u; - - /* Decrement tap count */ - tapCnt--; - - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps. - ** This is always be 2 taps since the filter length is even. */ - if((numTaps & 0x3u) != 0u) - { - - /* Read last two coefficients */ - c0 = *__SIMD32(pb)++; - - /* Perform the multiply-accumulates */ - acc0 = __SMLALD(x0, c0, acc0); - acc2 = __SMLALD(x2, c0, acc2); - - /* pack state variables */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x2, x0, 0); -#else - x1 = __PKHBT(x0, x2, 0); -#endif - - /* Read last state variables */ - x0 = *__SIMD32(px); - - /* Perform the multiply-accumulates */ - acc1 = __SMLALDX(x1, c0, acc1); - - /* pack state variables */ -#ifndef ARM_MATH_BIG_ENDIAN - x1 = __PKHBT(x0, x2, 0); -#else - x1 = __PKHBT(x2, x0, 0); -#endif - - /* Perform the multiply-accumulates */ - acc3 = __SMLALDX(x1, c0, acc3); - } - - /* The results in the 4 accumulators are in 2.30 format. Convert to 1.15 with saturation. - ** Then store the 4 outputs in the destination buffer. */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc0 >> 15), 16), __SSAT((acc1 >> 15), 16), 16); - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc2 >> 15), 16), __SSAT((acc3 >> 15), 16), 16); - -#else - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc1 >> 15), 16), __SSAT((acc0 >> 15), 16), 16); - - *__SIMD32(pDst)++ = - __PKHBT(__SSAT((acc3 >> 15), 16), __SSAT((acc2 >> 15), 16), 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - while(blkCnt > 0u) - { - /* Copy two samples into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Use SIMD to hold states and coefficients */ - px = pState; - pb = pCoeffs; - - tapCnt = numTaps >> 1u; - - do - { - acc0 += (q31_t) * px++ * *pb++; - acc0 += (q31_t) * px++ * *pb++; - tapCnt--; - } - while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 with saturation. - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) (__SSAT((acc0 >> 15), 16)); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy remaining data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#else /* ARM_MATH_CM0 */ - - -/* Run the below code for Cortex-M0 */ - -void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - - - - q15_t *px; /* Temporary pointer for state buffer */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Number of nTaps in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - tapCnt = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q31_t) * px++ * *pb++; - tapCnt--; - } while(tapCnt > 0u); - - /* The result is in 2.30 format. Convert to 1.15 - ** Then store the output in the destination buffer. */ - *pDst++ = (q15_t) __SSAT((acc >> 15u), 16); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = (numTaps - 1u); - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - - - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c deleted file mode 100644 index b3b84ec51f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q31.c +++ /dev/null @@ -1,363 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q31.c -* -* Description: Q31 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q31 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by log2(numTaps) bits. - * After all multiply-accumulates are performed, the 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * Refer to the function arm_fir_fast_q31() for a faster but less precise implementation of this filter for Cortex-M3 and Cortex-M4. - */ - -void arm_fir_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t x0, x1, x2; /* Temporary variables to hold state */ - q31_t c0; /* Temporary variable to hold coefficient value */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc0, acc1, acc2; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt, tapCntN3; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize / 3; - blockSize = blockSize - (3 * blkCnt); - - tapCnt = numTaps / 3; - tapCntN3 = numTaps - (3 * tapCnt); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy three new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first two samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1] */ - x0 = *(px++); - x1 = *(px++); - - /* Loop unrolling. Process 3 taps at a time. */ - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *pb; - - /* Read x[n-numTaps-2] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x0 * c0); - acc1 += ((q63_t) x1 * c0); - acc2 += ((q63_t) x2 * c0); - - /* Read the coefficient and state */ - c0 = *(pb + 1u); - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x1 * c0); - acc1 += ((q63_t) x2 * c0); - acc2 += ((q63_t) x0 * c0); - - /* Read the coefficient and state */ - c0 = *(pb + 2u); - x1 = *(px++); - - /* update coefficient pointer */ - pb += 3u; - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x2 * c0); - acc1 += ((q63_t) x0 * c0); - acc2 += ((q63_t) x1 * c0); - - /* Decrement the loop counter */ - i--; - } - - /* If the filter length is not a multiple of 3, compute the remaining filter taps */ - - i = tapCntN3; - - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q63_t) x0 * c0); - acc1 += ((q63_t) x1 * c0); - acc2 += ((q63_t) x2 * c0); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 3 to process the next group of 3 samples */ - pState = pState + 3; - - /* The results in the 3 accumulators are in 2.30 format. Convert to 1.31 - ** Then store the 3 outputs in the destination buffer. */ - *pDst++ = (q31_t) (acc0 >> 31u); - *pDst++ = (q31_t) (acc1 >> 31u); - *pDst++ = (q31_t) (acc2 >> 31u); - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 3, compute any remaining output samples here. - ** No loop unrolling is used. */ - - while(blockSize > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += (q63_t) * (px++) * (*(pb++)); - i--; - } while(i > 0u); - - /* The result is in 2.62 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc0 >> 31u); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blockSize--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - q63_t acc; /* Accumulator */ - uint32_t numTaps = S->numTaps; /* Length of the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState buffer contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = pCoeffs; - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q63_t) * px++ * *pb++; - i--; - } while(i > 0u); - - /* The result is in 2.62 format. Convert to 1.31 - ** Then store the output in the destination buffer. */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the starting of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - /* Copy numTaps number of values */ - tapCnt = numTaps - 1u; - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c deleted file mode 100644 index 624afa130a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_q7.c +++ /dev/null @@ -1,388 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_q7.c -* -* Description: Q7 FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR - * @{ - */ - -/** - * @param[in] *S points to an instance of the Q7 FIR filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is converted to 18.7 format by discarding the low 7 bits. - * Finally, the result is truncated to 1.7 format. - */ - -void arm_fir_q7( - const arm_fir_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *pStateCurnt; /* Points to the current sample of the state */ - q7_t x0, x1, x2, x3; /* Temporary variables to hold state */ - q7_t c0; /* Temporary variable to hold coefficient value */ - q7_t *px; /* Temporary pointer for state */ - q7_t *pb; /* Temporary pointer for coefficient buffer */ - q31_t acc0, acc1, acc2, acc3; /* Accumulators */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t i, tapCnt, blkCnt; /* Loop counters */ - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Apply loop unrolling and compute 4 output values simultaneously. - * The variables acc0 ... acc3 hold output values that are being computed: - * - * acc0 = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] - * acc1 = b[numTaps-1] * x[n-numTaps] + b[numTaps-2] * x[n-numTaps-1] + b[numTaps-3] * x[n-numTaps-2] +...+ b[0] * x[1] - * acc2 = b[numTaps-1] * x[n-numTaps+1] + b[numTaps-2] * x[n-numTaps] + b[numTaps-3] * x[n-numTaps-1] +...+ b[0] * x[2] - * acc3 = b[numTaps-1] * x[n-numTaps+2] + b[numTaps-2] * x[n-numTaps+1] + b[numTaps-3] * x[n-numTaps] +...+ b[0] * x[3] - */ - blkCnt = blockSize >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Copy four new input samples into the state buffer */ - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - *pStateCurnt++ = *pSrc++; - - /* Set all accumulators to zero */ - acc0 = 0; - acc1 = 0; - acc2 = 0; - acc3 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Read the first three samples from the state buffer: - * x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2] */ - x0 = *(px++); - x1 = *(px++); - x2 = *(px++); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - i = tapCnt; - - while(i > 0u) - { - /* Read the b[numTaps] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-3] sample */ - x3 = *(px++); - - /* acc0 += b[numTaps] * x[n-numTaps] */ - acc0 += ((q15_t) x0 * c0); - - /* acc1 += b[numTaps] * x[n-numTaps-1] */ - acc1 += ((q15_t) x1 * c0); - - /* acc2 += b[numTaps] * x[n-numTaps-2] */ - acc2 += ((q15_t) x2 * c0); - - /* acc3 += b[numTaps] * x[n-numTaps-3] */ - acc3 += ((q15_t) x3 * c0); - - /* Read the b[numTaps-1] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-4] sample */ - x0 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x1 * c0); - acc1 += ((q15_t) x2 * c0); - acc2 += ((q15_t) x3 * c0); - acc3 += ((q15_t) x0 * c0); - - /* Read the b[numTaps-2] coefficient */ - c0 = *(pb++); - - /* Read x[n-numTaps-5] sample */ - x1 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x2 * c0); - acc1 += ((q15_t) x3 * c0); - acc2 += ((q15_t) x0 * c0); - acc3 += ((q15_t) x1 * c0); - /* Read the b[numTaps-3] coefficients */ - c0 = *(pb++); - - /* Read x[n-numTaps-6] sample */ - x2 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x3 * c0); - acc1 += ((q15_t) x0 * c0); - acc2 += ((q15_t) x1 * c0); - acc3 += ((q15_t) x2 * c0); - i--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - - i = numTaps - (tapCnt * 4u); - while(i > 0u) - { - /* Read coefficients */ - c0 = *(pb++); - - /* Fetch 1 state variable */ - x3 = *(px++); - - /* Perform the multiply-accumulates */ - acc0 += ((q15_t) x0 * c0); - acc1 += ((q15_t) x1 * c0); - acc2 += ((q15_t) x2 * c0); - acc3 += ((q15_t) x3 * c0); - - /* Reuse the present sample states for next sample */ - x0 = x1; - x1 = x2; - x2 = x3; - - /* Decrement the loop counter */ - i--; - } - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 4; - - /* The results in the 4 accumulators are in 2.62 format. Convert to 1.31 - ** Then store the 4 outputs in the destination buffer. */ - acc0 = __SSAT((acc0 >> 7u), 8); - *pDst++ = acc0; - acc1 = __SSAT((acc1 >> 7u), 8); - *pDst++ = acc1; - acc2 = __SSAT((acc2 >> 7u), 8); - *pDst++ = acc2; - acc3 = __SSAT((acc3 >> 7u), 8); - *pDst++ = acc3; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 4u; - - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set the accumulator to zero */ - acc0 = 0; - - /* Initialize state pointer */ - px = pState; - - /* Initialize Coefficient pointer */ - pb = (pCoeffs); - - i = numTaps; - - /* Perform the multiply-accumulates */ - do - { - acc0 += (q15_t) * (px++) * (*(pb++)); - i--; - } while(i > 0u); - - /* The result is in 2.14 format. Convert to 1.7 - ** Then store the output in the destination buffer. */ - *pDst++ = __SSAT((acc0 >> 7u), 8); - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the samples loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - uint32_t numTaps = S->numTaps; /* Number of taps in the filter */ - uint32_t i, blkCnt; /* Loop counters */ - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *px, *pb; /* Temporary pointers to state and coeff */ - q31_t acc = 0; /* Accumlator */ - q7_t *pStateCurnt; /* Points to the current sample of the state */ - - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = S->pState + (numTaps - 1u); - - /* Initialize blkCnt with blockSize */ - blkCnt = blockSize; - - /* Perform filtering upto BlockSize - BlockSize%4 */ - while(blkCnt > 0u) - { - /* Copy one sample at a time into state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Set accumulator to zero */ - acc = 0; - - /* Initialize state pointer of type q7 */ - px = pState; - - /* Initialize coeff pointer of type q7 */ - pb = pCoeffs; - - - i = numTaps; - - while(i > 0u) - { - /* acc = b[numTaps-1] * x[n-numTaps-1] + b[numTaps-2] * x[n-numTaps-2] + b[numTaps-3] * x[n-numTaps-3] +...+ b[0] * x[0] */ - acc += (q15_t) * px++ * *pb++; - i--; - } - - /* Store the 1.7 format filter output in destination buffer */ - *pDst++ = (q7_t) __SSAT((acc >> 7), 8); - - /* Advance the state pointer by 1 to process the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. - ** Now copy the last numTaps - 1 samples to the satrt of the state buffer. - ** This prepares the state buffer for the next function call. */ - - - /* Points to the start of the state buffer */ - pStateCurnt = S->pState; - - - /* Copy numTaps number of values */ - i = (numTaps - 1u); - - /* Copy q7_t data */ - while(i > 0u) - { - *pStateCurnt++ = *pState++; - i--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c deleted file mode 100644 index e969d5c842..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_f32.c +++ /dev/null @@ -1,365 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_f32.c -* -* Description: Floating-point sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup FIR_Sparse Finite Impulse Response (FIR) Sparse Filters - * - * This group of functions implements sparse FIR filters. - * Sparse FIR filters are equivalent to standard FIR filters except that most of the coefficients are equal to zero. - * Sparse filters are used for simulating reflections in communications and audio applications. - * - * There are separate functions for Q7, Q15, Q31, and floating-point data types. - * The functions operate on blocks of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst points to input and output arrays respectively containing blockSize values. - * - * \par Algorithm: - * The sparse filter instant structure contains an array of tap indices pTapDelay which specifies the locations of the non-zero coefficients. - * This is in addition to the coefficient array b. - * The implementation essentially skips the multiplications by zero and leads to an efficient realization. - *
   
- *     y[n] = b[0] * x[n-pTapDelay[0]] + b[1] * x[n-pTapDelay[1]] + b[2] * x[n-pTapDelay[2]] + ...+ b[numTaps-1] * x[n-pTapDelay[numTaps-1]]    
- * 
- * \par - * \image html FIRSparse.gif "Sparse FIR filter. b[n] represents the filter coefficients" - * \par - * pCoeffs points to a coefficient array of size numTaps; - * pTapDelay points to an array of nonzero indices and is also of size numTaps; - * pState points to a state array of size maxDelay + blockSize, where - * maxDelay is the largest offset value that is ever used in the pTapDelay array. - * Some of the processing functions also require temporary working buffers. - * - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient and offset arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 4 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 4 different data type filter instance structures - *
    
- *arm_fir_sparse_instance_f32 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};    
- *arm_fir_sparse_instance_q31 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};    
- *arm_fir_sparse_instance_q15 S = {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};    
- *arm_fir_sparse_instance_q7 S =  {numTaps, 0, pState, pCoeffs, maxDelay, pTapDelay};    
- * 
- * \par - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the sparse FIR filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the floating-point sparse FIR filter. - * @param[in] *S points to an instance of the floating-point sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - */ - -void arm_fir_sparse_f32( - arm_fir_sparse_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - float32_t * pScratchIn, - uint32_t blockSize) -{ - - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *px; /* Scratch buffer pointer */ - float32_t *py = pState; /* Temporary pointers for state buffer */ - float32_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - float32_t *pOut; /* Destination pointer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - float32_t coeff = *pCoeffs++; /* Read the first coefficient value */ - - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, - (int32_t *) pSrc, 1, blockSize); - - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 Multiplications at a time. */ - blkCnt = blockSize >> 2u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - -#else - -/* Run the below code for Cortex-M0 */ - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in destination buffer */ - *pOut++ = *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer */ - px = pb; - - /* Working pointer for destination buffer */ - pOut = pDst; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pOut++ += *px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = - ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c deleted file mode 100644 index 2934352d05..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_f32.c +++ /dev/null @@ -1,102 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_f32.c -* -* Description: Floating-point sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the floating-point sparse FIR filter. - * @param[in,out] *S points to an instance of the floating-point sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of samples processed by the arm_fir_sparse_f32() function. - */ - -void arm_fir_sparse_init_f32( - arm_fir_sparse_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c deleted file mode 100644 index 47a116e952..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q15.c +++ /dev/null @@ -1,102 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q15.c -* -* Description: Q15 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q15 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q15 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of words processed by arm_fir_sparse_q15() function. - */ - -void arm_fir_sparse_init_q15( - arm_fir_sparse_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c deleted file mode 100644 index 360a219b20..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q31.c +++ /dev/null @@ -1,101 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q31.c -* -* Description: Q31 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q31 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q31 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the number of words processed by arm_fir_sparse_q31() function. - */ - -void arm_fir_sparse_init_q31( - arm_fir_sparse_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c deleted file mode 100644 index b400297ca6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_init_q7.c +++ /dev/null @@ -1,102 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_init_q7.c -* -* Description: Q7 sparse FIR filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Initialization function for the Q7 sparse FIR filter. - * @param[in,out] *S points to an instance of the Q7 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] *pCoeffs points to the array of filter coefficients. - * @param[in] *pState points to the state buffer. - * @param[in] *pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - * @return none - * - * Description: - * \par - * pCoeffs holds the filter coefficients and has length numTaps. - * pState holds the filter's state variables and must be of length - * maxDelay + blockSize, where maxDelay - * is the maximum number of delay line values. - * blockSize is the - * number of samples processed by the arm_fir_sparse_q7() function. - */ - -void arm_fir_sparse_init_q7( - arm_fir_sparse_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Assign TapDelay pointer */ - S->pTapDelay = pTapDelay; - - /* Assign MaxDelay */ - S->maxDelay = maxDelay; - - /* reset the stateIndex to 0 */ - S->stateIndex = 0u; - - /* Clear state buffer and size is always maxDelay + blockSize */ - memset(pState, 0, (maxDelay + blockSize) * sizeof(q7_t)); - - /* Assign state pointer */ - S->pState = pState; - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c deleted file mode 100644 index 016f833456..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q15.c +++ /dev/null @@ -1,406 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q15.c -* -* Description: Q15 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the Q15 sparse FIR filter. - * @param[in] *S points to an instance of the Q15 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] *pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The 1.15 x 1.15 multiplications yield a 2.30 result and these are added to a 2.30 accumulator. - * Thus the full precision of the multiplications is maintained but there is only a single guard bit in the accumulator. - * If the accumulator result overflows it will wrap around rather than saturate. - * After all multiply-accumulates are performed, the 2.30 accumulator is truncated to 2.15 format and then saturated to 1.15 format. - * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. - */ - - -void arm_fir_sparse_q15( - arm_fir_sparse_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - q15_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize) -{ - - q15_t *pState = S->pState; /* State pointer */ - q15_t *pIn = pSrc; /* Working pointer for input */ - q15_t *pOut = pDst; /* Working pointer for output */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *px; /* Temporary pointers for scratch buffer */ - q15_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q15_t *py = pState; /* Temporary pointers for state buffer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q15_t coeff = *pCoeffs++; /* Read the first coefficient value */ - q31_t *pScr2 = pScratchOut; /* Working pointer for pScratchOut */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in1, in2; /* Temporary variables */ - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in1 = *pScr2++; - in2 = *pScr2++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), - 16); - -#else - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), - 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - in1 = *pScr2++; - - in2 = *pScr2++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in1 >> 15, 16), (q15_t) __SSAT(in2 >> 15, 16), - 16); - -#else - - *__SIMD32(pOut)++ = - __PKHBT((q15_t) __SSAT(in2 >> 15, 16), (q15_t) __SSAT(in1 >> 15, 16), - 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - - blkCnt--; - - } - - /* If the blockSize is not a multiple of 4, - remaining samples are processed in the below loop */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q15(py, delaySize, &S->stateIndex, 1, pIn, 1, blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q15(py, delaySize, &readIndex, 1, - pb, pb, blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - *pScratchOut++ += (q31_t) * px++ * coeff; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - *pOut++ = (q15_t) __SSAT(*pScr2++ >> 15, 16); - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c deleted file mode 100644 index 3d2f6d4028..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q31.c +++ /dev/null @@ -1,370 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q31.c -* -* Description: Q31 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @addtogroup FIR_Sparse - * @{ - */ - -/** - * @brief Processing function for the Q31 sparse FIR filter. - * @param[in] *S points to an instance of the Q31 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The 1.31 x 1.31 multiplications are truncated to 2.30 format. - * This leads to loss of precision on the intermediate multiplications and provides only a single guard bit. - * If the accumulator result overflows, it wraps around rather than saturate. - * In order to avoid overflows the input signal or coefficients must be scaled down by log2(numTaps) bits. - */ - -void arm_fir_sparse_q31( - arm_fir_sparse_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - q31_t * pScratchIn, - uint32_t blockSize) -{ - - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *px; /* Scratch buffer pointer */ - q31_t *py = pState; /* Temporary pointers for state buffer */ - q31_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q31_t *pOut; /* Destination pointer */ - q63_t out; /* Temporary output variable */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q31_t coeff = *pCoeffs++; /* Read the first coefficient value */ - q31_t in; - - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_f32((int32_t *) py, delaySize, &S->stateIndex, 1, - (int32_t *) pSrc, 1, blockSize); - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 Multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* Working output pointer is updated */ - pOut = pDst; - - /* Output is converted into 1.31 format. */ - /* Loop over the blockSize. Unroll by a factor of 4. - * process 4 output samples at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * process the remaining output samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiplications and store in the destination buffer */ - *pOut++ = (q31_t) (((q63_t) * px++ * coeff) >> 32); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_f32((int32_t *) py, delaySize, &readIndex, 1, - (int32_t *) pb, (int32_t *) pb, blockSize, 1, - blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pOut = pDst; - - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - out = *pOut; - out += ((q63_t) * px++ * coeff) >> 32; - *pOut++ = (q31_t) (out); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = (int32_t) (S->stateIndex - blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* Working output pointer is updated */ - pOut = pDst; - - /* Output is converted into 1.31 format. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - in = *pOut << 1; - *pOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c deleted file mode 100644 index ace5d07037..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_fir_sparse_q7.c +++ /dev/null @@ -1,398 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fir_sparse_q7.c -* -* Description: Q7 sparse FIR filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup FIR_Sparse - * @{ - */ - - -/** - * @brief Processing function for the Q7 sparse FIR filter. - * @param[in] *S points to an instance of the Q7 sparse FIR structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data - * @param[in] *pScratchIn points to a temporary buffer of size blockSize. - * @param[in] *pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - * @return none. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * Both coefficients and state variables are represented in 1.7 format and multiplications yield a 2.14 result. - * The 2.14 intermediate results are accumulated in a 32-bit accumulator in 18.14 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * The accumulator is then converted to 18.7 format by discarding the low 7 bits. - * Finally, the result is truncated to 1.7 format. - */ - -void arm_fir_sparse_q7( - arm_fir_sparse_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - q7_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize) -{ - - q7_t *pState = S->pState; /* State pointer */ - q7_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q7_t *px; /* Scratch buffer pointer */ - q7_t *py = pState; /* Temporary pointers for state buffer */ - q7_t *pb = pScratchIn; /* Temporary pointers for scratch buffer */ - q7_t *pOut = pDst; /* Destination pointer */ - int32_t *pTapDelay = S->pTapDelay; /* Pointer to the array containing offset of the non-zero tap values. */ - uint32_t delaySize = S->maxDelay + blockSize; /* state length */ - uint16_t numTaps = S->numTaps; /* Filter order */ - int32_t readIndex; /* Read index of the state buffer */ - uint32_t tapCnt, blkCnt; /* loop counters */ - q7_t coeff = *pCoeffs++; /* Read the coefficient value */ - q31_t *pScr2 = pScratchOut; /* Working pointer for scratch buffer of output values */ - q31_t in; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t in1, in2, in3, in4; - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, - blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 multiplications at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize. Unroll by a factor of 4. - * Compute 4 MACS at a time. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - * compute the remaining samples */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize >> 2; - - while(blkCnt > 0u) - { - in1 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in2 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in3 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - in4 = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - *__SIMD32(pOut)++ = __PACKq7(in1, in2, in3, in4); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, - remaining samples are processed in the below loop */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* BlockSize of Input samples are copied into the state buffer */ - /* StateIndex points to the starting position to write in the state buffer */ - arm_circularWrite_q7(py, (int32_t) delaySize, &S->stateIndex, 1, pSrc, 1, - blockSize); - - /* Loop over the number of taps. */ - tapCnt = numTaps; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform multiplication and store in the scratch buffer */ - *pScratchOut++ = ((q31_t) * px++ * coeff); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Loop over the number of taps. */ - tapCnt = (uint32_t) numTaps - 1u; - - while(tapCnt > 0u) - { - /* Working pointer for state buffer is updated */ - py = pState; - - /* blockSize samples are read from the state buffer */ - arm_circularRead_q7(py, (int32_t) delaySize, &readIndex, 1, pb, pb, - (int32_t) blockSize, 1, blockSize); - - /* Working pointer for the scratch buffer of state values */ - px = pb; - - /* Working pointer for scratch buffer of output values */ - pScratchOut = pScr2; - - /* Loop over the blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Perform Multiply-Accumulate */ - in = *pScratchOut + ((q31_t) * px++ * coeff); - *pScratchOut++ = in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Load the coefficient value and - * increment the coefficient buffer for the next set of state values */ - coeff = *pCoeffs++; - - /* Read Index, from where the state buffer should be read, is calculated. */ - readIndex = - ((int32_t) S->stateIndex - (int32_t) blockSize) - *pTapDelay++; - - /* Wraparound of readIndex */ - if(readIndex < 0) - { - readIndex += (int32_t) delaySize; - } - - /* Decrement the tap loop counter */ - tapCnt--; - } - - /* All the output values are in pScratchOut buffer. - Convert them into 1.15 format, saturate and store in the destination buffer. */ - /* Loop over the blockSize. */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - *pOut++ = (q7_t) __SSAT(*pScr2++ >> 7, 8); - - /* Decrement the blockSize loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of FIR_Sparse group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c deleted file mode 100644 index 074605553d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_f32.c +++ /dev/null @@ -1,440 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_f32.c -* -* Description: Floating-point IIR Lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup IIR_Lattice Infinite Impulse Response (IIR) Lattice Filters - * - * This set of functions implements lattice filters - * for Q15, Q31 and floating-point data types. Lattice filters are used in a - * variety of adaptive filter applications. The filter structure has feedforward and - * feedback components and the net impulse response is infinite length. - * The functions operate on blocks - * of input and output data and each call to the function processes - * blockSize samples through the filter. pSrc and - * pDst point to input and output arrays containing blockSize values. - - * \par Algorithm: - * \image html IIRLattice.gif "Infinite Impulse Response Lattice filter" - *
    
- *    fN(n)   =  x(n)    
- *    fm-1(n) = fm(n) - km * gm-1(n-1)   for m = N, N-1, ...1    
- *    gm(n)   = km * fm-1(n) + gm-1(n-1) for m = N, N-1, ...1    
- *    y(n)    = vN * gN(n) + vN-1 * gN-1(n) + ...+ v0 * g0(n)    
- * 
- * \par - * pkCoeffs points to array of reflection coefficients of size numStages. - * Reflection coefficients are stored in time-reversed order. - * \par - *
    
- *    {kN, kN-1, ....k1}    
- * 
- * pvCoeffs points to the array of ladder coefficients of size (numStages+1). - * Ladder coefficients are stored in time-reversed order. - * \par - *
    
- *    {vN, vN-1, ...v0}    
- * 
- * pState points to a state array of size numStages + blockSize. - * The state variables shown in the figure above (the g values) are stored in the pState array. - * The state variables are updated after each block of data is processed; the coefficients are untouched. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter. - * Coefficient arrays may be shared among several instances while state variable arrays cannot be shared. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros and then manually initialize the instance structure as follows: - *
    
- *arm_iir_lattice_instance_f32 S = {numStages, pState, pkCoeffs, pvCoeffs};    
- *arm_iir_lattice_instance_q31 S = {numStages, pState, pkCoeffs, pvCoeffs};    
- *arm_iir_lattice_instance_q15 S = {numStages, pState, pkCoeffs, pvCoeffs};    
- * 
- * \par - * where numStages is the number of stages in the filter; pState points to the state buffer array; - * pkCoeffs points to array of the reflection coefficients; pvCoeffs points to the array of ladder coefficients. - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the IIR lattice filter functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the floating-point IIR lattice filter. - * @param[in] *S points to an instance of the floating-point IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - -void arm_iir_lattice_f32( - const arm_iir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t fnext1, gcurr1, gnext; /* Temporary variables for lattice stages */ - float32_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* temporary variables for counts */ - float32_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - float32_t *pState; /* State pointer */ - float32_t *pStateCurnt; /* State current pointer */ - float32_t k1, k2; - float32_t v1, v2, v3, v4; - float32_t gcurr2; - float32_t fnext2; - - /* initialise loop count */ - blkCnt = blockSize; - - /* initialise state pointer */ - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fnext2 = *pSrc++; - - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - - /* Set accumulator to zero */ - acc = 0.0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages) >> 2; - - while(tapCnt > 0u) - { - /* Read gN-1(n-1) from state buffer */ - gcurr1 = *px1; - - /* read reflection coefficient kN */ - k1 = *pk; - - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext1 = fnext2 - (k1 * gcurr1); - - /* read ladder coefficient vN */ - v1 = *pv; - - /* read next reflection coefficient kN-1 */ - k2 = *(pk + 1u); - - /* Read gN-2(n-1) from state buffer */ - gcurr2 = *(px1 + 1u); - - /* read next ladder coefficient vN-1 */ - v2 = *(pv + 1u); - - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext2 = fnext1 - (k2 * gcurr2); - - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = gcurr1 + (k1 * fnext1); - - /* read reflection coefficient kN-2 */ - k1 = *(pk + 2u); - - /* write gN(n) into state for next sample processing */ - *px2++ = gnext; - - /* Read gN-3(n-1) from state buffer */ - gcurr1 = *(px1 + 2u); - - /* y(n) += gN(n) * vN */ - acc += (gnext * v1); - - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fnext1 = fnext2 - (k1 * gcurr1); - - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = gcurr2 + (k2 * fnext2); - - /* Read gN-4(n-1) from state buffer */ - gcurr2 = *(px1 + 3u); - - /* y(n) += gN-1(n) * vN-1 */ - acc += (gnext * v2); - - /* read reflection coefficient kN-3 */ - k2 = *(pk + 3u); - - /* write gN-1(n) into state for next sample processing */ - *px2++ = gnext; - - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext2 = fnext1 - (k2 * gcurr2); - - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = gcurr1 + (k1 * fnext1); - - /* read ladder coefficient vN-2 */ - v3 = *(pv + 2u); - - /* y(n) += gN-2(n) * vN-2 */ - acc += (gnext * v3); - - /* write gN-2(n) into state for next sample processing */ - *px2++ = gnext; - - /* update pointer */ - pk += 4u; - - /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ - gnext = (fnext2 * k2) + gcurr2; - - /* read next ladder coefficient vN-3 */ - v4 = *(pv + 3u); - - /* y(n) += gN-4(n) * vN-4 */ - acc += (gnext * v4); - - /* write gN-3(n) into state for next sample processing */ - *px2++ = gnext; - - /* update pointers */ - px1 += 4u; - pv += 4u; - - tapCnt--; - - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages) % 0x4u; - - while(tapCnt > 0u) - { - gcurr1 = *px1++; - /* Process sample for last taps */ - fnext1 = fnext2 - ((*pk) * gcurr1); - gnext = (fnext1 * (*pk++)) + gcurr1; - /* Output samples for last taps */ - acc += (gnext * (*pv++)); - *px2++ = gnext; - fnext2 = fnext1; - - tapCnt--; - - } - - /* y(n) += g0(n) * v0 */ - acc += (fnext2 * (*pv)); - - *px2++ = fnext2; - - /* write out into pDst */ - *pDst++ = acc; - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - - } - - /* Calculate remaining number of copies */ - tapCnt = (numStages) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } -} - -#else - -void arm_iir_lattice_f32( - const arm_iir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - float32_t fcurr, fnext = 0, gcurr, gnext; /* Temporary variables for lattice stages */ - float32_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* temporary variables for counts */ - float32_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - float32_t *pState; /* State pointer */ - float32_t *pStateCurnt; /* State current pointer */ - - - /* Run the below code for Cortex-M0 */ - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0.0f; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for numStages */ - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = fcurr - ((*pk) * gcurr); - gnext = (fnext * (*pk++)) + gcurr; - - /* Output samples for last taps */ - acc += (gnext * (*pv++)); - *px2++ = gnext; - fcurr = fnext; - - /* Decrementing loop counter */ - tapCnt--; - - } - - /* y(n) += g0(n) * v0 */ - acc += (fnext * (*pv)); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = acc; - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages; - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -} - -#endif /* #ifndef ARM_MATH_CM0 */ - - -/** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c deleted file mode 100644 index 89c00c24df..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_f32.c +++ /dev/null @@ -1,86 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_f32.c -* -* Description: Floating-point IIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Initialization function for the floating-point IIR lattice filter. - * @param[in] *S points to an instance of the floating-point IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_iir_lattice_init_f32( - arm_iir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pkCoeffs, - float32_t * pvCoeffs, - float32_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - - /** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c deleted file mode 100644 index 7dac99fcab..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q15.c +++ /dev/null @@ -1,86 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_q15.c -* -* Description: Q15 IIR lattice filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q15 IIR lattice filter. - * @param[in] *S points to an instance of the Q15 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process per call. - * @return none. - */ - -void arm_iir_lattice_init_q15( - arm_iir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pkCoeffs, - q15_t * pvCoeffs, - q15_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - -/** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c deleted file mode 100644 index 73b18a5977..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_init_q31.c +++ /dev/null @@ -1,86 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_init_q31.c -* -* Description: Initialization function for the Q31 IIR lattice filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - - /** - * @brief Initialization function for the Q31 IIR lattice filter. - * @param[in] *S points to an instance of the Q31 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_iir_lattice_init_q31( - arm_iir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pkCoeffs, - q31_t * pvCoeffs, - q31_t * pState, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numStages = numStages; - - /* Assign reflection coefficient pointer */ - S->pkCoeffs = pkCoeffs; - - /* Assign ladder coefficient pointer */ - S->pvCoeffs = pvCoeffs; - - /* Clear state buffer and size is always blockSize + numStages */ - memset(pState, 0, (numStages + blockSize) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - -} - -/** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c deleted file mode 100644 index 5f0f891d18..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q15.c +++ /dev/null @@ -1,457 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_q15.c -* -* Description: Q15 IIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the Q15 IIR lattice filter. - * @param[in] *S points to an instance of the Q15 IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - -void arm_iir_lattice_q15( - const arm_iir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t fcurr, fnext, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - q15_t gnext1, gnext2; /* Temporary variables for lattice stages */ - uint32_t stgCnt; /* Temporary variables for counts */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q15_t *pState; /* State pointer */ - q15_t *pStateCurnt; /* State current pointer */ - q15_t out; /* Temporary variable for output */ - q15_t v1, v2; - q31_t v; /* Temporary variable for ladder coefficient */ - - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for first tap */ - gcurr = *px1++; - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* write gN(n) into state for next sample processing */ - *px2++ = (q15_t) gnext; - /* y(n) += gN(n) * vN */ - acc += (q31_t) ((gnext * (*pv++))); - - - /* Update f values for next coefficient processing */ - fcurr = fnext; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages - 1u) >> 2; - - while(tapCnt > 0u) - { - - /* Process sample for 2nd, 6th ...taps */ - /* Read gN-2(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 2nd, 6th .. taps */ - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext1 = (q15_t) __SSAT(gnext, 16); - /* write gN-1(n) into state */ - *px2++ = (q15_t) gnext1; - - - /* Process sample for 3nd, 7th ...taps */ - /* Read gN-3(n-1) from state */ - gcurr = *px1++; - /* Process sample for 3rd, 7th .. taps */ - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); - fcurr = __SSAT(fcurr, 16); - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; - gnext2 = (q15_t) __SSAT(gnext, 16); - /* write gN-2(n) into state */ - *px2++ = (q15_t) gnext2; - - /* Read vN-1 and vN-2 at a time */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - v = *__SIMD32(pv)++; - -#else - - v1 = *pv++; - v2 = *pv++; - -#ifndef ARM_MATH_BIG_ENDIAN - - v = __PKHBT(v1, v2, 16); - -#else - - v = __PKHBT(v2, v1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - - /* Pack gN-1(n) and gN-2(n) */ - -#ifndef ARM_MATH_BIG_ENDIAN - - gnext = __PKHBT(gnext1, gnext2, 16); - -#else - - gnext = __PKHBT(gnext2, gnext1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* y(n) += gN-1(n) * vN-1 */ - /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ - /* y(n) += gN-2(n) * vN-2 */ - /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ - acc = __SMLALD(gnext, v, acc); - - - /* Process sample for 4th, 8th ...taps */ - /* Read gN-4(n-1) from state */ - gcurr = *px1++; - /* Process sample for 4th, 8th .. taps */ - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN-3(n) = kN-3 * fN-1(n) + gN-1(n-1) */ - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext1 = (q15_t) __SSAT(gnext, 16); - /* write gN-3(n) for the next sample process */ - *px2++ = (q15_t) gnext1; - - - /* Process sample for 5th, 9th ...taps */ - /* Read gN-5(n-1) from state */ - gcurr = *px1++; - /* Process sample for 5th, 9th .. taps */ - /* fN-5(n) = fN-4(n) - kN-4 * gN-5(n-1) */ - fcurr = fnext - (((q31_t) gcurr * (*pk)) >> 15); - fcurr = __SSAT(fcurr, 16); - /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ - gnext = (((q31_t) fcurr * (*pk++)) >> 15) + gcurr; - gnext2 = (q15_t) __SSAT(gnext, 16); - /* write gN-4(n) for the next sample process */ - *px2++ = (q15_t) gnext2; - - /* Read vN-3 and vN-4 at a time */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - v = *__SIMD32(pv)++; - -#else - - v1 = *pv++; - v2 = *pv++; - -#ifndef ARM_MATH_BIG_ENDIAN - - v = __PKHBT(v1, v2, 16); - -#else - - v = __PKHBT(v2, v1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - - /* Pack gN-3(n) and gN-4(n) */ -#ifndef ARM_MATH_BIG_ENDIAN - - gnext = __PKHBT(gnext1, gnext2, 16); - -#else - - gnext = __PKHBT(gnext2, gnext1, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* y(n) += gN-4(n) * vN-4 */ - /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ - /* y(n) += gN-3(n) * vN-3 */ - /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ - acc = __SMLALD(gnext, v, acc); - - tapCnt--; - - } - - fnext = fcurr; - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages - 1u) % 0x4u; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = fcurr - (((q31_t) gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - gnext = (((q31_t) fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* Output samples for last taps */ - acc += (q31_t) (((q31_t) gnext * (*pv++))); - *px2++ = (q15_t) gnext; - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q31_t) (((q31_t) fnext * (*pv++))); - - out = (q15_t) __SSAT(acc >> 15, 16); - *px2++ = (q15_t) fnext; - - /* write out into pDst */ - *pDst++ = out; - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - stgCnt = (numStages >> 2u); - - /* copy data */ - while(stgCnt > 0u) - { -#ifndef UNALIGNED_SUPPORT_DISABLE - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - -#else - - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - stgCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - stgCnt = (numStages) % 0x4u; - - /* copy data */ - while(stgCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - stgCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - uint32_t stgCnt; /* Temporary variables for counts */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q15_t *px1, *px2, *pk, *pv; /* temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q15_t *pState; /* State pointer */ - q15_t *pStateCurnt; /* State current pointer */ - q15_t out; /* Temporary variable for output */ - - - blkCnt = blockSize; - - pState = &S->pState[0]; - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample */ - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = fcurr - ((gcurr * (*pk)) >> 15); - fnext = __SSAT(fnext, 16); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = ((fnext * (*pk++)) >> 15) + gcurr; - gnext = __SSAT(gnext, 16); - /* Output samples */ - /* y(n) += gN(n) * vN */ - acc += (q31_t) ((gnext * (*pv++))); - /* write gN(n) into state for next sample processing */ - *px2++ = (q15_t) gnext; - /* Update f values for next coefficient processing */ - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q31_t) ((fnext * (*pv++))); - - out = (q15_t) __SSAT(acc >> 15, 16); - *px2++ = (q15_t) fnext; - - /* write out into pDst */ - *pDst++ = out; - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - stgCnt = numStages; - - /* copy data */ - while(stgCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - stgCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - - -/** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c deleted file mode 100644 index adfd4dfb5d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_iir_lattice_q31.c +++ /dev/null @@ -1,345 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_iir_lattice_q31.c -* -* Description: Q31 IIR lattice filter processing function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup IIR_Lattice - * @{ - */ - -/** - * @brief Processing function for the Q31 IIR lattice filter. - * @param[in] *S points to an instance of the Q31 IIR lattice structure. - * @param[in] *pSrc points to the block of input data. - * @param[out] *pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2*log2(numStages) bits. - * After all multiply-accumulates are performed, the 2.62 accumulator is saturated to 1.32 format and then truncated to 1.31 format. - */ - -void arm_iir_lattice_q31( - const arm_iir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q31_t fcurr, fnext = 0, gcurr = 0, gnext; /* Temporary variables for lattice stages */ - q63_t acc; /* Accumlator */ - uint32_t blkCnt, tapCnt; /* Temporary variables for counts */ - q31_t *px1, *px2, *pk, *pv; /* Temporary pointers for state and coef */ - uint32_t numStages = S->numStages; /* number of stages */ - q31_t *pState; /* State pointer */ - q31_t *pStateCurnt; /* State current pointer */ - - blkCnt = blockSize; - - pState = &S->pState[0]; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - - /* Process sample for first tap */ - gcurr = *px1++; - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* write gN-1(n-1) into state for next sample processing */ - *px2++ = gnext; - /* y(n) += gN(n) * vN */ - acc += ((q63_t) gnext * *pv++); - - /* Update f values for next coefficient processing */ - fcurr = fnext; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = (numStages - 1u) >> 2; - - while(tapCnt > 0u) - { - - /* Process sample for 2nd, 6th .. taps */ - /* Read gN-2(n-1) from state buffer */ - gcurr = *px1++; - /* fN-2(n) = fN-1(n) - kN-1 * gN-2(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-1(n) = kN-1 * fN-2(n) + gN-2(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* y(n) += gN-1(n) * vN-1 */ - /* process for gN-5(n) * vN-5, gN-9(n) * vN-9 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-1(n) into state for next sample processing */ - *px2++ = gnext; - - /* Process sample for 3nd, 7th ...taps */ - /* Read gN-3(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 3rd, 7th .. taps */ - /* fN-3(n) = fN-2(n) - kN-2 * gN-3(n-1) */ - fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-2(n) = kN-2 * fN-3(n) + gN-3(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); - /* y(n) += gN-2(n) * vN-2 */ - /* process for gN-6(n) * vN-6, gN-10(n) * vN-10 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-2(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 4th, 8th ...taps */ - /* Read gN-4(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 4th, 8th .. taps */ - /* fN-4(n) = fN-3(n) - kN-3 * gN-4(n-1) */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-3(n) = kN-3 * fN-4(n) + gN-4(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* y(n) += gN-3(n) * vN-3 */ - /* process for gN-7(n) * vN-7, gN-11(n) * vN-11 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-3(n) into state for next sample processing */ - *px2++ = gnext; - - - /* Process sample for 5th, 9th ...taps */ - /* Read gN-5(n-1) from state buffer */ - gcurr = *px1++; - /* Process sample for 5th, 9th .. taps */ - /* fN-5(n) = fN-4(n) - kN-4 * gN-1(n-1) */ - fcurr = __QSUB(fnext, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - /* gN-4(n) = kN-4 * fN-5(n) + gN-5(n-1) */ - gnext = __QADD(gcurr, (q31_t) (((q63_t) fcurr * (*pk++)) >> 31)); - /* y(n) += gN-4(n) * vN-4 */ - /* process for gN-8(n) * vN-8, gN-12(n) * vN-12 ... */ - acc += ((q63_t) gnext * *pv++); - /* write gN-4(n) into state for next sample processing */ - *px2++ = gnext; - - tapCnt--; - - } - - fnext = fcurr; - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = (numStages - 1u) % 0x4u; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample for last taps */ - fnext = __QSUB(fcurr, (q31_t) (((q63_t) gcurr * (*pk)) >> 31)); - gnext = __QADD(gcurr, (q31_t) (((q63_t) fnext * (*pk++)) >> 31)); - /* Output samples for last taps */ - acc += ((q63_t) gnext * *pv++); - *px2++ = gnext; - fcurr = fnext; - - tapCnt--; - - } - - /* y(n) += g0(n) * v0 */ - acc += (q63_t) fnext *( - *pv++); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance the state pointer by 4 to process the next group of 4 samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - - } - - /* Calculate remaining number of copies */ - tapCnt = (numStages) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - }; - -#else - - /* Run the below code for Cortex-M0 */ - /* Sample processing */ - while(blkCnt > 0u) - { - /* Read Sample from input buffer */ - /* fN(n) = x(n) */ - fcurr = *pSrc++; - - /* Initialize state read pointer */ - px1 = pState; - /* Initialize state write pointer */ - px2 = pState; - /* Set accumulator to zero */ - acc = 0; - /* Initialize Ladder coeff pointer */ - pv = &S->pvCoeffs[0]; - /* Initialize Reflection coeff pointer */ - pk = &S->pkCoeffs[0]; - - tapCnt = numStages; - - while(tapCnt > 0u) - { - gcurr = *px1++; - /* Process sample */ - /* fN-1(n) = fN(n) - kN * gN-1(n-1) */ - fnext = - clip_q63_to_q31(((q63_t) fcurr - - ((q31_t) (((q63_t) gcurr * (*pk)) >> 31)))); - /* gN(n) = kN * fN-1(n) + gN-1(n-1) */ - gnext = - clip_q63_to_q31(((q63_t) gcurr + - ((q31_t) (((q63_t) fnext * (*pk++)) >> 31)))); - /* Output samples */ - /* y(n) += gN(n) * vN */ - acc += ((q63_t) gnext * *pv++); - /* write gN-1(n-1) into state for next sample processing */ - *px2++ = gnext; - /* Update f values for next coefficient processing */ - fcurr = fnext; - - tapCnt--; - } - - /* y(n) += g0(n) * v0 */ - acc += (q63_t) fnext *( - *pv++); - - *px2++ = fnext; - - /* write out into pDst */ - *pDst++ = (q31_t) (acc >> 31u); - - /* Advance the state pointer by 1 to process the next group of samples */ - pState = pState + 1u; - blkCnt--; - - } - - /* Processing is complete. Now copy last S->numStages samples to start of the buffer - for the preperation of next frame process */ - - /* Points to the start of the state buffer */ - pStateCurnt = &S->pState[0]; - pState = &S->pState[blockSize]; - - tapCnt = numStages; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - - - -/** - * @} end of IIR_Lattice group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c deleted file mode 100644 index 90fa8ae1e9..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_f32.c +++ /dev/null @@ -1,434 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_f32.c -* -* Description: Processing function for the floating-point LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup LMS Least Mean Square (LMS) Filters - * - * LMS filters are a class of adaptive filters that are able to "learn" an unknown transfer functions. - * LMS filters use a gradient descent method in which the filter coefficients are updated based on the instantaneous error signal. - * Adaptive filters are often used in communication systems, equalizers, and noise removal. - * The CMSIS DSP Library contains LMS filter functions that operate on Q15, Q31, and floating-point data types. - * The library also contains normalized LMS filters in which the filter coefficient adaptation is indepedent of the level of the input signal. - * - * An LMS filter consists of two components as shown below. - * The first component is a standard transversal or FIR filter. - * The second component is a coefficient update mechanism. - * The LMS filter has two input signals. - * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. - * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. - * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. - * This "error signal" tends towards zero as the filter adapts. - * The LMS processing functions accept the input and reference input signals and generate the filter output and error signal. - * \image html LMS.gif "Internal structure of the Least Mean Square filter" - * - * The functions operate on blocks of data and each call to the function processes - * blockSize samples through the filter. - * pSrc points to input signal, pRef points to reference signal, - * pOut points to output signal and pErr points to error signal. - * All arrays contain blockSize values. - * - * The functions operate on a block-by-block basis. - * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. - * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. - * - * \par Algorithm: - * The output signal y[n] is computed by a standard FIR filter: - *
    
- *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]    
- * 
- * - * \par - * The error signal equals the difference between the reference signal d[n] and the filter output: - *
    
- *     e[n] = d[n] - y[n].    
- * 
- * - * \par - * After each sample of the error signal is computed, the filter coefficients b[k] are updated on a sample-by-sample basis: - *
    
- *     b[k] = b[k] + e[n] * mu * x[n-k],  for k=0, 1, ..., numTaps-1    
- * 
- * where mu is the step size and controls the rate of coefficient convergence. - *\par - * In the APIs, pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
    
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}    
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. - * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter and - * coefficient and state arrays cannot be shared among instances. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Set the values in the state buffer to zeros before static initialization. - * The code below statically initializes each of the 3 different data type filter instance structures - *
    
- *    arm_lms_instance_f32 S = {numTaps, pState, pCoeffs, mu};    
- *    arm_lms_instance_q31 S = {numTaps, pState, pCoeffs, mu, postShift};    
- *    arm_lms_instance_q15 S = {numTaps, pState, pCoeffs, mu, postShift};    
- * 
- * where numTaps is the number of filter coefficients in the filter; pState is the address of the state buffer; - * pCoeffs is the address of the coefficient buffer; mu is the step size parameter; and postShift is the shift applied to coefficients. - * - * \par Fixed-Point Behavior: - * Care must be taken when using the Q15 and Q31 versions of the LMS filter. - * The following issues must be considered: - * - Scaling of coefficients - * - Overflow and saturation - * - * \par Scaling of Coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift. - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * This essentially scales the filter coefficients by 2^postShift and - * allows the filter coefficients to exceed the range [+1 -1). - * The value of postShift is set by the user based on the expected gain through the system being modeled. - * - * \par Overflow and Saturation: - * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are - * described separately as part of the function specific documentation below. - */ - -/** - * @addtogroup LMS - * @{ - */ - -/** - * @details - * This function operates on floating-point data types. - * - * @brief Processing function for floating-point LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_lms_f32( - const arm_lms_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - float32_t sum, e, d; /* accumulator, error, reference data sample */ - float32_t w = 0.0f; /* weight factor */ - - e = 0.0f; - d = 0.0f; - - /* S->pState points to state array which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator, store in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for the updating filter coefficients */ - w = e * mu; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result is stored in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Weighting factor for the LMS version */ - w = e * mu; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb = *pb + (w * (*px++)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - * start of the state buffer. This prepares the state buffer for the - * next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c deleted file mode 100644 index a2f51240a5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_f32.c +++ /dev/null @@ -1,90 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_f32.c -* -* Description: Floating-point LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Initialization function for floating-point LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to the coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -/** - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, where blockSize is the number of input samples processed by each call to arm_lms_f32(). - */ - -void arm_lms_init_f32( - arm_lms_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps */ - memset(pState, 0, (numTaps + (blockSize - 1)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c deleted file mode 100644 index 8f42949a61..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q15.c +++ /dev/null @@ -1,100 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_q15.c -* -* Description: Q15 LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - -/** -* @brief Initialization function for the Q15 LMS filter. -* @param[in] *S points to an instance of the Q15 LMS filter structure. -* @param[in] numTaps number of filter coefficients. -* @param[in] *pCoeffs points to the coefficient buffer. -* @param[in] *pState points to the state buffer. -* @param[in] mu step size that controls filter coefficient updates. -* @param[in] blockSize number of samples to process. -* @param[in] postShift bit shift applied to coefficients. -* @return none. -* -* \par Description: -* pCoeffs points to the array of filter coefficients stored in time reversed order: -*
    
-*    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
-* 
-* The initial filter coefficients serve as a starting point for the adaptive filter. -* pState points to the array of state variables and size of array is -* numTaps+blockSize-1 samples, where blockSize is the number of -* input samples processed by each call to arm_lms_q15(). -*/ - -void arm_lms_init_q15( - arm_lms_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint32_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Assign postShift value to be applied */ - S->postShift = postShift; - -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c deleted file mode 100644 index 58edb659ba..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_init_q31.c +++ /dev/null @@ -1,100 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_init_q31.c -* -* Description: Q31 LMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Initialization function for Q31 LMS filter. - * @param[in] *S points to an instance of the Q31 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to - * arm_lms_q31(). - */ - -void arm_lms_init_q31( - arm_lms_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint32_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, ((uint32_t) numTaps + (blockSize - 1u)) * sizeof(q31_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Assign postShift value to be applied */ - S->postShift = postShift; - -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c deleted file mode 100644 index b2ac452069..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_f32.c +++ /dev/null @@ -1,456 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_f32.c -* -* Description: Processing function for the floating-point Normalised LMS. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @defgroup LMS_NORM Normalized LMS Filters - * - * This set of functions implements a commonly used adaptive filter. - * It is related to the Least Mean Square (LMS) adaptive filter and includes an additional normalization - * factor which increases the adaptation rate of the filter. - * The CMSIS DSP Library contains normalized LMS filter functions that operate on Q15, Q31, and floating-point data types. - * - * A normalized least mean square (NLMS) filter consists of two components as shown below. - * The first component is a standard transversal or FIR filter. - * The second component is a coefficient update mechanism. - * The NLMS filter has two input signals. - * The "input" feeds the FIR filter while the "reference input" corresponds to the desired output of the FIR filter. - * That is, the FIR filter coefficients are updated so that the output of the FIR filter matches the reference input. - * The filter coefficient update mechanism is based on the difference between the FIR filter output and the reference input. - * This "error signal" tends towards zero as the filter adapts. - * The NLMS processing functions accept the input and reference input signals and generate the filter output and error signal. - * \image html LMS.gif "Internal structure of the NLMS adaptive filter" - * - * The functions operate on blocks of data and each call to the function processes - * blockSize samples through the filter. - * pSrc points to input signal, pRef points to reference signal, - * pOut points to output signal and pErr points to error signal. - * All arrays contain blockSize values. - * - * The functions operate on a block-by-block basis. - * Internally, the filter coefficients b[n] are updated on a sample-by-sample basis. - * The convergence of the LMS filter is slower compared to the normalized LMS algorithm. - * - * \par Algorithm: - * The output signal y[n] is computed by a standard FIR filter: - *
    
- *     y[n] = b[0] * x[n] + b[1] * x[n-1] + b[2] * x[n-2] + ...+ b[numTaps-1] * x[n-numTaps+1]    
- * 
- * - * \par - * The error signal equals the difference between the reference signal d[n] and the filter output: - *
    
- *     e[n] = d[n] - y[n].    
- * 
- * - * \par - * After each sample of the error signal is computed the instanteous energy of the filter state variables is calculated: - *
    
- *    E = x[n]^2 + x[n-1]^2 + ... + x[n-numTaps+1]^2.    
- * 
- * The filter coefficients b[k] are then updated on a sample-by-sample basis: - *
    
- *     b[k] = b[k] + e[n] * (mu/E) * x[n-k],  for k=0, 1, ..., numTaps-1    
- * 
- * where mu is the step size and controls the rate of coefficient convergence. - *\par - * In the APIs, pCoeffs points to a coefficient array of size numTaps. - * Coefficients are stored in time reversed order. - * \par - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * \par - * pState points to a state array of size numTaps + blockSize - 1. - * Samples in the state buffer are stored in the order: - * \par - *
    
- *    {x[n-numTaps+1], x[n-numTaps], x[n-numTaps-1], x[n-numTaps-2]....x[0], x[1], ..., x[blockSize-1]}    
- * 
- * \par - * Note that the length of the state buffer exceeds the length of the coefficient array by blockSize-1 samples. - * The increased state buffer length allows circular addressing, which is traditionally used in FIR filters, - * to be avoided and yields a significant speed improvement. - * The state variables are updated after each block of data is processed. - * \par Instance Structure - * The coefficients and state variables for a filter are stored together in an instance data structure. - * A separate instance structure must be defined for each filter and - * coefficient and state arrays cannot be shared among instances. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Zeros out the values in the state buffer. - * \par - * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. - * \par Fixed-Point Behavior: - * Care must be taken when using the Q15 and Q31 versions of the normalised LMS filter. - * The following issues must be considered: - * - Scaling of coefficients - * - Overflow and saturation - * - * \par Scaling of Coefficients: - * Filter coefficients are represented as fractional values and - * coefficients are restricted to lie in the range [-1 +1). - * The fixed-point functions have an additional scaling parameter postShift. - * At the output of the filter's accumulator is a shift register which shifts the result by postShift bits. - * This essentially scales the filter coefficients by 2^postShift and - * allows the filter coefficients to exceed the range [+1 -1). - * The value of postShift is set by the user based on the expected gain through the system being modeled. - * - * \par Overflow and Saturation: - * Overflow and saturation behavior of the fixed-point Q15 and Q31 versions are - * described separately as part of the function specific documentation below. - */ - - -/** - * @addtogroup LMS_NORM - * @{ - */ - - - /** - * @brief Processing function for floating-point normalized LMS filter. - * @param[in] *S points to an instance of the floating-point normalized LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - */ - -void arm_lms_norm_f32( - arm_lms_norm_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize) -{ - float32_t *pState = S->pState; /* State pointer */ - float32_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - float32_t *pStateCurnt; /* Points to the current sample of the state */ - float32_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - float32_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - float32_t energy; /* Energy of the input */ - float32_t sum, e, d; /* accumulator, error, reference data sample */ - float32_t w, x0, in; /* weight factor, temporary variable to hold input sample and state */ - - /* Initializations of error, difference, Coefficient update */ - e = 0.0f; - d = 0.0f; - w = 0.0f; - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= x0 * x0; - energy += in * in; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator, store in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for updating filter coefficients */ - /* epsilon value 0.000000119209289f */ - w = (e * mu) / (energy + 0.000000119209289f); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - *pb += w * (*px++); - pb++; - - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - S->energy = energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u)/4 samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= x0 * x0; - energy += in * in; - - /* Set the accumulator to zero */ - sum = 0.0f; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - sum += (*px++) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* The result in the accumulator is stored in the destination buffer. */ - *pOut++ = sum; - - /* Compute and store error */ - d = (float32_t) (*pRef++); - e = d - sum; - *pErr++ = e; - - /* Calculation of Weighting factor for updating filter coefficients */ - /* epsilon value 0.000000119209289f */ - w = (e * mu) / (energy + 0.000000119209289f); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCcoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb += w * (*px++); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - S->energy = energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c deleted file mode 100644 index 3d31cfb257..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_f32.c +++ /dev/null @@ -1,100 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_f32.c -* -* Description: Floating-point NLMS filter initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for floating-point normalized LMS filter. - * @param[in] *S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Description: - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to arm_lms_norm_f32(). - */ - -void arm_lms_norm_init_f32( - arm_lms_norm_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(float32_t)); - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialise Energy to zero */ - S->energy = 0.0f; - - /* Initialise x0 to zero */ - S->x0 = 0.0f; - -} - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c deleted file mode 100644 index a1cf1b001d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q15.c +++ /dev/null @@ -1,107 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_q15.c -* -* Description: Q15 NLMS initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for Q15 normalized LMS filter. - * @param[in] *S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to the array of state variables and size of array is - * numTaps+blockSize-1 samples, where blockSize is the number of input samples processed - * by each call to arm_lms_norm_q15(). - */ - -void arm_lms_norm_init_q15( - arm_lms_norm_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint8_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q15_t)); - - /* Assign post Shift value applied to coefficients */ - S->postShift = postShift; - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialize reciprocal pointer table */ - S->recipTable = (q15_t *) armRecipTableQ15; - - /* Initialise Energy to zero */ - S->energy = 0; - - /* Initialise x0 to zero */ - S->x0 = 0; - -} - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c deleted file mode 100644 index a2fae7b381..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_init_q31.c +++ /dev/null @@ -1,106 +0,0 @@ -/*----------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_init_q31.c -* -* Description: Q31 NLMS initialization function. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------*/ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @addtogroup LMS_NORM - * @{ - */ - - /** - * @brief Initialization function for Q31 normalized LMS filter. - * @param[in] *S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] *pCoeffs points to coefficient buffer. - * @param[in] *pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - * @return none. - * - * Description: - * \par - * pCoeffs points to the array of filter coefficients stored in time reversed order: - *
    
- *    {b[numTaps-1], b[numTaps-2], b[N-2], ..., b[1], b[0]}    
- * 
- * The initial filter coefficients serve as a starting point for the adaptive filter. - * pState points to an array of length numTaps+blockSize-1 samples, - * where blockSize is the number of input samples processed by each call to arm_lms_norm_q31(). - */ - -void arm_lms_norm_init_q31( - arm_lms_norm_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint8_t postShift) -{ - /* Assign filter taps */ - S->numTaps = numTaps; - - /* Assign coefficient pointer */ - S->pCoeffs = pCoeffs; - - /* Clear state buffer and size is always blockSize + numTaps - 1 */ - memset(pState, 0, (numTaps + (blockSize - 1u)) * sizeof(q31_t)); - - /* Assign post Shift value applied to coefficients */ - S->postShift = postShift; - - /* Assign state pointer */ - S->pState = pState; - - /* Assign Step size value */ - S->mu = mu; - - /* Initialize reciprocal pointer table */ - S->recipTable = (q31_t *) armRecipTableQ31; - - /* Initialise Energy to zero */ - S->energy = 0; - - /* Initialise x0 to zero */ - S->x0 = 0; - -} - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c deleted file mode 100644 index a1229a2036..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q15.c +++ /dev/null @@ -1,435 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_q15.c -* -* Description: Q15 NLMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - -/** -* @brief Processing function for Q15 normalized LMS filter. -* @param[in] *S points to an instance of the Q15 normalized LMS filter structure. -* @param[in] *pSrc points to the block of input data. -* @param[in] *pRef points to the block of reference data. -* @param[out] *pOut points to the block of output data. -* @param[out] *pErr points to the block of error data. -* @param[in] blockSize number of samples to process. -* @return none. -* -* Scaling and Overflow Behavior: -* \par -* The function is implemented using a 64-bit internal accumulator. -* Both coefficients and state variables are represented in 1.15 format and -* multiplications yield a 2.30 result. The 2.30 intermediate results are -* accumulated in a 64-bit accumulator in 34.30 format. -* There is no risk of internal overflow with this approach and the full -* precision of intermediate multiplications is preserved. After all additions -* have been performed, the accumulator is truncated to 34.15 format by -* discarding low 15 bits. Lastly, the accumulator is saturated to yield a -* result in 1.15 format. -* -* \par -* In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. -* - */ - -void arm_lms_norm_q15( - arm_lms_norm_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - q15_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q31_t energy; /* Energy of the input */ - q63_t acc; /* Accumulator */ - q15_t e = 0, d = 0; /* error, reference data sample */ - q15_t w = 0, in; /* weight factor and state */ - q15_t x0; /* temporary variable to hold input sample */ - //uint32_t shift = (uint32_t) S->postShift + 1u; /* Shift to be applied to the output */ - q15_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ - q15_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ - q31_t coef; /* Teporary variable for coefficient */ - q31_t acc_l, acc_h; - int32_t lShift = (15 - (int32_t) S->postShift); /* Post shift */ - int32_t uShift = (32 - lShift); - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= (((q31_t) x0 * (x0)) >> 15); - energy += (((q31_t) in * (in)) >> 15); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - - /* Perform the multiply-accumulate */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - -#else - - acc += (((q31_t) * px++ * (*pb++))); - acc += (((q31_t) * px++ * (*pb++))); - acc += (((q31_t) * px++ * (*pb++))); - acc += (((q31_t) * px++ * (*pb++))); - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (((q31_t) * px++ * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT(acc, 16u); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q15_t) acc; - *pErr++ = e; - - /* Calculation of 1/energy */ - postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, - &oneByEnergy, S->recipTable); - - /* Calculation of e * mu value */ - errorXmu = (q15_t) (((q31_t) e * mu) >> 15); - - /* Calculation of (e * mu) * (1/energy) value */ - acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); - - /* Weighting factor for the normalized version */ - w = (q15_t) __SSAT((q31_t) acc, 16); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q15_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - -#else - - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - -#endif - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy -= (((q31_t) x0 * (x0)) >> 15); - energy += (((q31_t) in * (in)) >> 15); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (((q31_t) * px++ * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT(acc, 16u); - - /* Converting the result to 1.15 format */ - //acc = __SSAT((acc >> (16u - shift)), 16u); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q15_t) acc; - *pErr++ = e; - - /* Calculation of 1/energy */ - postShift = arm_recip_q15((q15_t) energy + DELTA_Q15, - &oneByEnergy, S->recipTable); - - /* Calculation of e * mu value */ - errorXmu = (q15_t) (((q31_t) e * mu) >> 15); - - /* Calculation of (e * mu) * (1/energy) value */ - acc = (((q31_t) errorXmu * oneByEnergy) >> (15 - postShift)); - - /* Weighting factor for the normalized version */ - w = (q15_t) __SSAT((q31_t) acc, 16); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = *pb + (((q31_t) w * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q15_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* copy (numTaps - 1u) data */ - tapCnt = (numTaps - 1u); - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c deleted file mode 100644 index 791a8637cc..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_norm_q31.c +++ /dev/null @@ -1,426 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_norm_q31.c -* -* Description: Processing function for the Q31 NLMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS_NORM - * @{ - */ - -/** -* @brief Processing function for Q31 normalized LMS filter. -* @param[in] *S points to an instance of the Q31 normalized LMS filter structure. -* @param[in] *pSrc points to the block of input data. -* @param[in] *pRef points to the block of reference data. -* @param[out] *pOut points to the block of output data. -* @param[out] *pErr points to the block of error data. -* @param[in] blockSize number of samples to process. -* @return none. -* -* Scaling and Overflow Behavior: -* \par -* The function is implemented using an internal 64-bit accumulator. -* The accumulator has a 2.62 format and maintains full precision of the intermediate -* multiplication results but provides only a single guard bit. -* Thus, if the accumulator result overflows it wraps around rather than clip. -* In order to avoid overflows completely the input signal must be scaled down by -* log2(numTaps) bits. The reference signal should not be scaled down. -* After all multiply-accumulates are performed, the 2.62 accumulator is shifted -* and saturated to 1.31 format to yield the final result. -* The output signal and error signal are in 1.31 format. -* -* \par -* In this filter, filter coefficients are updated for each sample and the -* updation of filter cofficients are saturted. -* -*/ - -void arm_lms_norm_q31( - arm_lms_norm_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t *px, *pb; /* Temporary pointers for state and coefficient buffers */ - q31_t mu = S->mu; /* Adaptive factor */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t energy; /* Energy of the input */ - q63_t acc; /* Accumulator */ - q31_t e = 0, d = 0; /* error, reference data sample */ - q31_t w = 0, in; /* weight factor and state */ - q31_t x0; /* temporary variable to hold input sample */ -// uint32_t shift = 32u - ((uint32_t) S->postShift + 1u); /* Shift to be applied to the output */ - q31_t errorXmu, oneByEnergy; /* Temporary variables to store error and mu product and reciprocal of energy */ - q31_t postShift; /* Post shift to be applied to weight after reciprocal calculation */ - q31_t coef; /* Temporary variable for coef */ - q31_t acc_l, acc_h; /* temporary input */ - uint32_t uShift = ((uint32_t) S->postShift + 1u); - uint32_t lShift = 32u - uShift; /* Shift to be applied to the output */ - - energy = S->energy; - x0 = S->x0; - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy = (q31_t) ((((q63_t) energy << 32) - - (((q63_t) x0 * x0) << 1)) >> 32); - energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q31_t) acc; - *pErr++ = e; - - /* Calculates the reciprocal of energy */ - postShift = arm_recip_q31(energy + DELTA_Q31, - &oneByEnergy, &S->recipTable[0]); - - /* Calculation of product of (e * mu) */ - errorXmu = (q31_t) (((q63_t) e * mu) >> 31); - - /* Weighting factor for the normalized version */ - w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q31_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Read the sample from input buffer */ - in = *pSrc++; - - /* Update the energy calculation */ - energy = - (q31_t) ((((q63_t) energy << 32) - (((q63_t) x0 * x0) << 1)) >> 32); - energy = (q31_t) (((((q63_t) in * in) << 1) + (energy << 32)) >> 32); - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Converting the result to 1.31 format */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - - //acc = (q31_t) (acc >> shift); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - d = *pRef++; - e = d - (q31_t) acc; - *pErr++ = e; - - /* Calculates the reciprocal of energy */ - postShift = - arm_recip_q31(energy + DELTA_Q31, &oneByEnergy, &S->recipTable[0]); - - /* Calculation of product of (e * mu) */ - errorXmu = (q31_t) (((q63_t) e * mu) >> 31); - - /* Weighting factor for the normalized version */ - w = clip_q63_to_q31(((q63_t) errorXmu * oneByEnergy) >> (31 - postShift)); - - /* Initialize pState pointer */ - px = pState; - - /* Initialize coeff pointer */ - pb = (pCoeffs); - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) w * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Read the sample from state buffer */ - x0 = *pState; - - /* Advance state pointer by 1 for the next sample */ - pState = pState + 1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Save energy and x0 values for the next frame */ - S->energy = (q31_t) energy; - S->x0 = x0; - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u); - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS_NORM group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c deleted file mode 100644 index 91237c12d8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q15.c +++ /dev/null @@ -1,374 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_q15.c -* -* Description: Processing function for the Q15 LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Processing function for Q15 LMS filter. - * @param[in] *S points to an instance of the Q15 LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Scaling and Overflow Behavior: - * The function is implemented using a 64-bit internal accumulator. - * Both coefficients and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - * - * \par - * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. - * - */ - -void arm_lms_q15( - const arm_lms_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize) -{ - q15_t *pState = S->pState; /* State pointer */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - q15_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q15_t *pStateCurnt; /* Points to the current sample of the state */ - q15_t mu = S->mu; /* Adaptive factor */ - q15_t *px; /* Temporary pointer for state */ - q15_t *pb; /* Temporary pointer for coefficient buffer */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t acc; /* Accumulator */ - q15_t e = 0; /* error of data sample */ - q15_t alpha; /* Intermediate constant for taps update */ - q31_t acc_l, acc_h; - int32_t lShift = (15 - (int32_t) S->postShift); /* Post shift */ - int32_t uShift = (32 - lShift); - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t coef; /* Teporary variable for coefficient */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initializing blkCnt with blockSize */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2u; - - while(tapCnt > 0u) - { - /* acc += b[N] * x[n-N] + b[N-1] * x[n-N-1] */ - /* Perform the multiply-accumulate */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - acc = __SMLALD(*__SIMD32(px)++, (*__SIMD32(pb)++), acc); - -#else - - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (q63_t) (((q31_t) (*px++) * (*pb++))); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT(acc, 16); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q15_t) acc; - - *pErr++ = (q15_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q15_t) (((q31_t) e * (mu)) >> 15); - - /* Initialize state pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2u; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) * pb + (((q31_t) alpha * (*px++)) >> 15); - *pb++ = (q15_t) __SSAT((coef), 16); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Calculation of count for copying integer writes */ - tapCnt = (numTaps - 1u) >> 2; - - while(tapCnt > 0u) - { - -#ifndef UNALIGNED_SUPPORT_DISABLE - - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; - *__SIMD32(pStateCurnt)++ = *__SIMD32(pState)++; -#else - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; -#endif - - tapCnt--; - - } - - /* Calculation of count for remaining q15_t data */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += (q63_t) ((q31_t) (*px++) * (*pb++)); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - /* Apply shift for lower part of acc and upper part of acc */ - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Converting the result to 1.15 format and saturate the output */ - acc = __SSAT(acc, 16); - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q15_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q15_t) acc; - - *pErr++ = (q15_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q15_t) (((q31_t) e * (mu)) >> 15); - - /* Initialize pState pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - *pb++ += (q15_t) (((q31_t) alpha * (*px++)) >> 15); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c deleted file mode 100644 index c43d55d1df..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/FilteringFunctions/arm_lms_q31.c +++ /dev/null @@ -1,364 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_lms_q31.c -* -* Description: Processing function for the Q31 LMS filter. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -/** - * @ingroup groupFilters - */ - -/** - * @addtogroup LMS - * @{ - */ - - /** - * @brief Processing function for Q31 LMS filter. - * @param[in] *S points to an instance of the Q15 LMS filter structure. - * @param[in] *pSrc points to the block of input data. - * @param[in] *pRef points to the block of reference data. - * @param[out] *pOut points to the block of output data. - * @param[out] *pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - * @return none. - * - * \par Scaling and Overflow Behavior: - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate - * multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clips. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(numTaps) bits. - * The reference signal should not be scaled down. - * After all multiply-accumulates are performed, the 2.62 accumulator is shifted - * and saturated to 1.31 format to yield the final result. - * The output signal and error signal are in 1.31 format. - * - * \par - * In this filter, filter coefficients are updated for each sample and the updation of filter cofficients are saturted. - */ - -void arm_lms_q31( - const arm_lms_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize) -{ - q31_t *pState = S->pState; /* State pointer */ - uint32_t numTaps = S->numTaps; /* Number of filter coefficients in the filter */ - q31_t *pCoeffs = S->pCoeffs; /* Coefficient pointer */ - q31_t *pStateCurnt; /* Points to the current sample of the state */ - q31_t mu = S->mu; /* Adaptive factor */ - q31_t *px; /* Temporary pointer for state */ - q31_t *pb; /* Temporary pointer for coefficient buffer */ - uint32_t tapCnt, blkCnt; /* Loop counters */ - q63_t acc; /* Accumulator */ - q31_t e = 0; /* error of data sample */ - q31_t alpha; /* Intermediate constant for taps update */ - q31_t coef; /* Temporary variable for coef */ - q31_t acc_l, acc_h; /* temporary input */ - uint32_t uShift = ((uint32_t) S->postShift + 1u); - uint32_t lShift = 32u - uShift; /* Shift to be applied to the output */ - - /* S->pState points to buffer which contains previous frame (numTaps - 1) samples */ - /* pStateCurnt points to the location where the new input data should be written */ - pStateCurnt = &(S->pState[(numTaps - 1u)]); - - /* Initializing blkCnt with blockSize */ - blkCnt = blockSize; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize state pointer */ - px = pState; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - /* acc += b[N] * x[n-N] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-1] * x[n-N-1] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-2] * x[n-N-2] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* acc += b[N-3] * x[n-N-3] */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - /* Store the result from accumulator into the destination buffer. */ - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q31_t) acc; - - *pErr++ = (q31_t) e; - - /* Compute alpha i.e. intermediate constant for taps update */ - alpha = (q31_t) (((q63_t) e * mu) >> 31); - - /* Initialize state pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize coefficient pointer */ - pb = pCoeffs; - - /* Loop unrolling. Process 4 taps at a time. */ - tapCnt = numTaps >> 2; - - /* Update filter coefficients */ - while(tapCnt > 0u) - { - /* coef is in 2.30 format */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - /* get coef in 1.31 format by left shifting */ - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - /* update coefficient buffer to next coefficient */ - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* If the filter length is not a multiple of 4, compute the remaining filter taps */ - tapCnt = numTaps % 0x4u; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb = clip_q63_to_q31((q63_t) * pb + (coef << 1u)); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - satrt of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Loop unrolling for (numTaps - 1u) samples copy */ - tapCnt = (numTaps - 1u) >> 2u; - - /* copy data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Calculate remaining number of copies */ - tapCnt = (numTaps - 1u) % 0x4u; - - /* Copy the remaining q31_t data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - while(blkCnt > 0u) - { - /* Copy the new input sample into the state buffer */ - *pStateCurnt++ = *pSrc++; - - /* Initialize pState pointer */ - px = pState; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Set the accumulator to zero */ - acc = 0; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - acc += ((q63_t) (*px++)) * (*pb++); - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Converting the result to 1.31 format */ - /* Store the result from accumulator into the destination buffer. */ - /* Calc lower part of acc */ - acc_l = acc & 0xffffffff; - - /* Calc upper part of acc */ - acc_h = (acc >> 32) & 0xffffffff; - - acc = (uint32_t) acc_l >> lShift | acc_h << uShift; - - *pOut++ = (q31_t) acc; - - /* Compute and store error */ - e = *pRef++ - (q31_t) acc; - - *pErr++ = (q31_t) e; - - /* Weighting factor for the LMS version */ - alpha = (q31_t) (((q63_t) e * mu) >> 31); - - /* Initialize pState pointer */ - /* Advance state pointer by 1 for the next sample */ - px = pState++; - - /* Initialize pCoeffs pointer */ - pb = pCoeffs; - - /* Loop over numTaps number of values */ - tapCnt = numTaps; - - while(tapCnt > 0u) - { - /* Perform the multiply-accumulate */ - coef = (q31_t) (((q63_t) alpha * (*px++)) >> (32)); - *pb += (coef << 1u); - pb++; - - /* Decrement the loop counter */ - tapCnt--; - } - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Processing is complete. Now copy the last numTaps - 1 samples to the - start of the state buffer. This prepares the state buffer for the - next function call. */ - - /* Points to the start of the pState buffer */ - pStateCurnt = S->pState; - - /* Copy (numTaps - 1u) samples */ - tapCnt = (numTaps - 1u); - - /* Copy the data */ - while(tapCnt > 0u) - { - *pStateCurnt++ = *pState++; - - /* Decrement the loop counter */ - tapCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of LMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c deleted file mode 100644 index 09099ccb81..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_f32.c +++ /dev/null @@ -1,206 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_f32.c -* -* Description: Floating-point matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixAdd Matrix Addition - * - * Adds two matrices. - * \image html MatrixAddition.gif "Addition of two 3 x 3 matrices" - * - * The functions check to make sure that - * pSrcA, pSrcB, and pDst have the same - * number of rows and columns. - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - - -/** - * @brief Floating-point matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_add_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - -#ifndef ARM_MATH_CM0 - - float32_t inA1, inA2, inB1, inB2, out1, out2; /* temporary variables */ - -#endif // #ifndef ARM_MATH_CM0 - - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif - { - - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Loop unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add and then store the results in the destination buffer. */ - /* Read values from source A */ - inA1 = pIn1[0]; - - /* Read values from source B */ - inB1 = pIn2[0]; - - /* Read values from source A */ - inA2 = pIn1[1]; - - /* out = sourceA + sourceB */ - out1 = inA1 + inB1; - - /* Read values from source B */ - inB2 = pIn2[1]; - - /* Read values from source A */ - inA1 = pIn1[2]; - - /* out = sourceA + sourceB */ - out2 = inA2 + inB2; - - /* Read values from source B */ - inB1 = pIn2[2]; - - /* Store result in destination */ - pOut[0] = out1; - pOut[1] = out2; - - /* Read values from source A */ - inA2 = pIn1[3]; - - /* Read values from source B */ - inB2 = pIn2[3]; - - /* out = sourceA + sourceB */ - out1 = inA1 + inB1; - - /* out = sourceA + sourceB */ - out2 = inA2 + inB2; - - /* Store result in destination */ - pOut[2] = out1; - - /* Store result in destination */ - pOut[3] = out2; - - - /* update pointers to process next sampels */ - pIn1 += 4u; - pIn2 += 4u; - pOut += 4u; - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) + (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c deleted file mode 100644 index 4bfc878622..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q15.c +++ /dev/null @@ -1,161 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_q15.c -* -* Description: Q15 matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - -/** - * @brief Q15 matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -arm_status arm_mat_add_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint16_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint16_t) (pSrcA->numRows * pSrcA->numCols); - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop unrolling */ - blkCnt = (uint32_t) numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - *__SIMD32(pOut)++ = __QADD16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = (uint32_t) numSamples % 0x4u; - - /* q15 pointers of input and output are initialized */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __QADD16(*pInA++, *pInB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = (uint32_t) numSamples; - - - /* q15 pointers of input and output are initialized */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, Saturate and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ + *pInB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c deleted file mode 100644 index 1f7be21c55..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_add_q31.c +++ /dev/null @@ -1,205 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_add_q31.c -* -* Description: Q31 matrix addition -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixAdd - * @{ - */ - -/** - * @brief Q31 matrix addition. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - -arm_status arm_mat_add_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t inA1, inB1; /* temporary variables */ - -#ifndef ARM_MATH_CM0 - - q31_t inA2, inB2; /* temporary variables */ - q31_t out1, out2; /* temporary variables */ - -#endif // #ifndef ARM_MATH_CM0 - - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix addition */ - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, saturate and then store the results in the destination buffer. */ - /* Read values from source A */ - inA1 = pIn1[0]; - - /* Read values from source B */ - inB1 = pIn2[0]; - - /* Read values from source A */ - inA2 = pIn1[1]; - - /* Add and saturate */ - out1 = __QADD(inA1, inB1); - - /* Read values from source B */ - inB2 = pIn2[1]; - - /* Read values from source A */ - inA1 = pIn1[2]; - - /* Add and saturate */ - out2 = __QADD(inA2, inB2); - - /* Read values from source B */ - inB1 = pIn2[2]; - - /* Store result in destination */ - pOut[0] = out1; - pOut[1] = out2; - - /* Read values from source A */ - inA2 = pIn1[3]; - - /* Read values from source B */ - inB2 = pIn2[3]; - - /* Add and saturate */ - out1 = __QADD(inA1, inB1); - out2 = __QADD(inA2, inB2); - - /* Store result in destination */ - pOut[2] = out1; - pOut[3] = out2; - - /* update pointers to process next sampels */ - pIn1 += 4u; - pIn2 += 4u; - pOut += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) + B(m,n) */ - /* Add, saturate and then store the results in the destination buffer. */ - inA1 = *pIn1++; - inB1 = *pIn2++; - - inA1 = __QADD(inA1, inB1); - - /* Decrement the loop counter */ - blkCnt--; - - *pOut++ = inA1; - - } - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixAdd group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c deleted file mode 100644 index 9ffc96ee3e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_f32.c +++ /dev/null @@ -1,86 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_f32.c -* -* Description: Floating-point matrix initialization. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInit Matrix Initialization - * - * Initializes the underlying matrix data structure. - * The functions set the numRows, - * numCols, and pData fields - * of the matrix data structure. - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - -/** - * @brief Floating-point matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_f32( - arm_matrix_instance_f32 * S, - uint16_t nRows, - uint16_t nColumns, - float32_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c deleted file mode 100644 index 2bada7feda..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q15.c +++ /dev/null @@ -1,78 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_q15.c -* -* Description: Q15 matrix initialization. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - - /** - * @brief Q15 matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_q15( - arm_matrix_instance_q15 * S, - uint16_t nRows, - uint16_t nColumns, - q15_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c deleted file mode 100644 index 8828c2d2ea..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_init_q31.c +++ /dev/null @@ -1,82 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_init_q31.c -* -* Description: Q31 matrix initialization. -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInit Matrix Initialization - * - */ - -/** - * @addtogroup MatrixInit - * @{ - */ - - /** - * @brief Q31 matrix initialization. - * @param[in,out] *S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] *pData points to the matrix data array. - * @return none - */ - -void arm_mat_init_q31( - arm_matrix_instance_q31 * S, - uint16_t nRows, - uint16_t nColumns, - q31_t * pData) -{ - /* Assign Number of Rows */ - S->numRows = nRows; - - /* Assign Number of Columns */ - S->numCols = nColumns; - - /* Assign Data pointer */ - S->pData = pData; -} - -/** - * @} end of MatrixInit group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c deleted file mode 100644 index f346916e0c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_inverse_f32.c +++ /dev/null @@ -1,668 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_inverse_f32.c -* -* Description: Floating-point matrix inverse. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixInv Matrix Inverse - * - * Computes the inverse of a matrix. - * - * The inverse is defined only if the input matrix is square and non-singular (the determinant - * is non-zero). The function checks that the input and output matrices are square and of the - * same size. - * - * Matrix inversion is numerically sensitive and the CMSIS DSP library only supports matrix - * inversion of floating-point matrices. - * - * \par Algorithm - * The Gauss-Jordan method is used to find the inverse. - * The algorithm performs a sequence of elementary row-operations till it - * reduces the input matrix to an identity matrix. Applying the same sequence - * of elementary row-operations to an identity matrix yields the inverse matrix. - * If the input matrix is singular, then the algorithm terminates and returns error status - * ARM_MATH_SINGULAR. - * \image html MatrixInverse.gif "Matrix Inverse of a 3 x 3 matrix using Gauss-Jordan Method" - */ - -/** - * @addtogroup MatrixInv - * @{ - */ - -/** - * @brief Floating-point matrix inverse. - * @param[in] *pSrc points to input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns - * ARM_MATH_SIZE_MISMATCH if the input matrix is not square or if the size - * of the output matrix does not match the size of the input matrix. - * If the input matrix is found to be singular (non-invertible), then the function returns - * ARM_MATH_SINGULAR. Otherwise, the function returns ARM_MATH_SUCCESS. - */ - -arm_status arm_mat_inverse_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *pInT1, *pInT2; /* Temporary input data matrix pointer */ - float32_t *pInT3, *pInT4; /* Temporary output data matrix pointer */ - float32_t *pPivotRowIn, *pPRT_in, *pPivotRowDst, *pPRT_pDst; /* Temporary input and output data matrix pointer */ - uint32_t numRows = pSrc->numRows; /* Number of rows in the matrix */ - uint32_t numCols = pSrc->numCols; /* Number of Cols in the matrix */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t Xchg, in = 0.0f, in1; /* Temporary input values */ - uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ - arm_status status; /* status of matrix inverse */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) - || (pSrc->numRows != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - - /*-------------------------------------------------------------------------------------------------------------- - * Matrix Inverse can be solved using elementary row operations. - * - * Gauss-Jordan Method: - * - * 1. First combine the identity matrix and the input matrix separated by a bar to form an - * augmented matrix as follows: - * _ _ _ _ - * | a11 a12 | 1 0 | | X11 X12 | - * | | | = | | - * |_ a21 a22 | 0 1 _| |_ X21 X21 _| - * - * 2. In our implementation, pDst Matrix is used as identity matrix. - * - * 3. Begin with the first row. Let i = 1. - * - * 4. Check to see if the pivot for row i is zero. - * The pivot is the element of the main diagonal that is on the current row. - * For instance, if working with row i, then the pivot element is aii. - * If the pivot is zero, exchange that row with a row below it that does not - * contain a zero in column i. If this is not possible, then an inverse - * to that matrix does not exist. - * - * 5. Divide every element of row i by the pivot. - * - * 6. For every row below and row i, replace that row with the sum of that row and - * a multiple of row i so that each new element in column i below row i is zero. - * - * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros - * for every element below and above the main diagonal. - * - * 8. Now an identical matrix is formed to the left of the bar(input matrix, pSrc). - * Therefore, the matrix to the right of the bar is our solution(pDst matrix, pDst). - *----------------------------------------------------------------------------------------------------------------*/ - - /* Working pointer for destination matrix */ - pInT2 = pOut; - - /* Loop over the number of rows */ - rowCnt = numRows; - - /* Making the destination matrix as identity matrix */ - while(rowCnt > 0u) - { - /* Writing all zeroes in lower triangle of the destination matrix */ - j = numRows - rowCnt; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Writing all ones in the diagonal of the destination matrix */ - *pInT2++ = 1.0f; - - /* Writing all zeroes in upper triangle of the destination matrix */ - j = rowCnt - 1u; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Decrement the loop counter */ - rowCnt--; - } - - /* Loop over the number of columns of the input matrix. - All the elements in each column are processed by the row operations */ - loopCnt = numCols; - - /* Index modifier to navigate through the columns */ - l = 0u; - - while(loopCnt > 0u) - { - /* Check if the pivot element is zero.. - * If it is zero then interchange the row with non zero row below. - * If there is no non zero element to replace in the rows below, - * then the matrix is Singular. */ - - /* Working pointer for the input matrix that points - * to the pivot element of the particular row */ - pInT1 = pIn + (l * numCols); - - /* Working pointer for the destination matrix that points - * to the pivot element of the particular row */ - pInT3 = pOut + (l * numCols); - - /* Temporary variable to hold the pivot value */ - in = *pInT1; - - /* Destination pointer modifier */ - k = 1u; - - /* Check if the pivot element is zero */ - if(*pInT1 == 0.0f) - { - /* Loop over the number rows present below */ - i = numRows - (l + 1u); - - while(i > 0u) - { - /* Update the input and destination pointers */ - pInT2 = pInT1 + (numCols * l); - pInT4 = pInT3 + (numCols * k); - - /* Check if there is a non zero pivot element to - * replace in the rows below */ - if(*pInT2 != 0.0f) - { - /* Loop over number of columns - * to the right of the pilot element */ - j = numCols - l; - - while(j > 0u) - { - /* Exchange the row elements of the input matrix */ - Xchg = *pInT2; - *pInT2++ = *pInT1; - *pInT1++ = Xchg; - - /* Decrement the loop counter */ - j--; - } - - /* Loop over number of columns of the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Exchange the row elements of the destination matrix */ - Xchg = *pInT4; - *pInT4++ = *pInT3; - *pInT3++ = Xchg; - - /* Decrement the loop counter */ - j--; - } - - /* Flag to indicate whether exchange is done or not */ - flag = 1u; - - /* Break after exchange is done */ - break; - } - - /* Update the destination pointer modifier */ - k++; - - /* Decrement the loop counter */ - i--; - } - } - - /* Update the status if the matrix is singular */ - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - - break; - } - - /* Points to the pivot row of input and destination matrices */ - pPivotRowIn = pIn + (l * numCols); - pPivotRowDst = pOut + (l * numCols); - - /* Temporary pointers to the pivot row pointers */ - pInT1 = pPivotRowIn; - pInT2 = pPivotRowDst; - - /* Pivot element of the row */ - in = *(pIn + (l * numCols)); - - /* Loop over number of columns - * to the right of the pilot element */ - j = (numCols - l); - - while(j > 0u) - { - /* Divide each element of the row of the input matrix - * by the pivot element */ - in1 = *pInT1; - *pInT1++ = in1 / in; - - /* Decrement the loop counter */ - j--; - } - - /* Loop over number of columns of the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Divide each element of the row of the destination matrix - * by the pivot element */ - in1 = *pInT2; - *pInT2++ = in1 / in; - - /* Decrement the loop counter */ - j--; - } - - /* Replace the rows with the sum of that row and a multiple of row i - * so that each new element in column i above row i is zero.*/ - - /* Temporary pointers for input and destination matrices */ - pInT1 = pIn; - pInT2 = pOut; - - /* index used to check for pivot element */ - i = 0u; - - /* Loop over number of rows */ - /* to be replaced by the sum of that row and a multiple of row i */ - k = numRows; - - while(k > 0u) - { - /* Check for the pivot element */ - if(i == l) - { - /* If the processing element is the pivot element, - only the columns to the right are to be processed */ - pInT1 += numCols - l; - - pInT2 += numCols; - } - else - { - /* Element of the reference row */ - in = *pInT1; - - /* Working pointers for input and destination pivot rows */ - pPRT_in = pPivotRowIn; - pPRT_pDst = pPivotRowDst; - - /* Loop over the number of columns to the right of the pivot element, - to replace the elements in the input matrix */ - j = (numCols - l); - - while(j > 0u) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - in1 = *pInT1; - *pInT1++ = in1 - (in * *pPRT_in++); - - /* Decrement the loop counter */ - j--; - } - - /* Loop over the number of columns to - replace the elements in the destination matrix */ - j = numCols; - - while(j > 0u) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - in1 = *pInT2; - *pInT2++ = in1 - (in * *pPRT_pDst++); - - /* Decrement the loop counter */ - j--; - } - - } - - /* Increment the temporary input pointer */ - pInT1 = pInT1 + l; - - /* Decrement the loop counter */ - k--; - - /* Increment the pivot index */ - i++; - } - - /* Increment the input pointer */ - pIn++; - - /* Decrement the loop counter */ - loopCnt--; - - /* Increment the index modifier */ - l++; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t Xchg, in = 0.0f; /* Temporary input values */ - uint32_t i, rowCnt, flag = 0u, j, loopCnt, k, l; /* loop counters */ - arm_status status; /* status of matrix inverse */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pSrc->numCols) || (pDst->numRows != pDst->numCols) - || (pSrc->numRows != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - { - - /*-------------------------------------------------------------------------------------------------------------- - * Matrix Inverse can be solved using elementary row operations. - * - * Gauss-Jordan Method: - * - * 1. First combine the identity matrix and the input matrix separated by a bar to form an - * augmented matrix as follows: - * _ _ _ _ _ _ _ _ - * | | a11 a12 | | | 1 0 | | | X11 X12 | - * | | | | | | | = | | - * |_ |_ a21 a22 _| | |_0 1 _| _| |_ X21 X21 _| - * - * 2. In our implementation, pDst Matrix is used as identity matrix. - * - * 3. Begin with the first row. Let i = 1. - * - * 4. Check to see if the pivot for row i is zero. - * The pivot is the element of the main diagonal that is on the current row. - * For instance, if working with row i, then the pivot element is aii. - * If the pivot is zero, exchange that row with a row below it that does not - * contain a zero in column i. If this is not possible, then an inverse - * to that matrix does not exist. - * - * 5. Divide every element of row i by the pivot. - * - * 6. For every row below and row i, replace that row with the sum of that row and - * a multiple of row i so that each new element in column i below row i is zero. - * - * 7. Move to the next row and column and repeat steps 2 through 5 until you have zeros - * for every element below and above the main diagonal. - * - * 8. Now an identical matrix is formed to the left of the bar(input matrix, src). - * Therefore, the matrix to the right of the bar is our solution(dst matrix, dst). - *----------------------------------------------------------------------------------------------------------------*/ - - /* Working pointer for destination matrix */ - pInT2 = pOut; - - /* Loop over the number of rows */ - rowCnt = numRows; - - /* Making the destination matrix as identity matrix */ - while(rowCnt > 0u) - { - /* Writing all zeroes in lower triangle of the destination matrix */ - j = numRows - rowCnt; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Writing all ones in the diagonal of the destination matrix */ - *pInT2++ = 1.0f; - - /* Writing all zeroes in upper triangle of the destination matrix */ - j = rowCnt - 1u; - while(j > 0u) - { - *pInT2++ = 0.0f; - j--; - } - - /* Decrement the loop counter */ - rowCnt--; - } - - /* Loop over the number of columns of the input matrix. - All the elements in each column are processed by the row operations */ - loopCnt = numCols; - - /* Index modifier to navigate through the columns */ - l = 0u; - //for(loopCnt = 0u; loopCnt < numCols; loopCnt++) - while(loopCnt > 0u) - { - /* Check if the pivot element is zero.. - * If it is zero then interchange the row with non zero row below. - * If there is no non zero element to replace in the rows below, - * then the matrix is Singular. */ - - /* Working pointer for the input matrix that points - * to the pivot element of the particular row */ - pInT1 = pIn + (l * numCols); - - /* Working pointer for the destination matrix that points - * to the pivot element of the particular row */ - pInT3 = pOut + (l * numCols); - - /* Temporary variable to hold the pivot value */ - in = *pInT1; - - /* Destination pointer modifier */ - k = 1u; - - /* Check if the pivot element is zero */ - if(*pInT1 == 0.0f) - { - /* Loop over the number rows present below */ - for (i = (l + 1u); i < numRows; i++) - { - /* Update the input and destination pointers */ - pInT2 = pInT1 + (numCols * l); - pInT4 = pInT3 + (numCols * k); - - /* Check if there is a non zero pivot element to - * replace in the rows below */ - if(*pInT2 != 0.0f) - { - /* Loop over number of columns - * to the right of the pilot element */ - for (j = 0u; j < (numCols - l); j++) - { - /* Exchange the row elements of the input matrix */ - Xchg = *pInT2; - *pInT2++ = *pInT1; - *pInT1++ = Xchg; - } - - for (j = 0u; j < numCols; j++) - { - Xchg = *pInT4; - *pInT4++ = *pInT3; - *pInT3++ = Xchg; - } - - /* Flag to indicate whether exchange is done or not */ - flag = 1u; - - /* Break after exchange is done */ - break; - } - - /* Update the destination pointer modifier */ - k++; - } - } - - /* Update the status if the matrix is singular */ - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - - break; - } - - /* Points to the pivot row of input and destination matrices */ - pPivotRowIn = pIn + (l * numCols); - pPivotRowDst = pOut + (l * numCols); - - /* Temporary pointers to the pivot row pointers */ - pInT1 = pPivotRowIn; - pInT2 = pPivotRowDst; - - /* Pivot element of the row */ - in = *(pIn + (l * numCols)); - - /* Loop over number of columns - * to the right of the pilot element */ - for (j = 0u; j < (numCols - l); j++) - { - /* Divide each element of the row of the input matrix - * by the pivot element */ - *pInT1++ = *pInT1 / in; - } - for (j = 0u; j < numCols; j++) - { - /* Divide each element of the row of the destination matrix - * by the pivot element */ - *pInT2++ = *pInT2 / in; - } - - /* Replace the rows with the sum of that row and a multiple of row i - * so that each new element in column i above row i is zero.*/ - - /* Temporary pointers for input and destination matrices */ - pInT1 = pIn; - pInT2 = pOut; - - for (i = 0u; i < numRows; i++) - { - /* Check for the pivot element */ - if(i == l) - { - /* If the processing element is the pivot element, - only the columns to the right are to be processed */ - pInT1 += numCols - l; - pInT2 += numCols; - } - else - { - /* Element of the reference row */ - in = *pInT1; - - /* Working pointers for input and destination pivot rows */ - pPRT_in = pPivotRowIn; - pPRT_pDst = pPivotRowDst; - - /* Loop over the number of columns to the right of the pivot element, - to replace the elements in the input matrix */ - for (j = 0u; j < (numCols - l); j++) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - *pInT1++ = *pInT1 - (in * *pPRT_in++); - } - /* Loop over the number of columns to - replace the elements in the destination matrix */ - for (j = 0u; j < numCols; j++) - { - /* Replace the element by the sum of that row - and a multiple of the reference row */ - *pInT2++ = *pInT2 - (in * *pPRT_pDst++); - } - - } - /* Increment the temporary input pointer */ - pInT1 = pInT1 + l; - } - /* Increment the input pointer */ - pIn++; - - /* Decrement the loop counter */ - loopCnt--; - /* Increment the index modifier */ - l++; - } - - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - - if((flag != 1u) && (in == 0.0f)) - { - status = ARM_MATH_SINGULAR; - } - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixInv group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c deleted file mode 100644 index a2f513628e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_f32.c +++ /dev/null @@ -1,284 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_f32.c -* -* Description: Floating-point matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixMult Matrix Multiplication - * - * Multiplies two matrices. - * - * \image html MatrixMultiplication.gif "Multiplication of two 3 x 3 matrices" - - * Matrix multiplication is only defined if the number of columns of the - * first matrix equals the number of rows of the second matrix. - * Multiplying an M x N matrix with an N x P matrix results - * in an M x P matrix. - * When matrix size checking is enabled, the functions check: (1) that the inner dimensions of - * pSrcA and pSrcB are equal; and (2) that the size of the output - * matrix equals the outer dimensions of pSrcA and pSrcB. - */ - - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Floating-point matrix multiplication. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *px; /* Temporary output data matrix pointer */ - float32_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t in1, in2, in3, in4; - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0.0f; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2u; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - in3 = *pIn2; - pIn2 += numColsB; - in1 = pIn1[0]; - in2 = pIn1[1]; - sum += in1 * in3; - in4 = *pIn2; - pIn2 += numColsB; - sum += in2 * in4; - - in3 = *pIn2; - pIn2 += numColsB; - in1 = pIn1[2]; - in2 = pIn1[3]; - sum += in1 * in3; - in4 = *pIn2; - pIn2 += numColsB; - sum += in2 * in4; - pIn1 += 4u; - - /* Decrement the loop count */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining MACs here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Store the result in the destination buffer */ - *px++ = sum; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = pSrcB->pData + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pInA with each column in pInB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0.0f; - - /* Initialize the pointer pIn1 to point to the starting address of the row being processed */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pIn1++ * (*pIn2); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Store the result in the destination buffer */ - *px++ = sum; - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c deleted file mode 100644 index a88e3cdd1a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q15.c +++ /dev/null @@ -1,361 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_fast_q15.c -* -* Description: Q15 matrix multiplication (fast variant) -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - - -/** - * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @param[in] *pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The difference between the function arm_mat_mult_q15() and this fast variant is that - * the fast variant use a 32-bit rather than a 64-bit accumulator. - * The result of each 1.15 x 1.15 multiplication is truncated to - * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 - * format. Finally, the accumulator is saturated and converted to a 1.15 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides - * less precision since it discards the low 16 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down one of the input matrices by log2(numColsA) bits to - * avoid overflows, as a total of numColsA additions are computed internally for each - * output element. - * - * \par - * See arm_mat_mult_q15() for a slower implementation of this function - * which uses 64-bit accumulation to provide higher precision. - */ - -arm_status arm_mat_mult_fast_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState) -{ - q31_t sum; /* accumulator */ - q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - q31_t in; /* Temporary variable to hold the input value */ - q31_t inA1, inA2, inB1, inB2; - -#else - - q15_t in; /* Temporary variable to hold the input value */ - q15_t inA1, inA2, inB1, inB2; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif - { - /* Matrix transpose */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - col = numColsB >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pSrcBT + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { -#ifndef UNALIGNED_SUPPORT_DISABLE - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - -#else - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - col = numColsB % 0x4u; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pInB++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* Reset the variables for the usage in the following multiplication process */ - row = numRowsA; - i = 0u; - px = pDst->pData; - - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the transposed pSrcB data */ - pInB = pSrcBT; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Apply loop unrolling and compute 2 MACs simultaneously. */ - colCnt = numColsA >> 2; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pInA = pSrcA->pData + i; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - inA1 = *__SIMD32(pInA)++; - inB1 = *__SIMD32(pInB)++; - inA2 = *__SIMD32(pInA)++; - inB2 = *__SIMD32(pInB)++; - - sum = __SMLAD(inA1, inB1, sum); - sum = __SMLAD(inA2, inB2, sum); - -#else - - inA1 = *pInA++; - inB1 = *pInB++; - inA2 = *pInA++; - sum += inA1 * inB1; - inB2 = *pInB++; - - inA1 = *pInA++; - inB1 = *pInB++; - sum += inA2 * inB2; - inA2 = *pInA++; - inB2 = *pInB++; - - sum += inA1 * inB1; - sum += inA2 * inB2; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - colCnt--; - } - - /* process odd column samples */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += (q31_t) (*pInA++) * (*pInB++); - - colCnt--; - } - - /* Saturate and store the result in the destination buffer */ - *px = (q15_t) (sum >> 15); - px++; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - i = i + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c deleted file mode 100644 index 7fdbb1cb89..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_fast_q31.c +++ /dev/null @@ -1,218 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_fast_q31.c -* -* Description: Q31 matrix multiplication (fast variant). -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The difference between the function arm_mat_mult_q31() and this fast variant is that - * the fast variant use a 32-bit rather than a 64-bit accumulator. - * The result of each 1.31 x 1.31 multiplication is truncated to - * 2.30 format. These intermediate results are accumulated in a 32-bit register in 2.30 - * format. Finally, the accumulator is saturated and converted to a 1.31 result. - * - * \par - * The fast version has the same overflow behavior as the standard version but provides - * less precision since it discards the low 32 bits of each multiplication result. - * In order to avoid overflows completely the input signals must be scaled down. - * Scale down one of the input matrices by log2(numColsA) bits to - * avoid overflows, as a total of numColsA additions are computed internally for each - * output element. - * - * \par - * See arm_mat_mult_q31() for a slower implementation of this function - * which uses 64-bit accumulation to provide higher precision. - */ - -arm_status arm_mat_mult_fast_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ -// q31_t *pSrcB = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - q31_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - q31_t inA1, inA2, inA3, inA4, inB1, inB2, inB3, inB4; - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2; - - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - inB1 = *pIn2; - pIn2 += numColsB; - - inA1 = pIn1[0]; - inA2 = pIn1[1]; - - inB2 = *pIn2; - pIn2 += numColsB; - - inB3 = *pIn2; - pIn2 += numColsB; - - sum = (q31_t) ((((q63_t) sum << 32) + ((q63_t) inA1 * inB1)) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + ((q63_t) inA2 * inB2)) >> 32); - - inA3 = pIn1[2]; - inA4 = pIn1[3]; - - inB4 = *pIn2; - pIn2 += numColsB; - - sum = (q31_t) ((((q63_t) sum << 32) + ((q63_t) inA3 * inB3)) >> 32); - sum = (q31_t) ((((q63_t) sum << 32) + ((q63_t) inA4 * inB4)) >> 32); - - pIn1 += 4u; - - /* Decrement the loop counter */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum = (q31_t) ((((q63_t) sum << 32) + - ((q63_t) * pIn1++ * (*pIn2))) >> 32); - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.30 to 1.31 format and store in destination buffer */ - *px++ = sum << 1; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = pSrcB->pData + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c deleted file mode 100644 index b48d204ed5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q15.c +++ /dev/null @@ -1,467 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_q15.c -* -* Description: Q15 matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - - -/** - * @brief Q15 matrix multiplication - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @param[in] *pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. The inputs to the - * multiplications are in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate - * results are accumulated in a 64-bit accumulator in 34.30 format. This approach - * provides 33 guard bits and there is no risk of overflow. The 34.30 result is then - * truncated to 34.15 format by discarding the low 15 bits and then saturated to - * 1.15 format. - * - * \par - * Refer to arm_mat_mult_fast_q15() for a faster but less precise version of this function for Cortex-M3 and Cortex-M4. - * - */ - -arm_status arm_mat_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState) -{ - q63_t sum; /* accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q15_t *pSrcBT = pState; /* input data matrix pointer for transpose */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsB = pSrcB->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsB, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifndef UNALIGNED_SUPPORT_DISABLE - - q31_t in; /* Temporary variable to hold the input value */ - q31_t pSourceA1, pSourceB1, pSourceA2, pSourceB2; - -#else - - q15_t in; /* Temporary variable to hold the input value */ - q15_t inA1, inB1, inA2, inB2; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - { - /* Matrix transpose */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - col = numColsB >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pSrcBT + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read two elements from the row */ - in = *__SIMD32(pInB)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) in; - -#else - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *px = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *px = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - -#else - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Read one element from the row */ - in = *pInB++; - - /* Store one element in the destination */ - *px = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the column loop counter */ - col--; - } - - /* If the columns of pSrcB is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - col = numColsB % 0x4u; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pInB++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += numRowsB; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* Reset the variables for the usage in the following multiplication process */ - row = numRowsA; - i = 0u; - px = pDst->pData; - - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the transposed pSrcB data */ - pInB = pSrcBT; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Apply loop unrolling and compute 2 MACs simultaneously. */ - colCnt = numColsA >> 2; - - /* Initiate the pointer pIn1 to point to the starting address of the column being processed */ - pInA = pSrcA->pData + i; - - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* read real and imag values from pSrcA and pSrcB buffer */ - pSourceA1 = *__SIMD32(pInA)++; - pSourceB1 = *__SIMD32(pInB)++; - - pSourceA2 = *__SIMD32(pInA)++; - pSourceB2 = *__SIMD32(pInB)++; - - /* Multiply and Accumlates */ - sum = __SMLALD(pSourceA1, pSourceB1, sum); - sum = __SMLALD(pSourceA2, pSourceB2, sum); - -#else - /* read real and imag values from pSrcA and pSrcB buffer */ - inA1 = *pInA++; - inB1 = *pInB++; - inA2 = *pInA++; - /* Multiply and Accumlates */ - sum += inA1 * inB1; - inB2 = *pInB++; - - inA1 = *pInA++; - inB1 = *pInB++; - /* Multiply and Accumlates */ - sum += inA2 * inB2; - inA2 = *pInA++; - inB2 = *pInB++; - - /* Multiply and Accumlates */ - sum += inA1 * inB1; - sum += inA2 * inB2; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Decrement the loop counter */ - colCnt--; - } - - /* process remaining column samples */ - colCnt = numColsA & 3u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - sum += *pInA++ * *pInB++; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Saturate and store the result in the destination buffer */ - *px = (q15_t) (__SSAT((sum >> 15), 16)); - px++; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - - i = i + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A of Q15 type */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B of Q15 type */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - q15_t *px; /* Temporary output data matrix pointer */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pSrcA */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q31_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 34.30 to 1.15 format and store the saturated value in destination buffer */ - /* Saturate and store the result in the destination buffer */ - *px++ = (q15_t) __SSAT((sum >> 15), 16); - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - - /* Update the pointer pSrcA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c deleted file mode 100644 index eb76522042..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_mult_q31.c +++ /dev/null @@ -1,292 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_mult_q31.c -* -* Description: Q31 matrix multiplication. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixMult - * @{ - */ - -/** - * @brief Q31 matrix multiplication - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate - * multiplication results but provides only a single guard bit. There is no saturation - * on intermediate additions. Thus, if the accumulator overflows it wraps around and - * distorts the result. The input signals should be scaled down to avoid intermediate - * overflows. The input is thus scaled down by log2(numColsA) bits - * to avoid overflows, as a total of numColsA additions are performed internally. - * The 2.62 accumulator is right shifted by 31 bits and saturated to 1.31 format to yield the final result. - * - * \par - * See arm_mat_mult_fast_q31() for a faster but less precise implementation of this function for Cortex-M3 and Cortex-M4. - * - */ - -arm_status arm_mat_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - q63_t sum; /* Accumulator */ - uint16_t numRowsA = pSrcA->numRows; /* number of rows of input matrix A */ - uint16_t numColsB = pSrcB->numCols; /* number of columns of input matrix B */ - uint16_t numColsA = pSrcA->numCols; /* number of columns of input matrix A */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t col, i = 0u, j, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - q31_t a0, a1, a2, a3, b0, b1, b2, b3; - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - j = 0u; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Apply loop unrolling and compute 4 MACs simultaneously. */ - colCnt = numColsA >> 2; - - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - b0 = *pIn2; - pIn2 += numColsB; - - a0 = *pIn1++; - a1 = *pIn1++; - - b1 = *pIn2; - pIn2 += numColsB; - b2 = *pIn2; - pIn2 += numColsB; - - sum += (q63_t) a0 *b0; - sum += (q63_t) a1 *b1; - - a2 = *pIn1++; - a3 = *pIn1++; - - b3 = *pIn2; - pIn2 += numColsB; - - sum += (q63_t) a2 *b2; - sum += (q63_t) a3 *b3; - - /* Decrement the loop counter */ - colCnt--; - } - - /* If the columns of pSrcA is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - colCnt = numColsA % 0x4u; - - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ - *px++ = (q31_t) (sum >> 31); - - /* Update the pointer pIn2 to point to the starting address of the next column */ - j++; - pIn2 = (pSrcB->pData) + j; - - /* Decrement the column loop counter */ - col--; - - } while(col > 0u); - -#else - - /* Run the below code for Cortex-M0 */ - - q31_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - uint16_t col, i = 0u, row = numRowsA, colCnt; /* loop counters */ - arm_status status; /* status of matrix multiplication */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrcA->numCols != pSrcB->numRows) || - (pSrcA->numRows != pDst->numRows) || (pSrcB->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* The following loop performs the dot-product of each row in pSrcA with each column in pSrcB */ - /* row loop */ - do - { - /* Output pointer is set to starting address of the row being processed */ - px = pOut + i; - - /* For every row wise process, the column loop counter is to be initiated */ - col = numColsB; - - /* For every row wise process, the pIn2 pointer is set - ** to the starting address of the pSrcB data */ - pIn2 = pSrcB->pData; - - /* column loop */ - do - { - /* Set the variable sum, that acts as accumulator, to zero */ - sum = 0; - - /* Initiate the pointer pIn1 to point to the starting address of pInA */ - pIn1 = pInA; - - /* Matrix A columns number of MAC operations are to be performed */ - colCnt = numColsA; - - /* matrix multiplication */ - while(colCnt > 0u) - { - /* c(m,n) = a(1,1)*b(1,1) + a(1,2) * b(2,1) + .... + a(m,p)*b(p,n) */ - /* Perform the multiply-accumulates */ - sum += (q63_t) * pIn1++ * *pIn2; - pIn2 += numColsB; - - /* Decrement the loop counter */ - colCnt--; - } - - /* Convert the result from 2.62 to 1.31 format and store in destination buffer */ - *px++ = (q31_t) (sum >> 31); - - /* Decrement the column loop counter */ - col--; - - /* Update the pointer pIn2 to point to the starting address of the next column */ - pIn2 = pInB + (numColsB - col); - - } while(col > 0u); - -#endif - - /* Update the pointer pInA to point to the starting address of the next row */ - i = i + numColsB; - pInA = pInA + numColsA; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixMult group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c deleted file mode 100644 index e64cfd1d12..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_f32.c +++ /dev/null @@ -1,179 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_f32.c -* -* Description: Multiplies a floating-point matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixScale Matrix Scale - * - * Multiplies a matrix by a scalar. This is accomplished by multiplying each element in the - * matrix by the scalar. For example: - * \image html MatrixScale.gif "Matrix Scaling of a 3 x 3 matrix" - * - * The function checks to make sure that the input and output matrices are of the same size. - * - * In the fixed-point Q15 and Q31 functions, scale is represented by - * a fractional multiplication scaleFract and an arithmetic shift shift. - * The shift allows the gain of the scaling operation to exceed 1.0. - * The overall scale factor applied to the fixed-point data is - *
        
- *     scale = scaleFract * 2^shift.        
- * 
- */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Floating-point matrix scaling. - * @param[in] *pSrc points to input matrix structure - * @param[in] scale scale factor to be applied - * @param[out] *pDst points to output matrix structure - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - * - */ - -arm_status arm_mat_scale_f32( - const arm_matrix_instance_f32 * pSrc, - float32_t scale, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - -#ifndef ARM_MATH_CM0 - - float32_t in1, in2, in3, in4; /* temporary variables */ - float32_t out1, out2, out3, out4; /* temporary variables */ - -#endif // #ifndef ARM_MATH_CM0 - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * scale */ - /* Scaling and results are stored in the destination buffer. */ - in1 = pIn[0]; - in2 = pIn[1]; - in3 = pIn[2]; - in4 = pIn[3]; - - out1 = in1 * scale; - out2 = in2 * scale; - out3 = in3 * scale; - out4 = in4 * scale; - - - pOut[0] = out1; - pOut[1] = out2; - pOut[2] = out3; - pOut[3] = out4; - - /* update pointers to process next sampels */ - pIn += 4u; - pOut += 4u; - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * scale */ - /* The results are stored in the destination buffer. */ - *pOut++ = (*pIn++) * scale; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c deleted file mode 100644 index 58011254c8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q15.c +++ /dev/null @@ -1,181 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_q15.c -* -* Description: Multiplies a Q15 matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Q15 matrix scaling. - * @param[in] *pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.15 format. - * These are multiplied to yield a 2.30 intermediate result and this is shifted with saturation to 1.15 format. - */ - -arm_status arm_mat_scale_q15( - const arm_matrix_instance_q15 * pSrc, - q15_t scaleFract, - int32_t shift, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pIn = pSrc->pData; /* input data matrix pointer */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - int32_t totShift = 15 - shift; /* total shift to apply after scaling */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - -#ifndef ARM_MATH_CM0 - - q15_t in1, in2, in3, in4; - q31_t out1, out2, out3, out4; - q31_t inA1, inA2; - -#endif // #ifndef ARM_MATH_CM0 - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif // #ifdef ARM_MATH_MATRIX_CHECK - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - /* Loop Unrolling */ - blkCnt = numSamples >> 2; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - /* Reading 2 inputs from memory */ - inA1 = _SIMD32_OFFSET(pIn); - inA2 = _SIMD32_OFFSET(pIn + 2); - - /* C = A * scale */ - /* Scale the inputs and then store the 2 results in the destination buffer - * in single cycle by packing the outputs */ - out1 = (q31_t) ((q15_t) (inA1 >> 16) * scaleFract); - out2 = (q31_t) ((q15_t) inA1 * scaleFract); - out3 = (q31_t) ((q15_t) (inA2 >> 16) * scaleFract); - out4 = (q31_t) ((q15_t) inA2 * scaleFract); - - out1 = out1 >> totShift; - inA1 = _SIMD32_OFFSET(pIn + 4); - out2 = out2 >> totShift; - inA2 = _SIMD32_OFFSET(pIn + 6); - out3 = out3 >> totShift; - out4 = out4 >> totShift; - - in1 = (q15_t) (__SSAT(out1, 16)); - in2 = (q15_t) (__SSAT(out2, 16)); - in3 = (q15_t) (__SSAT(out3, 16)); - in4 = (q15_t) (__SSAT(out4, 16)); - - _SIMD32_OFFSET(pOut) = __PKHBT(in2, in1, 16); - _SIMD32_OFFSET(pOut + 2) = __PKHBT(in4, in3, 16); - - /* update pointers to process next sampels */ - pIn += 4u; - pOut += 4u; - - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - *pOut++ = - (q15_t) (__SSAT(((q31_t) (*pIn++) * scaleFract) >> totShift, 16)); - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c deleted file mode 100644 index e5e1241254..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_scale_q31.c +++ /dev/null @@ -1,201 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_scale_q31.c -* -* Description: Multiplies a Q31 matrix by a scalar. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixScale - * @{ - */ - -/** - * @brief Q31 matrix scaling. - * @param[in] *pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The input data *pSrc and scaleFract are in 1.31 format. - * These are multiplied to yield a 2.62 intermediate result and this is shifted with saturation to 1.31 format. - */ - -arm_status arm_mat_scale_q31( - const arm_matrix_instance_q31 * pSrc, - q31_t scaleFract, - int32_t shift, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn = pSrc->pData; /* input data matrix pointer */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - int32_t totShift = shift + 1; /* shift to apply after scaling */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix scaling */ - q31_t in1, in2, out1; /* temporary variabels */ - -#ifndef ARM_MATH_CM0 - - q31_t in3, in4, out2, out3, out4; /* temporary variables */ - -#endif // #ifndef ARM_MAT_CM0 - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch */ - if((pSrc->numRows != pDst->numRows) || (pSrc->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif // #ifdef ARM_MATH_MATRIX_CHECK - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrc->numRows * pSrc->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Read values from input */ - in1 = *pIn; - in2 = *(pIn + 1); - in3 = *(pIn + 2); - in4 = *(pIn + 3); - - /* multiply input with scaler value */ - in1 = ((q63_t) in1 * scaleFract) >> 32; - in2 = ((q63_t) in2 * scaleFract) >> 32; - in3 = ((q63_t) in3 * scaleFract) >> 32; - in4 = ((q63_t) in4 * scaleFract) >> 32; - - /* apply shifting */ - out1 = in1 << totShift; - out2 = in2 << totShift; - - /* saturate the results. */ - if(in1 != (out1 >> totShift)) - out1 = 0x7FFFFFFF ^ (in1 >> 31); - - if(in2 != (out2 >> totShift)) - out2 = 0x7FFFFFFF ^ (in2 >> 31); - - out3 = in3 << totShift; - out4 = in4 << totShift; - - *pOut = out1; - *(pOut + 1) = out2; - - if(in3 != (out3 >> totShift)) - out3 = 0x7FFFFFFF ^ (in3 >> 31); - - if(in4 != (out4 >> totShift)) - out4 = 0x7FFFFFFF ^ (in4 >> 31); - - - *(pOut + 2) = out3; - *(pOut + 3) = out4; - - /* update pointers to process next sampels */ - pIn += 4u; - pOut += 4u; - - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) * k */ - /* Scale, saturate and then store the results in the destination buffer. */ - in1 = *pIn++; - - in2 = ((q63_t) in1 * scaleFract) >> 32; - - out1 = in2 << totShift; - - if(in2 != (out1 >> totShift)) - out1 = 0x7FFFFFFF ^ (in2 >> 31); - - *pOut++ = out1; - - /* Decrement the numSamples loop counter */ - blkCnt--; - } - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixScale group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c deleted file mode 100644 index 3544d8e825..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_f32.c +++ /dev/null @@ -1,207 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_f32.c -* -* Description: Floating-point matrix subtraction. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @defgroup MatrixSub Matrix Subtraction - * - * Subtract two matrices. - * \image html MatrixSubtraction.gif "Subraction of two 3 x 3 matrices" - * - * The functions check to make sure that - * pSrcA, pSrcB, and pDst have the same - * number of rows and columns. - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Floating-point matrix subtraction - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_sub_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - float32_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - -#ifndef ARM_MATH_CM0 - - float32_t inA1, inA2, inB1, inB2, out1, out2; /* temporary variables */ - -#endif // #ifndef ARM_MATH_CM0 - - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - /* Read values from source A */ - inA1 = pIn1[0]; - - /* Read values from source B */ - inB1 = pIn2[0]; - - /* Read values from source A */ - inA2 = pIn1[1]; - - /* out = sourceA - sourceB */ - out1 = inA1 - inB1; - - /* Read values from source B */ - inB2 = pIn2[1]; - - /* Read values from source A */ - inA1 = pIn1[2]; - - /* out = sourceA - sourceB */ - out2 = inA2 - inB2; - - /* Read values from source B */ - inB1 = pIn2[2]; - - /* Store result in destination */ - pOut[0] = out1; - pOut[1] = out2; - - /* Read values from source A */ - inA2 = pIn1[3]; - - /* Read values from source B */ - inB2 = pIn2[3]; - - /* out = sourceA - sourceB */ - out1 = inA1 - inB1; - - - /* out = sourceA - sourceB */ - out2 = inA2 - inB2; - - /* Store result in destination */ - pOut[2] = out1; - - /* Store result in destination */ - pOut[3] = out2; - - - /* update pointers to process next sampels */ - pIn1 += 4u; - pIn2 += 4u; - pOut += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (*pIn1++) - (*pIn2++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c deleted file mode 100644 index 1857fd837c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q15.c +++ /dev/null @@ -1,158 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_q15.c -* -* Description: Q15 Matrix subtraction -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Q15 matrix subtraction. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - */ - -arm_status arm_mat_sub_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pInA = pSrcA->pData; /* input data matrix pointer A */ - q15_t *pInB = pSrcB->pData; /* input data matrix pointer B */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Apply loop unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, Saturate and then store the results in the destination buffer. */ - *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - *__SIMD32(pOut)++ = __QSUB16(*__SIMD32(pInA)++, *__SIMD32(pInB)++); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __QSUB16(*pInA++, *pInB++); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract and then store the results in the destination buffer. */ - *pOut++ = (q15_t) __SSAT(((q31_t) * pInA++ - *pInB++), 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c deleted file mode 100644 index 279fd7f7c1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_sub_q31.c +++ /dev/null @@ -1,206 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_sub_q31.c -* -* Description: Q31 matrix subtraction -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixSub - * @{ - */ - -/** - * @brief Q31 matrix subtraction. - * @param[in] *pSrcA points to the first input matrix structure - * @param[in] *pSrcB points to the second input matrix structure - * @param[out] *pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - * - * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range [0x80000000 0x7FFFFFFF] will be saturated. - */ - - -arm_status arm_mat_sub_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn1 = pSrcA->pData; /* input data matrix pointer A */ - q31_t *pIn2 = pSrcB->pData; /* input data matrix pointer B */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t inA1, inB1; /* temporary variables */ - -#ifndef ARM_MATH_CM0 - - q31_t inA2, inB2; /* temporary variables */ - q31_t out1, out2; /* temporary variables */ - -#endif // #ifndef ARM_MATH_CM0 - - uint32_t numSamples; /* total number of elements in the matrix */ - uint32_t blkCnt; /* loop counters */ - arm_status status; /* status of matrix subtraction */ - - -#ifdef ARM_MATH_MATRIX_CHECK - /* Check for matrix mismatch condition */ - if((pSrcA->numRows != pSrcB->numRows) || - (pSrcA->numCols != pSrcB->numCols) || - (pSrcA->numRows != pDst->numRows) || (pSrcA->numCols != pDst->numCols)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif - { - /* Total number of samples in the input matrix */ - numSamples = (uint32_t) pSrcA->numRows * pSrcA->numCols; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Loop Unrolling */ - blkCnt = numSamples >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, saturate and then store the results in the destination buffer. */ - /* Read values from source A */ - inA1 = pIn1[0]; - - /* Read values from source B */ - inB1 = pIn2[0]; - - /* Read values from source A */ - inA2 = pIn1[1]; - - /* Subtract and saturate */ - out1 = __QSUB(inA1, inB1); - - /* Read values from source B */ - inB2 = pIn2[1]; - - /* Read values from source A */ - inA1 = pIn1[2]; - - /* Subtract and saturate */ - out2 = __QSUB(inA2, inB2); - - /* Read values from source B */ - inB1 = pIn2[2]; - - /* Store result in destination */ - pOut[0] = out1; - pOut[1] = out2; - - /* Read values from source A */ - inA2 = pIn1[3]; - - /* Read values from source B */ - inB2 = pIn2[3]; - - /* Subtract and saturate */ - out1 = __QSUB(inA1, inB1); - - /* Subtract and saturate */ - out2 = __QSUB(inA2, inB2); - - /* Store result in destination */ - pOut[2] = out1; - pOut[3] = out2; - - /* update pointers to process next samples */ - pIn1 += 4u; - pIn2 += 4u; - pOut += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the numSamples is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = numSamples % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initialize blkCnt with number of samples */ - blkCnt = numSamples; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C(m,n) = A(m,n) - B(m,n) */ - /* Subtract, saturate and then store the results in the destination buffer. */ - inA1 = *pIn1++; - inB1 = *pIn2++; - - inA1 = __QSUB(inA1, inB1); - - *pOut++ = inA1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixSub group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c deleted file mode 100644 index 235028f5ab..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_f32.c +++ /dev/null @@ -1,216 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_f32.c -* -* Description: Floating-point matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -/** - * @defgroup MatrixTrans Matrix Transpose - * - * Tranposes a matrix. - * Transposing an M x N matrix flips it around the center diagonal and results in an N x M matrix. - * \image html MatrixTranspose.gif "Transpose of a 3 x 3 matrix" - */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/** - * @brief Floating-point matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - - -arm_status arm_mat_trans_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst) -{ - float32_t *pIn = pSrc->pData; /* input data matrix pointer */ - float32_t *pOut = pDst->pData; /* output data matrix pointer */ - float32_t *px; /* Temporary output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of rows */ - uint16_t nColumns = pSrc->numCols; /* number of columns */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* Loop Unrolling */ - blkCnt = nColumns >> 2; - - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) /* column loop */ - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - - /* Perform matrix transpose for last 3 samples here. */ - blkCnt = nColumns % 0x4u; - - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - uint16_t col, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* Initialize column loop counter */ - col = nColumns; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - col--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); /* row loop end */ - - /* Set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c deleted file mode 100644 index be9c78e003..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q15.c +++ /dev/null @@ -1,282 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_q15.c -* -* Description: Q15 matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/* - * @brief Q15 matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_trans_q15( - const arm_matrix_instance_q15 * pSrc, - arm_matrix_instance_q15 * pDst) -{ - q15_t *pSrcA = pSrc->pData; /* input data matrix pointer */ - q15_t *pOut = pDst->pData; /* output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of nRows */ - uint16_t nColumns = pSrc->numCols; /* number of nColumns */ - uint16_t col, row = nRows, i = 0u; /* row and column loop counters */ - arm_status status; /* status of matrix transpose */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ -#ifndef UNALIGNED_SUPPORT_DISABLE - - q31_t in; /* variable to hold temporary output */ - -#else - - q15_t in; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - - /* Apply loop unrolling and exchange the columns with row elements */ - col = nColumns >> 2u; - - /* The pointer pOut is set to starting address of the column being processed */ - pOut = pDst->pData + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(col > 0u) - { -#ifndef UNALIGNED_SUPPORT_DISABLE - - /* Read two elements from the row */ - in = *__SIMD32(pSrcA)++; - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) in; - -#else - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Unpack and store the second element in the destination */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *pOut = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Read two elements from the row */ -#ifndef ARM_MATH_BIG_ENDIAN - - in = *__SIMD32(pSrcA)++; - -#else - - in = *__SIMD32(pSrcA)++; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Unpack and store one element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) in; - -#else - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Unpack and store the second element in the destination */ -#ifndef ARM_MATH_BIG_ENDIAN - - *pOut = (q15_t) ((in & (q31_t) 0xffff0000) >> 16); - -#else - - *pOut = (q15_t) in; - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - -#else - /* Read one element from the row */ - in = *pSrcA++; - - /* Store one element in the destination */ - *pOut = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Read one element from the row */ - in = *pSrcA++; - - /* Store one element in the destination */ - *pOut = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Read one element from the row */ - in = *pSrcA++; - - /* Store one element in the destination */ - *pOut = in; - - /* Update the pointer px to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Read one element from the row */ - in = *pSrcA++; - - /* Store one element in the destination */ - *pOut = in; - -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Decrement the column loop counter */ - col--; - } - - /* Perform matrix transpose for last 3 samples here. */ - col = nColumns % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer pOut is set to starting address of the column being processed */ - pOut = pDst->pData + i; - - /* Initialize column loop counter */ - col = nColumns; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *pOut = *pSrcA++; - - /* Update the pointer pOut to point to the next row of the transposed matrix */ - pOut += nRows; - - /* Decrement the column loop counter */ - col--; - } - - i++; - - /* Decrement the row loop counter */ - row--; - - } while(row > 0u); - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c deleted file mode 100644 index 253a923d1c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/MatrixFunctions/arm_mat_trans_q31.c +++ /dev/null @@ -1,208 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mat_trans_q31.c -* -* Description: Q31 matrix transpose. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupMatrix - */ - -/** - * @addtogroup MatrixTrans - * @{ - */ - -/* - * @brief Q31 matrix transpose. - * @param[in] *pSrc points to the input matrix - * @param[out] *pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - -arm_status arm_mat_trans_q31( - const arm_matrix_instance_q31 * pSrc, - arm_matrix_instance_q31 * pDst) -{ - q31_t *pIn = pSrc->pData; /* input data matrix pointer */ - q31_t *pOut = pDst->pData; /* output data matrix pointer */ - q31_t *px; /* Temporary output data matrix pointer */ - uint16_t nRows = pSrc->numRows; /* number of nRows */ - uint16_t nColumns = pSrc->numCols; /* number of nColumns */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - uint16_t blkCnt, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* Apply loop unrolling and exchange the columns with row elements */ - blkCnt = nColumns >> 2u; - - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - - /* Perform matrix transpose for last 3 samples here. */ - blkCnt = nColumns % 0x4u; - - while(blkCnt > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - uint16_t col, i = 0u, row = nRows; /* loop counters */ - arm_status status; /* status of matrix transpose */ - - -#ifdef ARM_MATH_MATRIX_CHECK - - /* Check for matrix mismatch condition */ - if((pSrc->numRows != pDst->numCols) || (pSrc->numCols != pDst->numRows)) - { - /* Set status as ARM_MATH_SIZE_MISMATCH */ - status = ARM_MATH_SIZE_MISMATCH; - } - else -#endif /* #ifdef ARM_MATH_MATRIX_CHECK */ - - { - /* Matrix transpose by exchanging the rows with columns */ - /* row loop */ - do - { - /* The pointer px is set to starting address of the column being processed */ - px = pOut + i; - - /* Initialize column loop counter */ - col = nColumns; - - while(col > 0u) - { - /* Read and store the input element in the destination */ - *px = *pIn++; - - /* Update the pointer px to point to the next row of the transposed matrix */ - px += nRows; - - /* Decrement the column loop counter */ - col--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - i++; - - /* Decrement the row loop counter */ - row--; - - } - while(row > 0u); /* row loop end */ - - /* set status as ARM_MATH_SUCCESS */ - status = ARM_MATH_SUCCESS; - } - - /* Return to application */ - return (status); -} - -/** - * @} end of MatrixTrans group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c deleted file mode 100644 index afd9648852..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_f32.c +++ /dev/null @@ -1,178 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_max_f32.c -* -* Description: Maximum value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup Max Maximum - * - * Computes the maximum value of an array of data. - * The function returns both the maximum value and its position within the array. - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t maxVal1, maxVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 1u; - } - - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 2u; - } - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 3u; - } - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 4u; - } - - count += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* if (blockSize - 1u) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - float32_t maxVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - blkCnt = (blockSize - 1u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and it's index */ - out = maxVal1; - outIndex = blockSize - blkCnt; - } - - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Store the maximum value and it's index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c deleted file mode 100644 index 939b5236f6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q15.c +++ /dev/null @@ -1,168 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_max_q15.c -* -* Description: Maximum value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q15_t maxVal1, maxVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 1u; - } - - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 2u; - } - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 3u; - } - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 4u; - } - - count += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* if (blockSize - 1u) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - q15_t maxVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - blkCnt = (blockSize - 1u); - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and it's index */ - out = maxVal1; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c deleted file mode 100644 index 18e7572975..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q31.c +++ /dev/null @@ -1,169 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_max_q31.c -* -* Description: Maximum value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t maxVal1, maxVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 1u; - } - - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 2u; - } - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 3u; - } - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 4u; - } - - count += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* if (blockSize - 1u) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - q31_t maxVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - blkCnt = (blockSize - 1u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and it's index */ - out = maxVal1; - outIndex = blockSize - blkCnt; - } - - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Max group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c deleted file mode 100644 index 110a8fe5f7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_max_q7.c +++ /dev/null @@ -1,169 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_max_q7.c -* -* Description: Maximum value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Max - * @{ - */ - - -/** - * @brief Maximum value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult maximum value returned here - * @param[out] *pIndex index of maximum value returned here - * @return none. - */ - -void arm_max_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t maxVal1, maxVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 1u; - } - - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 2u; - } - - maxVal2 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and its index */ - out = maxVal1; - outIndex = count + 3u; - } - - /* compare for the maximum value */ - if(out < maxVal2) - { - /* Update the maximum value and its index */ - out = maxVal2; - outIndex = count + 4u; - } - - count += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* if (blockSize - 1u) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - q7_t maxVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - blkCnt = (blockSize - 1u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* Initialize maxVal to the next consecutive values one by one */ - maxVal1 = *pSrc++; - - /* compare for the maximum value */ - if(out < maxVal1) - { - /* Update the maximum value and it's index */ - out = maxVal1; - outIndex = blockSize - blkCnt; - } - /* Decrement the loop counter */ - blkCnt--; - - } - - /* Store the maximum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; - -} - -/** - * @} end of Max group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c deleted file mode 100644 index 7823d746ca..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_f32.c +++ /dev/null @@ -1,131 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mean_f32.c -* -* Description: Mean value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup mean Mean - * - * Calculates the mean of the input vector. Mean is defined as the average of the elements in the vector. - * The underlying algorithm is used: - * - *
    
- * 	Result = (pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]) / blockSize;    
- * 
- * - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup mean - * @{ - */ - - -/** - * @brief Mean value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - */ - - -void arm_mean_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - sum += in1; - sum += in2; - sum += in3; - sum += in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = sum / (float32_t) blockSize; -} - -/** - * @} end of mean group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c deleted file mode 100644 index 49ec1e62e7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q15.c +++ /dev/null @@ -1,125 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q15.c -* -* Description: Mean value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.15 format and is accumulated in a 32-bit - * accumulator in 17.15 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is saturated and truncated to yield a result of 1.15 format. - * - */ - - -void arm_mean_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q15_t) (sum / blockSize); -} - -/** - * @} end of mean group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c deleted file mode 100644 index 88a5de2995..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q31.c +++ /dev/null @@ -1,128 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q31.c -* -* Description: Mean value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - *\par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.31 format and is accumulated in a 64-bit - * accumulator in 33.31 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is truncated to yield a result of 1.31 format. - * - */ - - -void arm_mean_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - sum += in1; - sum += in2; - sum += in3; - sum += in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q31_t) (sum / (int32_t) blockSize); -} - -/** - * @} end of mean group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c deleted file mode 100644 index a34c011bc1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_mean_q7.c +++ /dev/null @@ -1,125 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_mean_q7.c -* -* Description: Mean value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup mean - * @{ - */ - -/** - * @brief Mean value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult mean value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.7 format and is accumulated in a 32-bit - * accumulator in 25.7 format. - * There is no risk of internal overflow with this approach, and the - * full precision of intermediate result is preserved. - * Finally, the accumulator is truncated to yield a result of 1.7 format. - * - */ - - -void arm_mean_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - in = *__SIMD32(pSrc)++; - - sum += ((in << 24) >> 24); - sum += ((in << 16) >> 24); - sum += ((in << 8) >> 24); - sum += (in >> 24); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - sum += *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) / blockSize */ - /* Store the result to the destination */ - *pResult = (q7_t) (sum / (int32_t) blockSize); -} - -/** - * @} end of mean group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c deleted file mode 100644 index dc2fdf624f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_f32.c +++ /dev/null @@ -1,175 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_min_f32.c -* -* Description: Minimum value of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup Min Minimum - * - * Computes the minimum value of an array of data. - * The function returns both the minimum value and its position within the array. - * There are separate functions for floating-point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t minVal1, minVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 1u; - } - - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 2u; - } - - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 3u; - } - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 4u; - } - - count += 4u; - - blkCnt--; - } - - /* if (blockSize - 1u ) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - float32_t minVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - blkCnt = (blockSize - 1u); - -#endif // #ifndef ARM_MATH_CM0 - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and it's index */ - out = minVal1; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } - - /* Store the minimum value and it's index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c deleted file mode 100644 index 35b67bb1e9..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q15.c +++ /dev/null @@ -1,169 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_min_q15.c -* -* Description: Minimum value of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q15_t minVal1, minVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 1u; - } - - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 2u; - } - - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 3u; - } - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 4u; - } - - count += 4u; - - blkCnt--; - } - - /* if (blockSize - 1u ) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - q15_t minVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - blkCnt = (blockSize - 1u); - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#endif // #ifndef ARM_MATH_CM0 - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and it's index */ - out = minVal1; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } - - - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c deleted file mode 100644 index 4a9befc75c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q31.c +++ /dev/null @@ -1,168 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_min_q31.c -* -* Description: Minimum value of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t minVal1, minVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 1u; - } - - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 2u; - } - - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 3u; - } - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 4u; - } - - count += 4u; - - blkCnt--; - } - - /* if (blockSize - 1u ) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - q31_t minVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - blkCnt = (blockSize - 1u); - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - -#endif // #ifndef ARM_MATH_CM0 - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and it's index */ - out = minVal1; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; -} - -/** - * @} end of Min group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c deleted file mode 100644 index aaf8ad9ff8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_min_q7.c +++ /dev/null @@ -1,170 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_min_q7.c -* -* Description: Minimum value of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup Min - * @{ - */ - - -/** - * @brief Minimum value of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult minimum value returned here - * @param[out] *pIndex index of minimum value returned here - * @return none. - * - */ - -void arm_min_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex) -{ -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q7_t minVal1, minVal2, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex, count; /* loop counter */ - - /* Initialise the count value. */ - count = 0u; - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - /* Loop unrolling */ - blkCnt = (blockSize - 1u) >> 2u; - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 1u; - } - - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 2u; - } - - minVal2 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and its index */ - out = minVal1; - outIndex = count + 3u; - } - - /* compare for the minimum value */ - if(out > minVal2) - { - /* Update the minimum value and its index */ - out = minVal2; - outIndex = count + 4u; - } - - count += 4u; - - blkCnt--; - } - - /* if (blockSize - 1u ) is not multiple of 4 */ - blkCnt = (blockSize - 1u) % 4u; - -#else - - /* Run the below code for Cortex-M0 */ - - q7_t minVal1, out; /* Temporary variables to store the output value. */ - uint32_t blkCnt, outIndex; /* loop counter */ - - /* Initialise the index value to zero. */ - outIndex = 0u; - /* Load first input value that act as reference value for comparision */ - out = *pSrc++; - - blkCnt = (blockSize - 1u); - -#endif // #ifndef ARM_MATH_CM0 - - while(blkCnt > 0) - { - /* Initialize minVal to the next consecutive values one by one */ - minVal1 = *pSrc++; - - /* compare for the minimum value */ - if(out > minVal1) - { - /* Update the minimum value and it's index */ - out = minVal1; - outIndex = blockSize - blkCnt; - } - - blkCnt--; - - } - - /* Store the minimum value and its index into destination pointers */ - *pResult = out; - *pIndex = outIndex; - - -} - -/** - * @} end of Min group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c deleted file mode 100644 index 5ee0060d8f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_f32.c +++ /dev/null @@ -1,138 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_power_f32.c -* -* Description: Sum of the squares of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup power Power - * - * Calculates the sum of the squares of the elements in the input vector. - * The underlying algorithm is used: - * - *
    
- * 	Result = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + pSrc[2] * pSrc[2] + ... + pSrc[blockSize-1] * pSrc[blockSize-1];    
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup power - * @{ - */ - - -/** - * @brief Sum of the squares of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - */ - - -void arm_power_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* accumulator */ - float32_t in; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* compute power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result to the destination */ - *pResult = sum; -} - -/** - * @} end of power group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c deleted file mode 100644 index aed06a17ac..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q15.c +++ /dev/null @@ -1,144 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_power_q15.c -* -* Description: Sum of the squares of the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 34.30 format. - * - */ - -void arm_power_q15( - q15_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in32; /* Temporary variable to store input value */ - q15_t in16; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in32 = *__SIMD32(pSrc)++; - sum = __SMLALD(in32, in32, sum); - in32 = *__SIMD32(pSrc)++; - sum = __SMLALD(in32, in32, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in16 = *pSrc++; - sum = __SMLALD(in16, in16, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* Temporary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q31_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Store the results in 34.30 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c deleted file mode 100644 index 43f03f757f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q31.c +++ /dev/null @@ -1,135 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_power_q31.c -* -* Description: Sum of the squares of the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.31 format. - * Intermediate multiplication yields a 2.62 format, and this - * result is truncated to 2.48 format by discarding the lower 14 bits. - * The 2.48 result is then added without saturation to a 64-bit accumulator in 16.48 format. - * With 15 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 16.48 format. - * - */ - -void arm_power_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0; /* Temporary result storage */ - q31_t in; - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power then shift intermediate results by 14 bits to maintain 16.48 format and then store the result in a temporary variable sum, providing 15 guard bits. */ - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q63_t) in * in) >> 14u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the results in 16.48 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c deleted file mode 100644 index 5cb99b4c2f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_power_q7.c +++ /dev/null @@ -1,133 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_power_q7.c -* -* Description: Sum of the squares of the elements of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup power - * @{ - */ - -/** - * @brief Sum of the squares of the elements of a Q7 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult sum of the squares value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 32-bit internal accumulator. - * The input is represented in 1.7 format. - * Intermediate multiplication yields a 2.14 format, and this - * result is added without saturation to an accumulator in 18.14 format. - * With 17 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the return result is in 18.14 format. - * - */ - -void arm_power_q7( - q7_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q31_t sum = 0; /* Temporary result storage */ - q7_t in; /* Temporary variable to store input */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t input1; /* Temporary variable to store packed input */ - q31_t in1, in2; /* Temporary variables to store input */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* Reading two inputs of pSrc vector and packing */ - input1 = *__SIMD32(pSrc)++; - - in1 = __SXTB16(__ROR(input1, 8)); - in2 = __SXTB16(input1); - - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* calculate power and accumulate to accumulator */ - sum = __SMLAD(in1, in1, sum); - sum = __SMLAD(in2, in2, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute Power and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += ((q15_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Store the result in 18.14 format */ - *pResult = sum; -} - -/** - * @} end of power group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c deleted file mode 100644 index 573896ed4d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_f32.c +++ /dev/null @@ -1,133 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rms_f32.c -* -* Description: Root mean square value of an array of F32 type -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup RMS Root mean square (RMS) - * - * - * Calculates the Root Mean Sqaure of the elements in the input vector. - * The underlying algorithm is used: - * - *
    
- * 	Result = sqrt(((pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]) / blockSize));    
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup RMS - * @{ - */ - - -/** - * @brief Root Mean Square of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - */ - -void arm_rms_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Accumulator */ - float32_t in; /* Tempoprary variable to store input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the result in a temporary variable, sum */ - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Rms and store the result in the destination */ - arm_sqrt_f32(sum / (float32_t) blockSize, pResult); -} - -/** - * @} end of RMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c deleted file mode 100644 index 491c652e7a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q15.c +++ /dev/null @@ -1,153 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rms_q15.c -* -* Description: Root Mean Square of the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup RMS - * @{ - */ - -/** - * @brief Root Mean Square of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - * - */ - -void arm_rms_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q63_t sum = 0; /* accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* temporary variable to store the input value */ - q15_t in1; /* temporary variable to store the input value */ - uint32_t blkCnt; /* loop counter */ - - /* loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - in = *__SIMD32(pSrc)++; - sum = __SMLALD(in, in, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in1 = *pSrc++; - sum = __SMLALD(in1, in1, sum); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Truncating and saturating the accumulator to 1.15 format */ - sum = __SSAT((q31_t) (sum >> 15), 16); - - in1 = (q15_t) (sum / blockSize); - - /* Store the result in the destination */ - arm_sqrt_q15(in1, pResult); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* temporary variable to store the input value */ - uint32_t blkCnt; /* loop counter */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += ((q31_t) in * in); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Truncating and saturating the accumulator to 1.15 format */ - sum = __SSAT((q31_t) (sum >> 15), 16); - - in = (q15_t) (sum / blockSize); - - /* Store the result in the destination */ - arm_sqrt_q15(in, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of RMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c deleted file mode 100644 index 54038eb12e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_rms_q31.c +++ /dev/null @@ -1,146 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rms_q31.c -* -* Description: Root Mean Square of the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup RMS - * @{ - */ - - -/** - * @brief Root Mean Square of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult rms value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows, it wraps around and distorts the result. - * In order to avoid overflows completely, the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - -void arm_rms_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* accumulator */ - q31_t in; /* Temporary variable to store the input */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in1, in2, in3, in4; /* Temporary input variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 8 outputs at a time. - ** a second loop below computes the remaining 1 to 7 samples. */ - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the result in a temporary variable, sum */ - /* read two samples from source buffer */ - in1 = pSrc[0]; - in2 = pSrc[1]; - - /* calculate power and accumulate to accumulator */ - sum += (q63_t) in1 *in1; - sum += (q63_t) in2 *in2; - - /* read two samples from source buffer */ - in3 = pSrc[2]; - in4 = pSrc[3]; - - /* calculate power and accumulate to accumulator */ - sum += (q63_t) in3 *in3; - sum += (q63_t) in4 *in4; - - - /* update source buffer to process next samples */ - pSrc += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 8, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A[0] * A[0] + A[1] * A[1] + A[2] * A[2] + ... + A[blockSize-1] * A[blockSize-1] */ - /* Compute sum of the squares and then store the results in a temporary variable, sum */ - in = *pSrc++; - sum += (q63_t) in *in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Convert data in 2.62 to 1.31 by 31 right shifts and saturate */ - - sum = __SSAT(sum >> 31, 31); - - - /* Compute Rms and store the result in the destination vector */ - arm_sqrt_q31((q31_t) ((q31_t) sum / (int32_t) blockSize), pResult); -} - -/** - * @} end of RMS group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c deleted file mode 100644 index 6442d5c295..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_f32.c +++ /dev/null @@ -1,188 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_std_f32.c -* -* Description: Standard deviation of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup STD Standard deviation - * - * Calculates the standard deviation of the elements in the input vector. - * The underlying algorithm is used: - * - *
    
- * 	Result = sqrt((sumOfSquares - sum2 / blockSize) / (blockSize - 1))   
- *   
- *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]   
- *   
- *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]   
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup STD - * @{ - */ - - -/** - * @brief Standard deviation of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * - */ - - -void arm_std_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - float32_t sum = 0.0f; /* Temporary result storage */ - float32_t sumOfSquares = 0.0f; /* Sum of squares */ - float32_t in; /* input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t meanOfSquares, mean, squareOfMean; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - meanOfSquares = sumOfSquares / ((float32_t) blockSize - 1.0f); - - /* Compute mean of all input values */ - mean = sum / (float32_t) blockSize; - - /* Compute square of mean */ - squareOfMean = (mean * mean) * (((float32_t) blockSize) / - ((float32_t) blockSize - 1.0f)); - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_f32((meanOfSquares - squareOfMean), pResult); - -#else - - /* Run the below code for Cortex-M0 */ - - float32_t squareOfSum; /* Square of Sum */ - float32_t var; /* Temporary varaince storage */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += in * in; - - /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ - /* Compute Sum of the input samples - * and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute the square of sum */ - squareOfSum = ((sum * sum) / (float32_t) blockSize); - - /* Compute the variance */ - var = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_f32(var, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of STD group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c deleted file mode 100644 index 2d1a49a505..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q15.c +++ /dev/null @@ -1,197 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_std_q15.c -* -* Description: Standard deviation of an array of Q15 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup STD - * @{ - */ - -/** - * @brief Standard deviation of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - */ - -void arm_std_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult) -{ - q31_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ - q15_t mean; /* mean */ - uint32_t blkCnt; /* loop counter */ - q15_t t; /* Temporary variable */ - q63_t sumOfSquares = 0; /* Accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* input value */ - q15_t in1; /* input value */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - sumOfSquares = __SMLALD(in, in, sumOfSquares); - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - sumOfSquares = __SMLALD(in, in, sumOfSquares); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in1 = *pSrc++; - sumOfSquares = __SMLALD(in1, in1, sumOfSquares); - sum += in1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - - /* Compute mean of all input values */ - t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); - mean = (q15_t) __SSAT(sum, 16u); - - /* Compute square of mean */ - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* mean of the squares minus the square of the mean. */ - in1 = (q15_t) (meanOfSquares - squareOfMean); - - /* Compute standard deviation and store the result to the destination */ - arm_sqrt_q15(in1, pResult); - -#else - - /* Run the below code for Cortex-M0 */ - q15_t in; /* input value */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += (in * in); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0 / (blockSize - 1)) * 16384LL); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - - /* Compute mean of all input values */ - mean = (q15_t) __SSAT(sum, 16u); - - /* Compute square of mean of the input samples - * and then store the result in a temporary variable, squareOfMean.*/ - t = (q15_t) ((1.0 / (blockSize * (blockSize - 1))) * 32768LL); - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* mean of the squares minus the square of the mean. */ - in = (q15_t) (meanOfSquares - squareOfMean); - - /* Compute standard deviation and store the result to the destination */ - arm_sqrt_q15(in, pResult); - -#endif /* #ifndef ARM_MATH_CM0 */ - - -} - -/** - * @} end of STD group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c deleted file mode 100644 index 45bec01a1f..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_std_q31.c +++ /dev/null @@ -1,184 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_std_q31.c -* -* Description: Standard deviation of an array of Q31 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup STD - * @{ - */ - - -/** - * @brief Standard deviation of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult standard deviation value returned here - * @return none. - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - - -void arm_std_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q63_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ - q31_t mean; /* mean */ - q31_t in; /* input value */ - q31_t t; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - q63_t sumOfSquares = 0; /* Accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += in; - sumOfSquares += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += in; - sumOfSquares += ((q63_t) (in) * (in)); - in = *pSrc++; - sum += in; - sumOfSquares += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += ((q63_t) (in) * (in)); - - /* Decrement the loop counter */ - blkCnt--; - } - - t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - sumOfSquares = (sumOfSquares >> 31); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += ((q63_t) (in) * (in)); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); - sumOfSquares = (sumOfSquares >> 31); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 30); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Compute mean of all input values */ - t = (q31_t) ((1.0f / (blockSize * (blockSize - 1u))) * 2147483648.0f); - mean = (q31_t) (sum); - - /* Compute square of mean */ - squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); - - - /* Compute standard deviation and then store the result to the destination */ - arm_sqrt_q31(meanOfSquares - squareOfMean, pResult); - -} - -/** - * @} end of STD group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c deleted file mode 100644 index 2adcfb443b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_f32.c +++ /dev/null @@ -1,184 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_var_f32.c -* -* Description: Variance of the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @defgroup variance Variance - * - * Calculates the variance of the elements in the input vector. - * The underlying algorithm is used: - * - *
    
- * 	Result = (sumOfSquares - sum2 / blockSize) / (blockSize - 1)   
- *   
- *	   where, sumOfSquares = pSrc[0] * pSrc[0] + pSrc[1] * pSrc[1] + ... + pSrc[blockSize-1] * pSrc[blockSize-1]   
- *   
- *	                   sum = pSrc[0] + pSrc[1] + pSrc[2] + ... + pSrc[blockSize-1]   
- * 
- * - * There are separate functions for floating point, Q31, and Q15 data types. - */ - -/** - * @addtogroup variance - * @{ - */ - - -/** - * @brief Variance of the elements of a floating-point vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - */ - - -void arm_var_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult) -{ - - float32_t sum = 0.0f; /* Temporary result storage */ - float32_t sumOfSquares = 0.0f; /* Sum of squares */ - float32_t in; /* input value */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t meanOfSquares, mean, squareOfMean; /* Temporary variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sum += in; - sumOfSquares += in * in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - meanOfSquares = sumOfSquares / ((float32_t) blockSize - 1.0f); - - /* Compute mean of all input values */ - mean = sum / (float32_t) blockSize; - - /* Compute square of mean */ - squareOfMean = (mean * mean) * (((float32_t) blockSize) / - ((float32_t) blockSize - 1.0f)); - - /* Compute variance and then store the result to the destination */ - *pResult = meanOfSquares - squareOfMean; - -#else - - /* Run the below code for Cortex-M0 */ - float32_t squareOfSum; /* Square of Sum */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += in * in; - - /* C = (A[0] + A[1] + ... + A[blockSize-1]) */ - /* Compute Sum of the input samples - * and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute the square of sum */ - squareOfSum = ((sum * sum) / (float32_t) blockSize); - - /* Compute the variance */ - *pResult = ((sumOfSquares - squareOfSum) / (float32_t) (blockSize - 1.0f)); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of variance group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c deleted file mode 100644 index 08dbc6587c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q15.c +++ /dev/null @@ -1,180 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_var_q15.c -* -* Description: Variance of an array of Q15 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup variance - * @{ - */ - -/** - * @brief Variance of the elements of a Q15 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - * \par - * The function is implemented using a 64-bit internal accumulator. - * The input is represented in 1.15 format. - * Intermediate multiplication yields a 2.30 format, and this - * result is added without saturation to a 64-bit accumulator in 34.30 format. - * With 33 guard bits in the accumulator, there is no risk of overflow, and the - * full precision of the intermediate multiplication is preserved. - * Finally, the 34.30 result is truncated to 34.15 format by discarding the lower - * 15 bits, and then saturated to yield a result in 1.15 format. - * - */ - - -void arm_var_q15( - q15_t * pSrc, - uint32_t blockSize, - q31_t * pResult) -{ - q31_t sum = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* Mean of square and square of mean */ - q15_t mean; /* mean */ - uint32_t blkCnt; /* loop counter */ - q15_t t; /* Temporary variable */ - q63_t sumOfSquares = 0; /* Accumulator */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t in; /* Input variable */ - q15_t in1; /* Temporary variable */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - sumOfSquares = __SMLALD(in, in, sumOfSquares); - in = *__SIMD32(pSrc)++; - sum += ((in << 16) >> 16); - sum += (in >> 16); - sumOfSquares = __SMLALD(in, in, sumOfSquares); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in1 = *pSrc++; - sum += in1; - sumOfSquares = __SMLALD(in1, in1, sumOfSquares); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t in; /* Temporary variable */ - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sumOfSquares. */ - in = *pSrc++; - sumOfSquares += (in * in); - - /* C = (A[0] + A[1] + A[2] + ... + A[blockSize-1]) */ - /* Compute sum of all input values and then store the result in a temporary variable, sum. */ - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - t = (q15_t) ((1.0f / (float32_t) (blockSize - 1u)) * 16384); - sumOfSquares = __SSAT((sumOfSquares >> 15u), 16u); - meanOfSquares = (q31_t) ((sumOfSquares * t) >> 14u); - -#endif /* #ifndef ARM_MATH_CM0 */ - - /* Compute mean of all input values */ - t = (q15_t) ((1.0f / (float32_t) (blockSize * (blockSize - 1u))) * 32768); - mean = __SSAT(sum, 16u); - - /* Compute square of mean */ - squareOfMean = ((q31_t) mean * mean) >> 15; - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 15); - - /* Compute variance and then store the result to the destination */ - *pResult = (meanOfSquares - squareOfMean); - -} - -/** - * @} end of variance group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c deleted file mode 100644 index 13d6c15cb5..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/StatisticsFunctions/arm_var_q31.c +++ /dev/null @@ -1,170 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_var_q31.c -* -* Description: Variance of an array of Q31 type. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupStats - */ - -/** - * @addtogroup variance - * @{ - */ - -/** - * @brief Variance of the elements of a Q31 vector. - * @param[in] *pSrc points to the input vector - * @param[in] blockSize length of the input vector - * @param[out] *pResult variance value returned here - * @return none. - * - * @details - * Scaling and Overflow Behavior: - * - *\par - * The function is implemented using an internal 64-bit accumulator. - * The input is represented in 1.31 format, and intermediate multiplication - * yields a 2.62 format. - * The accumulator maintains full precision of the intermediate multiplication results, - * but provides only a single guard bit. - * There is no saturation on intermediate additions. - * If the accumulator overflows it wraps around and distorts the result. - * In order to avoid overflows completely the input signal must be scaled down by - * log2(blockSize) bits, as a total of blockSize additions are performed internally. - * Finally, the 2.62 accumulator is right shifted by 31 bits to yield a 1.31 format value. - * - */ - - -void arm_var_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult) -{ - q63_t sum = 0, sumSquare = 0; /* Accumulator */ - q31_t meanOfSquares, squareOfMean; /* square of mean and mean of square */ - q31_t mean; /* mean */ - q31_t in; /* input value */ - q31_t t; /* Temporary variable */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q63_t sumSquare1 = 0; /* Accumulator */ - q31_t in1, in2, in3, in4; /* Temporary input variables */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - /* read input samples from source buffer */ - in1 = pSrc[0]; - in2 = pSrc[1]; - - /* calculate sum of inputs */ - sum += in1; - /* calculate sum of squares */ - sumSquare += ((q63_t) (in1) * (in1)); - in3 = pSrc[2]; - sum += in2; - sumSquare1 += ((q63_t) (in2) * (in2)); - in4 = pSrc[3]; - sum += in3; - sumSquare += ((q63_t) (in3) * (in3)); - sum += in4; - sumSquare1 += ((q63_t) (in4) * (in4)); - - /* update input pointer to process next samples */ - pSrc += 4u; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* add two accumulators */ - sumSquare = sumSquare + sumSquare1; - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (A[0] * A[0] + A[1] * A[1] + ... + A[blockSize-1] * A[blockSize-1]) */ - /* Compute Sum of squares of the input samples - * and then store the result in a temporary variable, sum. */ - in = *pSrc++; - sumSquare += ((q63_t) (in) * (in)); - sum += in; - - /* Decrement the loop counter */ - blkCnt--; - } - - t = (q31_t) ((1.0f / (float32_t) (blockSize - 1u)) * 1073741824.0f); - - /* Compute Mean of squares of the input samples - * and then store the result in a temporary variable, meanOfSquares. */ - sumSquare = (sumSquare >> 31); - meanOfSquares = (q31_t) ((sumSquare * t) >> 30); - - /* Compute mean of all input values */ - t = (q31_t) ((1.0f / (blockSize * (blockSize - 1u))) * 2147483648.0f); - mean = (q31_t) (sum); - - /* Compute square of mean */ - squareOfMean = (q31_t) (((q63_t) mean * mean) >> 31); - squareOfMean = (q31_t) (((q63_t) squareOfMean * t) >> 31); - - /* Compute variance and then store the result to the destination */ - *pResult = (q63_t) meanOfSquares - squareOfMean; - -} - -/** - * @} end of variance group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c deleted file mode 100644 index 619c1577a6..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_f32.c +++ /dev/null @@ -1,130 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_copy_f32.c -* -* Description: Copies the elements of a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup copy Vector Copy - * - * Copies sample by sample from source vector to destination vector. - * - *
    
- * 	pDst[n] = pSrc[n];   0 <= n < blockSize.    
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a floating-point vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - - -void arm_copy_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - *pDst++ = in1; - *pDst++ = in2; - *pDst++ = in3; - *pDst++ = in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c deleted file mode 100644 index 00be9dc0b2..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q15.c +++ /dev/null @@ -1,109 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q15.c -* -* Description: Copies the elements of a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ -/** - * @brief Copies the elements of a Q15 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Read two inputs */ - *__SIMD32(pDst)++ = *__SIMD32(pSrc)++; - *__SIMD32(pDst)++ = *__SIMD32(pSrc)++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the value in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c deleted file mode 100644 index 7ab0849f6e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q31.c +++ /dev/null @@ -1,118 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q31.c -* -* Description: Copies the elements of a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a Q31 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the values in the destination buffer */ - in1 = *pSrc++; - in2 = *pSrc++; - in3 = *pSrc++; - in4 = *pSrc++; - - *pDst++ = in1; - *pDst++ = in2; - *pDst++ = in3; - *pDst++ = in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the value in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c deleted file mode 100644 index 425885753e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_copy_q7.c +++ /dev/null @@ -1,110 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_copy_q7.c -* -* Description: Copies the elements of a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup copy - * @{ - */ - -/** - * @brief Copies the elements of a Q7 vector. - * @param[in] *pSrc points to input vector - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the input vector - * @return none. - * - */ - -void arm_copy_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - /* 4 samples are copied and stored at a time using SIMD */ - *__SIMD32(pDst)++ = *__SIMD32(pSrc)++; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = A */ - /* Copy and then store the results in the destination buffer */ - *pDst++ = *pSrc++; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of BasicCopy group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c deleted file mode 100644 index 439e60db0c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_f32.c +++ /dev/null @@ -1,129 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fill_f32.c -* -* Description: Fills a constant value into a floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup Fill Vector Fill - * - * Fills the destination vector with a constant value. - * - *
    
- * 	pDst[n] = value;   0 <= n < blockSize.    
- * 
- * - * There are separate functions for floating point, Q31, Q15, and Q7 data types. - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a floating-point vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - - -void arm_fill_f32( - float32_t value, - float32_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - float32_t in1 = value; - float32_t in2 = value; - float32_t in3 = value; - float32_t in4 = value; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = in1; - *pDst++ = in2; - *pDst++ = in3; - *pDst++ = in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c deleted file mode 100644 index 8f60d3b4ef..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q15.c +++ /dev/null @@ -1,115 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q15.c -* -* Description: Fills a constant value into a Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q15 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q15( - q15_t value, - q15_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t packedValue; /* value packed to 32 bits */ - - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Packing two 16 bit values to 32 bit value in order to use SIMD */ - packedValue = __PKHBT(value, value, 16u); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *__SIMD32(pDst)++ = packedValue; - *__SIMD32(pDst)++ = packedValue; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c deleted file mode 100644 index 35565c3cf7..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q31.c +++ /dev/null @@ -1,116 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q31.c -* -* Description: Fills a constant value into a Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q31 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q31( - q31_t value, - q31_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1 = value; - q31_t in2 = value; - q31_t in3 = value; - q31_t in4 = value; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = in1; - *pDst++ = in2; - *pDst++ = in3; - *pDst++ = in4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c deleted file mode 100644 index 481d4c8f7b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_fill_q7.c +++ /dev/null @@ -1,113 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_fill_q7.c -* -* Description: Fills a constant value into a Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup Fill - * @{ - */ - -/** - * @brief Fills a constant value into a Q7 vector. - * @param[in] value input value to be filled - * @param[out] *pDst points to output vector - * @param[in] blockSize length of the output vector - * @return none. - * - */ - -void arm_fill_q7( - q7_t value, - q7_t * pDst, - uint32_t blockSize) -{ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t packedValue; /* value packed to 32 bits */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* Packing four 8 bit values to 32 bit value in order to use SIMD */ - packedValue = __PACKq7(value, value, value, value); - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *__SIMD32(pDst)++ = packedValue; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = value */ - /* Fill the value in the destination buffer */ - *pDst++ = value; - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of Fill group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c deleted file mode 100644 index 1537b93ab9..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q15.c +++ /dev/null @@ -1,196 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q15.c -* -* Description: Converts the elements of the floating-point vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q15 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * \par - * The equation used for the conversion process is: - *
    
- * 	pDst[n] = (q15_t)(pSrc[n] * 32768);   0 <= n < blockSize.    
- * 
- * \par Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q15 range [0x8000 0x7FFF] will be saturated. - * \note - * In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - * - */ - - -void arm_float_to_q15( - float32_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 32768.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = (q15_t) (__SSAT((q31_t) (in), 16)); - -#else - - /* C = A * 32768 */ - /* convert from float to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) __SSAT((q31_t) (*pIn++ * 32768.0f), 16); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c deleted file mode 100644 index 3ab52b9ff0..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q31.c +++ /dev/null @@ -1,203 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q31.c -* -* Description: Converts the elements of the floating-point vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup float_to_x Convert 32-bit floating point value - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q31 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - *\par Description: - * \par - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q31_t)(pSrc[n] * 2147483648);   0 <= n < blockSize.    
- * 
- * Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q31 range[0x80000000 0x7FFFFFFF] will be saturated. - * - * \note In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - */ - - -void arm_float_to_q31( - float32_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 32768 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 2147483648.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = clip_q63_to_q31((q63_t) (in)); - -#else - - /* C = A * 2147483648 */ - /* convert from float to Q31 and then store the results in the destination buffer */ - *pDst++ = clip_q63_to_q31((q63_t) (*pIn++ * 2147483648.0f)); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c deleted file mode 100644 index dea14c6a14..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_float_to_q7.c +++ /dev/null @@ -1,195 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_float_to_q7.c -* -* Description: Converts the elements of the floating-point vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup float_to_x - * @{ - */ - -/** - * @brief Converts the elements of the floating-point vector to Q7 vector. - * @param[in] *pSrc points to the floating-point input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - *\par Description: - * \par - * The equation used for the conversion process is: - *
    
- * 	pDst[n] = (q7_t)(pSrc[n] * 128);   0 <= n < blockSize.    
- * 
- * \par Scaling and Overflow Behavior: - * \par - * The function uses saturating arithmetic. - * Results outside of the allowable Q7 range [0x80 0x7F] will be saturated. - * \note - * In order to apply rounding, the library should be rebuilt with the ROUNDING macro - * defined in the preprocessor section of project options. - */ - - -void arm_float_to_q7( - float32_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - float32_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifdef ARM_MATH_ROUNDING - - float32_t in; - -#endif /* #ifdef ARM_MATH_ROUNDING */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - - while(blkCnt > 0u) - { - -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128); - in += in > 0 ? 0.5 : -0.5; - *pDst++ = (q7_t) (__SSAT((q15_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - - -#else - - /* Run the below code for Cortex-M0 */ - - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - - while(blkCnt > 0u) - { -#ifdef ARM_MATH_ROUNDING - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - in = *pIn++; - in = (in * 128.0f); - in += in > 0 ? 0.5f : -0.5f; - *pDst++ = (q7_t) (__SSAT((q31_t) (in), 8)); - -#else - - /* C = A * 128 */ - /* convert from float to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) __SSAT((q31_t) (*pIn++ * 128.0f), 8); - -#endif /* #ifdef ARM_MATH_ROUNDING */ - - /* Decrement the loop counter */ - blkCnt--; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of float_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c deleted file mode 100644 index ce51e9a395..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_float.c +++ /dev/null @@ -1,126 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_float.c -* -* Description: Converts the elements of the Q15 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q15_to_x Convert 16-bit Integer value - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - - - - -/** - * @brief Converts the elements of the Q15 vector to floating-point vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (float32_t) pSrc[n] / 32768;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q15_to_float( - q15_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 32768 */ - /* convert from q15 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 32768 */ - /* convert from q15 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 32768.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q15_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c deleted file mode 100644 index a0f66c29e8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q31.c +++ /dev/null @@ -1,148 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_q31.c -* -* Description: Converts the elements of the Q15 vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q15 vector to Q31 vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q31_t) pSrc[n] << 16;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q15_to_q31( - q15_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2; - q31_t out1, out2, out3, out4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q31_t)A << 16 */ - /* convert from q15 to q31 and then store the results in the destination buffer */ - in1 = *__SIMD32(pIn)++; - in2 = *__SIMD32(pIn)++; - -#ifndef ARM_MATH_BIG_ENDIAN - - /* extract lower 16 bits to 32 bit result */ - out1 = in1 << 16u; - /* extract upper 16 bits to 32 bit result */ - out2 = in1 & 0xFFFF0000; - /* extract lower 16 bits to 32 bit result */ - out3 = in2 << 16u; - /* extract upper 16 bits to 32 bit result */ - out4 = in2 & 0xFFFF0000; - -#else - - /* extract upper 16 bits to 32 bit result */ - out1 = in1 & 0xFFFF0000; - /* extract lower 16 bits to 32 bit result */ - out2 = in1 << 16u; - /* extract upper 16 bits to 32 bit result */ - out3 = in2 & 0xFFFF0000; - /* extract lower 16 bits to 32 bit result */ - out4 = in2 << 16u; - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - *pDst++ = out1; - *pDst++ = out2; - *pDst++ = out3; - *pDst++ = out4; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q31_t)A << 16 */ - /* convert from q15 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 16; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q15_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c deleted file mode 100644 index 87fe63d9eb..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q15_to_q7.c +++ /dev/null @@ -1,146 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q15_to_q7.c -* -* Description: Converts the elements of the Q15 vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q15_to_x - * @{ - */ - - -/** - * @brief Converts the elements of the Q15 vector to Q7 vector. - * @param[in] *pSrc points to the Q15 input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q7_t) pSrc[n] >> 8;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q15_to_q7( - q15_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - q15_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2; - q31_t out1, out2; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 8 */ - /* convert from q15 to q7 and then store the results in the destination buffer */ - in1 = *__SIMD32(pIn)++; - in2 = *__SIMD32(pIn)++; - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __PKHTB(in2, in1, 16); - out2 = __PKHBT(in2, in1, 16); - -#else - - out1 = __PKHTB(in1, in2, 16); - out2 = __PKHBT(in1, in2, 16); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - /* rotate packed value by 24 */ - out2 = ((uint32_t) out2 << 8) | ((uint32_t) out2 >> 24); - - /* anding with 0xff00ff00 to get two 8 bit values */ - out1 = out1 & 0xFF00FF00; - /* anding with 0x00ff00ff to get two 8 bit values */ - out2 = out2 & 0x00FF00FF; - - /* oring two values(contains two 8 bit values) to get four packed 8 bit values */ - out1 = out1 | out2; - - /* store 4 samples at a time to destiantion buffer */ - *__SIMD32(pDst)++ = out1; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 8 */ - /* convert from q15 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 8); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q15_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c deleted file mode 100644 index 94deec9a1b..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_float.c +++ /dev/null @@ -1,123 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_float.c -* -* Description: Converts the elements of the Q31 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q31_to_x Convert 32-bit Integer value - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to floating-point vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (float32_t) pSrc[n] / 2147483648;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q31_to_float( - q31_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 2147483648 */ - /* convert from q31 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 2147483648 */ - /* convert from q31 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 2147483648.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q31_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c deleted file mode 100644 index ba79f85a13..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q15.c +++ /dev/null @@ -1,137 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_q15.c -* -* Description: Converts the elements of the Q31 vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to Q15 vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q15_t) pSrc[n] >> 16;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q31_to_q15( - q31_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - q31_t out1, out2; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q15_t) A >> 16 */ - /* convert from q31 to q15 and then store the results in the destination buffer */ - in1 = *pIn++; - in2 = *pIn++; - in3 = *pIn++; - in4 = *pIn++; - - /* pack two higher 16-bit values from two 32-bit values */ -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __PKHTB(in2, in1, 16); - out2 = __PKHTB(in4, in3, 16); - -#else - - out1 = __PKHTB(in1, in2, 16); - out2 = __PKHTB(in3, in4, 16); - -#endif // #ifdef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst)++ = out1; - *__SIMD32(pDst)++ = out2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q15_t) A >> 16 */ - /* convert from q31 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) (*pIn++ >> 16); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q31_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c deleted file mode 100644 index afc8fdbed4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q31_to_q7.c +++ /dev/null @@ -1,128 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q31_to_q7.c -* -* Description: Converts the elements of the Q31 vector to Q7 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q31_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q31 vector to Q7 vector. - * @param[in] *pSrc points to the Q31 input vector - * @param[out] *pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q7_t) pSrc[n] >> 24;   0 <= n < blockSize.     
- * 
- * - */ - - -void arm_q31_to_q7( - q31_t * pSrc, - q7_t * pDst, - uint32_t blockSize) -{ - q31_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - q31_t in1, in2, in3, in4; - q7_t out1, out2, out3, out4; - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 24 */ - /* convert from q31 to q7 and then store the results in the destination buffer */ - in1 = *pIn++; - in2 = *pIn++; - in3 = *pIn++; - in4 = *pIn++; - - out1 = (q7_t) (in1 >> 24); - out2 = (q7_t) (in2 >> 24); - out3 = (q7_t) (in3 >> 24); - out4 = (q7_t) (in4 >> 24); - - *__SIMD32(pDst)++ = __PACKq7(out1, out2, out3, out4); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q7_t) A >> 24 */ - /* convert from q31 to q7 and then store the results in the destination buffer */ - *pDst++ = (q7_t) (*pIn++ >> 24); - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q31_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c deleted file mode 100644 index be4ac5fe30..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_float.c +++ /dev/null @@ -1,123 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_float.c -* -* Description: Converts the elements of the Q7 vector to floating-point vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @defgroup q7_to_x Convert 8-bit Integer value - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q7 vector to floating-point vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the floating-point output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (float32_t) pSrc[n] / 128;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q7_to_float( - q7_t * pSrc, - float32_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (float32_t) A / 128 */ - /* convert from q7 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - *pDst++ = ((float32_t) * pIn++ / 128.0f); - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (float32_t) A / 128 */ - /* convert from q7 to float and then store the results in the destination buffer */ - *pDst++ = ((float32_t) * pIn++ / 128.0f); - - /* Decrement the loop counter */ - blkCnt--; - } -} - -/** - * @} end of q7_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c deleted file mode 100644 index 019ca48159..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q15.c +++ /dev/null @@ -1,149 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_q15.c -* -* Description: Converts the elements of the Q7 vector to Q15 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - - - - -/** - * @brief Converts the elements of the Q7 vector to Q15 vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q15_t) pSrc[n] << 8;   0 <= n < blockSize.    
- * 
- * - */ - - -void arm_q7_to_q15( - q7_t * pSrc, - q15_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - q31_t in; - q31_t in1, in2; - q31_t out1, out2; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q15_t) A << 8 */ - /* convert from q7 to q15 and then store the results in the destination buffer */ - in = *__SIMD32(pIn)++; - - /* rotatate in by 8 and extend two q7_t values to q15_t values */ - in1 = __SXTB16(__ROR(in, 8)); - - /* extend remainig two q7_t values to q15_t values */ - in2 = __SXTB16(in); - - in1 = in1 << 8u; - in2 = in2 << 8u; - - in1 = in1 & 0xFF00FF00; - in2 = in2 & 0xFF00FF00; - -#ifndef ARM_MATH_BIG_ENDIAN - - out2 = __PKHTB(in1, in2, 16); - out1 = __PKHBT(in2, in1, 16); - -#else - - out1 = __PKHTB(in1, in2, 16); - out2 = __PKHBT(in2, in1, 16); - -#endif - - *__SIMD32(pDst)++ = out1; - *__SIMD32(pDst)++ = out2; - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q15_t) A << 8 */ - /* convert from q7 to q15 and then store the results in the destination buffer */ - *pDst++ = (q15_t) * pIn++ << 8; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q7_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c deleted file mode 100644 index bbbcc6f4a3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/SupportFunctions/arm_q7_to_q31.c +++ /dev/null @@ -1,134 +0,0 @@ -/* ---------------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_q7_to_q31.c -* -* Description: Converts the elements of the Q7 vector to Q31 vector. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* ---------------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupSupport - */ - -/** - * @addtogroup q7_to_x - * @{ - */ - -/** - * @brief Converts the elements of the Q7 vector to Q31 vector. - * @param[in] *pSrc points to the Q7 input vector - * @param[out] *pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - * @return none. - * - * \par Description: - * - * The equation used for the conversion process is: - * - *
    
- * 	pDst[n] = (q31_t) pSrc[n] << 24;   0 <= n < blockSize.   
- * 
- * - */ - - -void arm_q7_to_q31( - q7_t * pSrc, - q31_t * pDst, - uint32_t blockSize) -{ - q7_t *pIn = pSrc; /* Src pointer */ - uint32_t blkCnt; /* loop counter */ - -#ifndef ARM_MATH_CM0 - - q31_t in; - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /*loop Unrolling */ - blkCnt = blockSize >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - while(blkCnt > 0u) - { - /* C = (q31_t) A << 24 */ - /* convert from q7 to q31 and then store the results in the destination buffer */ - in = *__SIMD32(pIn)++; - -#ifndef ARM_MATH_BIG_ENDIAN - - *pDst++ = (__ROR(in, 8)) & 0xFF000000; - *pDst++ = (__ROR(in, 16)) & 0xFF000000; - *pDst++ = (__ROR(in, 24)) & 0xFF000000; - *pDst++ = (in & 0xFF000000); - -#else - - *pDst++ = (in & 0xFF000000); - *pDst++ = (__ROR(in, 24)) & 0xFF000000; - *pDst++ = (__ROR(in, 16)) & 0xFF000000; - *pDst++ = (__ROR(in, 8)) & 0xFF000000; - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - /* Decrement the loop counter */ - blkCnt--; - } - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - blkCnt = blockSize % 0x4u; - -#else - - /* Run the below code for Cortex-M0 */ - - /* Loop over blockSize number of values */ - blkCnt = blockSize; - -#endif /* #ifndef ARM_MATH_CM0 */ - - while(blkCnt > 0u) - { - /* C = (q31_t) A << 24 */ - /* convert from q7 to q31 and then store the results in the destination buffer */ - *pDst++ = (q31_t) * pIn++ << 24; - - /* Decrement the loop counter */ - blkCnt--; - } - -} - -/** - * @} end of q7_to_x group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_bitreversal.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_bitreversal.c deleted file mode 100644 index 3da790ebb1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_bitreversal.c +++ /dev/null @@ -1,222 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_bitreversal.c -* -* Description: This file has common tables like Bitreverse, reciprocal etc which are used across different functions -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Initial Version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftSize length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table. - * @param[in] *pBitRevTab points to the bit reversal table. - * @return none. - */ - -void arm_bitreversal_f32( - float32_t * pSrc, - uint16_t fftSize, - uint16_t bitRevFactor, - uint16_t * pBitRevTab) -{ - uint16_t fftLenBy2, fftLenBy2p1; - uint16_t i, j; - float32_t in; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftSize >> 1u; - fftLenBy2p1 = (fftSize >> 1u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - in = pSrc[2u * i]; - pSrc[2u * i] = pSrc[2u * j]; - pSrc[2u * j] = in; - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[(2u * i) + 1u]; - pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; - pSrc[(2u * j) + 1u] = in; - - /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ - in = pSrc[2u * (i + fftLenBy2p1)]; - pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; - pSrc[2u * (j + fftLenBy2p1)] = in; - - /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ - in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; - pSrc[(2u * (i + fftLenBy2p1)) + 1u] = - pSrc[(2u * (j + fftLenBy2p1)) + 1u]; - pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; - - } - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[2u * (i + 1u)]; - pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; - pSrc[2u * (j + fftLenBy2)] = in; - - /* pSrc[i+2u] <-> pSrc[j+2u] */ - in = pSrc[(2u * (i + 1u)) + 1u]; - pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; - pSrc[(2u * (j + fftLenBy2)) + 1u] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTab; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTab += bitRevFactor; - } -} - - - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - -void arm_bitreversal_q31( - q31_t * pSrc, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTable) -{ - uint32_t fftLenBy2, fftLenBy2p1, i, j; - q31_t in; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftLen / 2u; - fftLenBy2p1 = (fftLen / 2u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - in = pSrc[2u * i]; - pSrc[2u * i] = pSrc[2u * j]; - pSrc[2u * j] = in; - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[(2u * i) + 1u]; - pSrc[(2u * i) + 1u] = pSrc[(2u * j) + 1u]; - pSrc[(2u * j) + 1u] = in; - - /* pSrc[i+fftLenBy2p1] <-> pSrc[j+fftLenBy2p1] */ - in = pSrc[2u * (i + fftLenBy2p1)]; - pSrc[2u * (i + fftLenBy2p1)] = pSrc[2u * (j + fftLenBy2p1)]; - pSrc[2u * (j + fftLenBy2p1)] = in; - - /* pSrc[i+fftLenBy2p1+1u] <-> pSrc[j+fftLenBy2p1+1u] */ - in = pSrc[(2u * (i + fftLenBy2p1)) + 1u]; - pSrc[(2u * (i + fftLenBy2p1)) + 1u] = - pSrc[(2u * (j + fftLenBy2p1)) + 1u]; - pSrc[(2u * (j + fftLenBy2p1)) + 1u] = in; - - } - - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[2u * (i + 1u)]; - pSrc[2u * (i + 1u)] = pSrc[2u * (j + fftLenBy2)]; - pSrc[2u * (j + fftLenBy2)] = in; - - /* pSrc[i+2u] <-> pSrc[j+2u] */ - in = pSrc[(2u * (i + 1u)) + 1u]; - pSrc[(2u * (i + 1u)) + 1u] = pSrc[(2u * (j + fftLenBy2)) + 1u]; - pSrc[(2u * (j + fftLenBy2)) + 1u] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTable; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTable += bitRevFactor; - } -} - - - -/* - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - -void arm_bitreversal_q15( - q15_t * pSrc16, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTab) -{ - q31_t *pSrc = (q31_t *) pSrc16; - q31_t in; - uint32_t fftLenBy2, fftLenBy2p1; - uint32_t i, j; - - /* Initializations */ - j = 0u; - fftLenBy2 = fftLen / 2u; - fftLenBy2p1 = (fftLen / 2u) + 1u; - - /* Bit Reversal Implementation */ - for (i = 0u; i <= (fftLenBy2 - 2u); i += 2u) - { - if(i < j) - { - /* pSrc[i] <-> pSrc[j]; */ - /* pSrc[i+1u] <-> pSrc[j+1u] */ - in = pSrc[i]; - pSrc[i] = pSrc[j]; - pSrc[j] = in; - - /* pSrc[i + fftLenBy2p1] <-> pSrc[j + fftLenBy2p1]; */ - /* pSrc[i + fftLenBy2p1+1u] <-> pSrc[j + fftLenBy2p1+1u] */ - in = pSrc[i + fftLenBy2p1]; - pSrc[i + fftLenBy2p1] = pSrc[j + fftLenBy2p1]; - pSrc[j + fftLenBy2p1] = in; - } - - /* pSrc[i+1u] <-> pSrc[j+fftLenBy2]; */ - /* pSrc[i+2] <-> pSrc[j+fftLenBy2+1u] */ - in = pSrc[i + 1u]; - pSrc[i + 1u] = pSrc[j + fftLenBy2]; - pSrc[j + fftLenBy2] = in; - - /* Reading the index for the bit reversal */ - j = *pBitRevTab; - - /* Updating the bit reversal index depending on the fft length */ - pBitRevTab += bitRevFactor; - } -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_f32.c deleted file mode 100644 index 274b699281..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_f32.c +++ /dev/null @@ -1,511 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix2_f32.c -* -* Description: Radix-2 Decimation in Frequency CFFT & CIFFT Floating point processing function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.3 2010/11/29 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup Radix2_CFFT_CIFFT Radix-2 Complex FFT Functions - * - * \par - * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). - * Computational complexity of CFFT reduces drastically when compared to DFT. - * \par - * This set of functions implements CFFT/CIFFT - * for Q15, Q31, and floating-point data types. The functions operates on in-place buffer which uses same buffer for input and output. - * Complex input is stored in input buffer in an interleaved fashion. - * - * \par - * The functions operate on blocks of input and output data and each call to the function processes - * 2*fftLen samples through the transform. pSrc points to In-place arrays containing 2*fftLen values. - * \par - * The pSrc points to the array of in-place buffer of size 2*fftLen and inputs and outputs are stored in an interleaved fashion as shown below. - *
 {real[0], imag[0], real[1], imag[1],..} 
- * - * \par Lengths supported by the transform: - * \par - * Internally, the function utilize a radix-2 decimation in frequency(DIF) algorithm - * and the size of the FFT supported are of the lengths [16, 32, 64, 128, 256, 512, 1024, 2048, 4096]. - * - * - * \par Algorithm: - * - * Complex Fast Fourier Transform: - * \par - * Input real and imaginary data: - *
   
- * x(n) = xa + j * ya   
- * x(n+N/2 ) = xb + j * yb   
- * 
- * where N is length of FFT - * \par - * Output real and imaginary data: - *
   
- * X(2r) = xa'+ j * ya'   
- * X(2r+1) = xb'+ j * yb'   
- * 
- * \par - * Twiddle factors for radix-2 FFT: - *
   
- * Wn = cosVal + j * (- sinVal)   
- * 
- * - * \par - * \image html CFFT_Radix2.gif "Radix-2 Decimation-in Frequency Complex Fast Fourier Transform" - * - * \par - * Output from Radix-2 CFFT Results in Digit reversal order. Interchange middle two branches of every butterfly results in Bit reversed output. - * \par - * Butterfly CFFT equations: - *
   
- * xa' = xa + xb  
- * ya' = ya + yb  
- * xb' = (xa-xb)* cosVal + (ya-yb) * sinVal   
- * yb' = (ya-yb)* cosVal - (xa-xb) * sinVal   
- * 
- * - * - * Complex Inverse Fast Fourier Transform: - * \par - * CIFFT uses same twiddle factor table as CFFT with modifications in the design equation as shown below. - * - * \par - * Modified Butterfly CIFFT equations: - *
   
- * xa' = xa + xb  
- * ya' = ya + yb  
- * xb' = (xa-xb)* cosVal - (ya-yb) * sinVal   
- * yb' = (ya-yb)* cosVal + (xa-xb) * sinVal   
- * 
- * - * \par Instance Structure - * A separate instance structure must be defined for each Instance but the twiddle factors and bit reversal tables can be reused. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes twiddle factor table and bit reversal table pointers - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
   
- *arm_cfft_radix2_instance_f32 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor, onebyfftLen};   
- *arm_cfft_radix2_instance_q31 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
- *arm_cfft_radix2_instance_q15 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};   
- * 
- * \par - * where fftLen length of CFFT/CIFFT; ifftFlag Flag for selection of CFFT or CIFFT(Set ifftFlag to calculate CIFFT otherwise calculates CFFT); - * bitReverseFlag Flag for selection of output order(Set bitReverseFlag to output in normal order otherwise output in bit reversed order); - * pTwiddlepoints to array of twiddle coefficients; pBitRevTable points to the array of bit reversal table. - * twidCoefModifier modifier for twiddle factor table which supports all FFT lengths with same table; - * pBitRevTable modifier for bit reversal table which supports all FFT lengths with same table. - * onebyfftLen value of 1/fftLen to calculate CIFFT; - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the CFFT/CIFFT function. - * Refer to the function specific documentation below for usage guidelines. - */ - - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the floating-point Radix-2 CFFT/CIFFT. - * @param[in] *S points to an instance of the floating-point Radix-2 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - */ - -void arm_cfft_radix2_f32( - const arm_cfft_radix2_instance_f32 * S, - float32_t * pSrc) -{ - - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-2 */ - arm_radix2_butterfly_inverse_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier, S->onebyfftLen); - } - else - { - /* Complex FFT radix-2 */ - arm_radix2_butterfly_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_f32(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - - -/** - * @} end of Radix2_CFFT_CIFFT group - */ - - - -/* ---------------------------------------------------------------------- -** Internal helper function used by the FFTs -** ------------------------------------------------------------------- */ - -/* - * @brief Core function for the floating-point CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to the twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix2_butterfly_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier) -{ - - int i, j, k, l; - int n1, n2, ia; - float32_t xt, yt, cosVal, sinVal; - -#ifndef ARM_MATH_CM0 - - /* Initializations for the first stage */ - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - - /* Twiddle coefficients index modifier */ - ia = ia + twidCoefModifier; - - /* index calculation for the input as, */ - /* pSrc[i + 0], pSrc[i + fftLen/1] */ - l = i + n2; - - /* Butterfly implementation */ - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2u * l] = xt * cosVal + yt * sinVal; - - pSrc[2u * l + 1u] = yt * cosVal - xt * sinVal; - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2u * l] = xt * cosVal + yt * sinVal; - - pSrc[2u * l + 1u] = yt * cosVal - xt * sinVal; - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - } // groups loop end - -#else - - //N = fftLen; - n2 = fftLen; - - // loop for stage - for (k = fftLen; k > 1; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2 * l] = (cosVal * xt + sinVal * yt); // >> 15; - pSrc[2 * l + 1] = (cosVal * yt - sinVal * xt); // >> 15; - - } - } - twidCoefModifier = twidCoefModifier << 1u; - } - -#endif // #ifndef ARM_MATH_CM0 - -} - - -void arm_radix2_butterfly_inverse_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier, - float32_t onebyfftLen) -{ - - int i, j, k, l; - int n1, n2, ia; - float32_t xt, yt, cosVal, sinVal; - -#ifndef ARM_MATH_CM0 - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2u * l] = xt * cosVal - yt * sinVal; - - pSrc[2u * l + 1u] = yt * cosVal + xt * sinVal; - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2u * l] = xt * cosVal - yt * sinVal; - - pSrc[2u * l + 1u] = yt * cosVal + xt * sinVal; - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) * onebyfftLen; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) * onebyfftLen; - - pSrc[2u * l] = xt * onebyfftLen; - - pSrc[2u * l + 1u] = yt * onebyfftLen; - - } // butterfly loop end - -#else - - //N = fftLen; - n2 = fftLen; - - // loop for stage - for (k = fftLen; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = pSrc[2 * i] + pSrc[2 * l]; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = pSrc[2 * l + 1] + pSrc[2 * i + 1]; - - pSrc[2u * l] = xt * cosVal - yt * sinVal; - - pSrc[2u * l + 1u] = yt * cosVal + xt * sinVal; - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) * onebyfftLen; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) * onebyfftLen; - - pSrc[2u * l] = xt * onebyfftLen; - - pSrc[2u * l + 1u] = yt * onebyfftLen; - - } // butterfly loop end - -#endif // #ifndef ARM_MATH_CM0 - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_f32.c deleted file mode 100644 index a41ed25d2c..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_f32.c +++ /dev/null @@ -1,198 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_f32.c -* -* Description: Radix-4 Decimation in Frequency Floating-point CFFT & CIFFT Initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - -/** -* @brief Initialization function for the floating-point CFFT/CIFFT. -* @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ -arm_status arm_cfft_radix2_init_f32( - arm_cfft_radix2_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialise the FFT length */ - S->fftLen = fftLen; - - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (float32_t *) twiddleCoef; - - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - - case 4096u: - /* Initializations of structure parameters for 4096 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.000244140625; - break; - - case 2048u: - /* Initializations of structure parameters for 2048 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 2u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 2u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[1]; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.00048828125; - break; - - case 1024u: - /* Initializations of structure parameters for 1024 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 4u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 4u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.0009765625f; - break; - - case 512u: - /* Initializations of structure parameters for 512 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 8u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 8u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[7]; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.001953125; - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - S->onebyfftLen = 0.00390625f; - break; - - case 128u: - /* Initializations of structure parameters for 128 point FFT */ - S->twidCoefModifier = 32u; - S->bitRevFactor = 32u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[31]; - S->onebyfftLen = 0.0078125; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - S->onebyfftLen = 0.015625f; - break; - - case 32u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 128u; - S->bitRevFactor = 128u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[127]; - S->onebyfftLen = 0.03125; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - S->onebyfftLen = 0.0625f; - break; - - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix2_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q15.c deleted file mode 100644 index 86aa149b2d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q15.c +++ /dev/null @@ -1,186 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix2_init_q15.c -* -* Description: Radix-2 Decimation in Frequency Q15 FFT & IFFT initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - -/** -* @brief Initialization function for the Q15 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix2_init_q15( - arm_cfft_radix2_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialise the FFT length */ - S->fftLen = fftLen; - - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q15_t *) twiddleCoefQ15; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - case 4096u: - /* Initializations of structure parameters for 4096 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - - break; - - case 2048u: - /* Initializations of structure parameters for 2048 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 2u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 2u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[1]; - - break; - - case 1024u: - /* Initializations of structure parameters for 1024 point FFT */ - S->twidCoefModifier = 4u; - S->bitRevFactor = 4u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - - break; - - case 512u: - /* Initializations of structure parameters for 512 point FFT */ - S->twidCoefModifier = 8u; - S->bitRevFactor = 8u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[7]; - - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - - break; - - case 128u: - /* Initializations of structure parameters for 128 point FFT */ - S->twidCoefModifier = 32u; - S->bitRevFactor = 32u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[31]; - - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - - break; - - case 32u: - /* Initializations of structure parameters for 32 point FFT */ - S->twidCoefModifier = 128u; - S->bitRevFactor = 128u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[127]; - - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - - break; - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix2_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q31.c deleted file mode 100644 index 29aa9a74bd..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_init_q31.c +++ /dev/null @@ -1,164 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix2_init_q31.c -* -* Description: Radix-2 Decimation in Frequency Fixed-point CFFT & CIFFT Initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - - -/** -* -* @brief Initialization function for the Q31 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix2_init_q31( - arm_cfft_radix2_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialise the FFT length */ - S->fftLen = fftLen; - - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q31_t *) twiddleCoefQ31; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of Instance structure depending on the FFT length */ - switch (S->fftLen) - { - /* Initializations of structure parameters for 4096 point FFT */ - case 4096u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - break; - - /* Initializations of structure parameters for 2048 point FFT */ - case 2048u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 2u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 2u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[1]; - break; - - /* Initializations of structure parameters for 1024 point FFT */ - case 1024u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 4u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 4u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - break; - - /* Initializations of structure parameters for 512 point FFT */ - case 512u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 8u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 8u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[7]; - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - break; - - case 128u: - /* Initializations of structure parameters for 128 point FFT */ - S->twidCoefModifier = 32u; - S->bitRevFactor = 32u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[31]; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - break; - - case 32u: - /* Initializations of structure parameters for 32 point FFT */ - S->twidCoefModifier = 128u; - S->bitRevFactor = 128u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[127]; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - break; - - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix2_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q15.c deleted file mode 100644 index 00c7420cf4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q15.c +++ /dev/null @@ -1,712 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix2_q15.c -* -* Description: Radix-2 Decimation in Frequency CFFT & CIFFT Fixed point processing function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup Radix2_CFFT_CIFFT Radix-2 Complex FFT Functions - * - * \par - * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). - * Computational complexity of CFFT reduces drastically when compared to DFT. - */ - - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the fixed-point CFFT/CIFFT. - * @param[in] *S points to an instance of the fixed-point CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - */ - -void arm_cfft_radix2_q15( - const arm_cfft_radix2_instance_q15 * S, - q15_t * pSrc) -{ - - if(S->ifftFlag == 1u) - { - arm_radix2_butterfly_inverse_q15(pSrc, S->fftLen, - S->pTwiddle, S->twidCoefModifier); - } - else - { - arm_radix2_butterfly_q15(pSrc, S->fftLen, - S->pTwiddle, S->twidCoefModifier); - } - - arm_bitreversal_q15(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); -} - -/** - * @} end of Radix2_CFFT_CIFFT group - */ - -void arm_radix2_butterfly_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pCoef, - uint16_t twidCoefModifier) -{ -#ifndef ARM_MATH_CM0 - - int i, j, k, l; - int n1, n2, ia; - q15_t in; - q31_t T, S, R; - q31_t coeff, out1, out2; - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(coeff, R) >> 16; - out2 = __SMUSDX(coeff, R); - -#else - - out1 = __SMUSDX(R, coeff) >> 16u; - out2 = __SMUAD(coeff, R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - i++; - l++; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(coeff, R) >> 16; - out2 = __SMUSDX(coeff, R); - -#else - - out1 = __SMUSDX(R, coeff) >> 16u; - out2 = __SMUAD(coeff, R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(coeff, R) >> 16; - out2 = __SMUSDX(coeff, R); - -#else - - out1 = __SMUSDX(R, coeff) >> 16u; - out2 = __SMUAD(coeff, R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - i += n1; - - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(coeff, R) >> 16; - out2 = __SMUSDX(coeff, R); - -#else - - out1 = __SMUSDX(R, coeff) >> 16u; - out2 = __SMUAD(coeff, R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __QADD16(T, S); - - _SIMD32_OFFSET(pSrc + (2u * l)) = R; - - i += n1; - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __QADD16(T, S); - - _SIMD32_OFFSET(pSrc + (2u * l)) = R; - - } // groups loop end - - -#else - - int i, j, k, l; - int n1, n2, ia; - q15_t xt, yt, cosVal, sinVal; - - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = (pSrc[2 * i] >> 2u) - (pSrc[2 * l] >> 2u); - pSrc[2 * i] = ((pSrc[2 * i] >> 2u) + (pSrc[2 * l] >> 2u)) >> 1u; - - yt = (pSrc[2 * i + 1] >> 2u) - (pSrc[2 * l + 1] >> 2u); - pSrc[2 * i + 1] = - ((pSrc[2 * l + 1] >> 2u) + (pSrc[2 * i + 1] >> 2u)) >> 1u; - - pSrc[2u * l] = (((int16_t) (((q31_t) xt * cosVal) >> 16)) + - ((int16_t) (((q31_t) yt * sinVal) >> 16))); - - pSrc[2u * l + 1u] = (((int16_t) (((q31_t) yt * cosVal) >> 16)) - - ((int16_t) (((q31_t) xt * sinVal) >> 16))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) >> 1u; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) >> 1u; - - pSrc[2u * l] = (((int16_t) (((q31_t) xt * cosVal) >> 16)) + - ((int16_t) (((q31_t) yt * sinVal) >> 16))); - - pSrc[2u * l + 1u] = (((int16_t) (((q31_t) yt * cosVal) >> 16)) - - ((int16_t) (((q31_t) xt * sinVal) >> 16))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - -#endif // #ifndef ARM_MATH_CM0 - -} - - -void arm_radix2_butterfly_inverse_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pCoef, - uint16_t twidCoefModifier) -{ -#ifndef ARM_MATH_CM0 - - int i, j, k, l; - int n1, n2, ia; - q15_t in; - q31_t T, S, R; - q31_t coeff, out1, out2; - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(coeff, R) >> 16; - out2 = __SMUADX(coeff, R); -#else - - out1 = __SMUADX(R, coeff) >> 16u; - out2 = __SMUSD(__QSUB(0, coeff), R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - i++; - l++; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(coeff, R) >> 16; - out2 = __SMUADX(coeff, R); -#else - - out1 = __SMUADX(R, coeff) >> 16u; - out2 = __SMUSD(__QSUB(0, coeff), R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(coeff, R) >> 16; - out2 = __SMUADX(coeff, R); - -#else - - out1 = __SMUADX(R, coeff) >> 16u; - out2 = __SMUSD(__QSUB(0, coeff), R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - i += n1; - - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __SHADD16(T, S); - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(coeff, R) >> 16; - out2 = __SMUADX(coeff, R); -#else - - out1 = __SMUADX(R, coeff) >> 16u; - out2 = __SMUSD(__QSUB(0, coeff), R); - -#endif // #ifndef ARM_MATH_BIG_ENDIAN - - _SIMD32_OFFSET(pSrc + (2u * l)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - coeff = _SIMD32_OFFSET(pCoef + (ia * 2u)); - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - - T = _SIMD32_OFFSET(pSrc + (2 * i)); - - S = _SIMD32_OFFSET(pSrc + (2 * l)); - - R = __QSUB16(T, S); - - _SIMD32_OFFSET(pSrc + (2 * i)) = __QADD16(T, S); - - _SIMD32_OFFSET(pSrc + (2u * l)) = R; - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - -#else - - - int i, j, k, l; - int n1, n2, ia; - q15_t xt, yt, cosVal, sinVal; - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = (pSrc[2 * i] >> 2u) - (pSrc[2 * l] >> 2u); - pSrc[2 * i] = ((pSrc[2 * i] >> 2u) + (pSrc[2 * l] >> 2u)) >> 1u; - - yt = (pSrc[2 * i + 1] >> 2u) - (pSrc[2 * l + 1] >> 2u); - pSrc[2 * i + 1] = - ((pSrc[2 * l + 1] >> 2u) + (pSrc[2 * i + 1] >> 2u)) >> 1u; - - pSrc[2u * l] = (((int16_t) (((q31_t) xt * cosVal) >> 16)) - - ((int16_t) (((q31_t) yt * sinVal) >> 16))); - - pSrc[2u * l + 1u] = (((int16_t) (((q31_t) yt * cosVal) >> 16)) + - ((int16_t) (((q31_t) xt * sinVal) >> 16))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) >> 1u; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) >> 1u; - - pSrc[2u * l] = (((int16_t) (((q31_t) xt * cosVal) >> 16)) - - ((int16_t) (((q31_t) yt * sinVal) >> 16))); - - pSrc[2u * l + 1u] = (((int16_t) (((q31_t) yt * cosVal) >> 16)) + - ((int16_t) (((q31_t) xt * sinVal) >> 16))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - } // groups loop end - - -#endif // #ifndef ARM_MATH_CM0 - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q31.c deleted file mode 100644 index dd4b9e6b24..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix2_q31.c +++ /dev/null @@ -1,310 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix2_q31.c -* -* Description: Radix-2 Decimation in Frequency CFFT & CIFFT Fixed point processing function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup Radix2_CFFT_CIFFT Radix-2 Complex FFT Functions - * - * \par - * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). - * Computational complexity of CFFT reduces drastically when compared to DFT. - */ - - -/** - * @addtogroup Radix2_CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the fixed-point CFFT/CIFFT. - * @param[in] *S points to an instance of the fixed-point CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - */ - -void arm_cfft_radix2_q31( - const arm_cfft_radix2_instance_q31 * S, - q31_t * pSrc) -{ - - if(S->ifftFlag == 1u) - { - arm_radix2_butterfly_inverse_q31(pSrc, S->fftLen, - S->pTwiddle, S->twidCoefModifier); - } - else - { - arm_radix2_butterfly_q31(pSrc, S->fftLen, - S->pTwiddle, S->twidCoefModifier); - } - - arm_bitreversal_q31(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); -} - -/** - * @} end of Radix2_CFFT_CIFFT group - */ - -void arm_radix2_butterfly_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint16_t twidCoefModifier) -{ - - int i, j, k, l; - int n1, n2, ia; - q31_t xt, yt, cosVal, sinVal; - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - l = i + n2; - xt = (pSrc[2 * i] >> 2u) - (pSrc[2 * l] >> 2u); - pSrc[2 * i] = ((pSrc[2 * i] >> 2u) + (pSrc[2 * l] >> 2u)) >> 1u; - - yt = (pSrc[2 * i + 1] >> 2u) - (pSrc[2 * l + 1] >> 2u); - pSrc[2 * i + 1] = - ((pSrc[2 * l + 1] >> 2u) + (pSrc[2 * i + 1] >> 2u)) >> 1u; - - pSrc[2u * l] = (((int32_t) (((q63_t) xt * cosVal) >> 32)) + - ((int32_t) (((q63_t) yt * sinVal) >> 32))); - - pSrc[2u * l + 1u] = (((int32_t) (((q63_t) yt * cosVal) >> 32)) - - ((int32_t) (((q63_t) xt * sinVal) >> 32))); - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) >> 1u; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) >> 1u; - - pSrc[2u * l] = (((int32_t) (((q63_t) xt * cosVal) >> 32)) + - ((int32_t) (((q63_t) yt * sinVal) >> 32))); - - pSrc[2u * l + 1u] = (((int32_t) (((q63_t) yt * cosVal) >> 32)) - - ((int32_t) (((q63_t) xt * sinVal) >> 32))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - i += n1; - l = i + n2; - - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - } // butterfly loop end - -} - - -void arm_radix2_butterfly_inverse_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint16_t twidCoefModifier) -{ - - int i, j, k, l; - int n1, n2, ia; - q31_t xt, yt, cosVal, sinVal; - - //N = fftLen; - n2 = fftLen; - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (i = 0; i < n2; i++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - l = i + n2; - xt = (pSrc[2 * i] >> 2u) - (pSrc[2 * l] >> 2u); - pSrc[2 * i] = ((pSrc[2 * i] >> 2u) + (pSrc[2 * l] >> 2u)) >> 1u; - - yt = (pSrc[2 * i + 1] >> 2u) - (pSrc[2 * l + 1] >> 2u); - pSrc[2 * i + 1] = - ((pSrc[2 * l + 1] >> 2u) + (pSrc[2 * i + 1] >> 2u)) >> 1u; - - pSrc[2u * l] = (((int32_t) (((q63_t) xt * cosVal) >> 32)) - - ((int32_t) (((q63_t) yt * sinVal) >> 32))); - - pSrc[2u * l + 1u] = (((int32_t) (((q63_t) yt * cosVal) >> 32)) + - ((int32_t) (((q63_t) xt * sinVal) >> 32))); - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - - // loop for stage - for (k = fftLen / 2; k > 2; k = k >> 1) - { - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - // loop for groups - for (j = 0; j < n2; j++) - { - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = j; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]) >> 1u; - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]) >> 1u; - - pSrc[2u * l] = (((int32_t) (((q63_t) xt * cosVal) >> 32)) - - ((int32_t) (((q63_t) yt * sinVal) >> 32))); - - pSrc[2u * l + 1u] = (((int32_t) (((q63_t) yt * cosVal) >> 32)) + - ((int32_t) (((q63_t) xt * sinVal) >> 32))); - - } // butterfly loop end - - } // groups loop end - - twidCoefModifier = twidCoefModifier << 1u; - } // stages loop end - - n1 = n2; - n2 = n2 >> 1; - ia = 0; - - cosVal = pCoef[ia * 2]; - sinVal = pCoef[(ia * 2) + 1]; - ia = ia + twidCoefModifier; - - // loop for butterfly - for (i = 0; i < fftLen; i += n1) - { - l = i + n2; - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - i += n1; - l = i + n2; - - xt = pSrc[2 * i] - pSrc[2 * l]; - pSrc[2 * i] = (pSrc[2 * i] + pSrc[2 * l]); - - yt = pSrc[2 * i + 1] - pSrc[2 * l + 1]; - pSrc[2 * i + 1] = (pSrc[2 * l + 1] + pSrc[2 * i + 1]); - - pSrc[2u * l] = xt; - - pSrc[2u * l + 1u] = yt; - - } // butterfly loop end - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c deleted file mode 100644 index d51e9830bc..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_f32.c +++ /dev/null @@ -1,1236 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_f32.c -* -* Description: Radix-4 Decimation in Frequency CFFT & CIFFT Floating point processing function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup Radix4_CFFT_CIFFT Radix-4 Complex FFT Functions - * - * \par - * Complex Fast Fourier Transform(CFFT) and Complex Inverse Fast Fourier Transform(CIFFT) is an efficient algorithm to compute Discrete Fourier Transform(DFT) and Inverse Discrete Fourier Transform(IDFT). - * Computational complexity of CFFT reduces drastically when compared to DFT. - * \par - * This set of functions implements CFFT/CIFFT - * for Q15, Q31, and floating-point data types. The functions operates on in-place buffer which uses same buffer for input and output. - * Complex input is stored in input buffer in an interleaved fashion. - * - * \par - * The functions operate on blocks of input and output data and each call to the function processes - * 2*fftLen samples through the transform. pSrc points to In-place arrays containing 2*fftLen values. - * \par - * The pSrc points to the array of in-place buffer of size 2*fftLen and inputs and outputs are stored in an interleaved fashion as shown below. - *
 {real[0], imag[0], real[1], imag[1],..} 
- * - * \par Lengths supported by the transform: - * \par - * Internally, the function utilize a radix-4 decimation in frequency(DIF) algorithm - * and the size of the FFT supported are of the lengths [16, 64, 256, 1024]. - * - * - * \par Algorithm: - * - * Complex Fast Fourier Transform: - * \par - * Input real and imaginary data: - *
    
- * x(n) = xa + j * ya    
- * x(n+N/4 ) = xb + j * yb    
- * x(n+N/2 ) = xc + j * yc    
- * x(n+3N 4) = xd + j * yd    
- * 
- * where N is length of FFT - * \par - * Output real and imaginary data: - *
    
- * X(4r) = xa'+ j * ya'    
- * X(4r+1) = xb'+ j * yb'    
- * X(4r+2) = xc'+ j * yc'    
- * X(4r+3) = xd'+ j * yd'    
- * 
- * \par - * Twiddle factors for radix-4 FFT: - *
    
- * Wn = co1 + j * (- si1)    
- * W2n = co2 + j * (- si2)    
- * W3n = co3 + j * (- si3)    
- * 
- * - * \par - * \image html CFFT.gif "Radix-4 Decimation-in Frequency Complex Fast Fourier Transform" - * - * \par - * Output from Radix-4 CFFT Results in Digit reversal order. Interchange middle two branches of every butterfly results in Bit reversed output. - * \par - * Butterfly CFFT equations: - *
    
- * xa' = xa + xb + xc + xd    
- * ya' = ya + yb + yc + yd    
- * xc' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1)    
- * yc' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1)    
- * xb' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2)    
- * yb' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2)    
- * xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3)    
- * yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3)    
- * 
- * - * - * Complex Inverse Fast Fourier Transform: - * \par - * CIFFT uses same twiddle factor table as CFFT with modifications in the design equation as shown below. - * - * \par - * Modified Butterfly CIFFT equations: - *
    
- * xa' = xa + xb + xc + xd    
- * ya' = ya + yb + yc + yd    
- * xc' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1)    
- * yc' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1)    
- * xb' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2)    
- * yb' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2)    
- * xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3)    
- * yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3)    
- * 
- * - * \par Instance Structure - * A separate instance structure must be defined for each Instance but the twiddle factors and bit reversal tables can be reused. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes twiddle factor table and bit reversal table pointers - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
    
- *arm_cfft_radix4_instance_f32 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor, onebyfftLen};    
- *arm_cfft_radix4_instance_q31 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};    
- *arm_cfft_radix4_instance_q15 S = {fftLen, ifftFlag, bitReverseFlag, pTwiddle, pBitRevTable, twidCoefModifier, bitRevFactor};    
- * 
- * \par - * where fftLen length of CFFT/CIFFT; ifftFlag Flag for selection of CFFT or CIFFT(Set ifftFlag to calculate CIFFT otherwise calculates CFFT); - * bitReverseFlag Flag for selection of output order(Set bitReverseFlag to output in normal order otherwise output in bit reversed order); - * pTwiddlepoints to array of twiddle coefficients; pBitRevTable points to the array of bit reversal table. - * twidCoefModifier modifier for twiddle factor table which supports all FFT lengths with same table; - * pBitRevTable modifier for bit reversal table which supports all FFT lengths with same table. - * onebyfftLen value of 1/fftLen to calculate CIFFT; - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the CFFT/CIFFT function. - * Refer to the function specific documentation below for usage guidelines. - */ - - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the floating-point Radix-4 CFFT/CIFFT. - * @param[in] *S points to an instance of the floating-point Radix-4 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - */ - -void arm_cfft_radix4_f32( - const arm_cfft_radix4_instance_f32 * S, - float32_t * pSrc) -{ - - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier, S->onebyfftLen); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_f32(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_f32(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - - -/** - * @} end of Radix4_CFFT_CIFFT group - */ - - -/* ---------------------------------------------------------------------- -** Internal helper function used by the FFTs -** ------------------------------------------------------------------- */ - -/* - * @brief Core function for the floating-point CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to the twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier) -{ - - float32_t co1, co2, co3, si1, si2, si3; - uint32_t ia1, ia2, ia3; - uint32_t i0, i1, i2, i3; - uint32_t n1, n2, j, k; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - float32_t xaIn, yaIn, xbIn, ybIn, xcIn, ycIn, xdIn, ydIn; - float32_t Xaplusc, Xbplusd, Yaplusc, Ybplusd, Xaminusc, Xbminusd, Yaminusc, - Ybminusd; - float32_t Xb12C_out, Yb12C_out, Xc12C_out, Yc12C_out, Xd12C_out, Yd12C_out; - float32_t Xb12_out, Yb12_out, Xc12_out, Yc12_out, Xd12_out, Yd12_out; - float32_t *ptr1; - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - xaIn = pSrc[(2u * i0)]; - yaIn = pSrc[(2u * i0) + 1u]; - - xcIn = pSrc[(2u * i2)]; - ycIn = pSrc[(2u * i2) + 1u]; - - xbIn = pSrc[(2u * i1)]; - ybIn = pSrc[(2u * i1) + 1u]; - - xdIn = pSrc[(2u * i3)]; - ydIn = pSrc[(2u * i3) + 1u]; - - /* xa + xc */ - Xaplusc = xaIn + xcIn; - /* xb + xd */ - Xbplusd = xbIn + xdIn; - /* ya + yc */ - Yaplusc = yaIn + ycIn; - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - /* xb - xd */ - Xbminusd = xbIn - xdIn; - /* ya - yc */ - Yaminusc = yaIn - ycIn; - /* yb + yd */ - Ybminusd = ybIn - ydIn; - - /* xa' = xa + xb + xc + xd */ - pSrc[(2u * i0)] = Xaplusc + Xbplusd; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = Yaplusc + Ybplusd; - - /* (xa - xc) + (yb - yd) */ - Xb12C_out = (Xaminusc + Ybminusd); - /* (ya - yc) + (xb - xd) */ - Yb12C_out = (Yaminusc - Xbminusd); - /* (xa + xc) - (xb + xd) */ - Xc12C_out = (Xaplusc - Xbplusd); - /* (ya + yc) - (yb + yd) */ - Yc12C_out = (Yaplusc - Ybplusd); - /* (xa - xc) - (yb - yd) */ - Xd12C_out = (Xaminusc - Ybminusd); - /* (ya - yc) + (xb - xd) */ - Yd12C_out = (Xbminusd + Yaminusc); - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* index calculation for the coefficients */ - ia3 = ia2 + ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - Xb12_out = Xb12C_out * co1; - Yb12_out = Yb12C_out * co1; - Xc12_out = Xc12C_out * co2; - Yc12_out = Yc12C_out * co2; - Xd12_out = Xd12C_out * co3; - Yd12_out = Yd12C_out * co3; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - Xb12_out += Yb12C_out * si1; - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - Yb12_out -= Xb12C_out * si1; - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - Xc12_out += Yc12C_out * si2; - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - Yc12_out -= Xc12C_out * si2; - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - Xd12_out += Yd12C_out * si3; - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - Yd12_out -= Xd12C_out * si3; - - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = Xc12_out; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = Yc12_out; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = Xb12_out; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = Yb12_out; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = Xd12_out; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = Yd12_out; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } - while(--j); - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - xaIn = pSrc[(2u * i0)]; - yaIn = pSrc[(2u * i0) + 1u]; - - xbIn = pSrc[(2u * i1)]; - ybIn = pSrc[(2u * i1) + 1u]; - - xcIn = pSrc[(2u * i2)]; - ycIn = pSrc[(2u * i2) + 1u]; - - xdIn = pSrc[(2u * i3)]; - ydIn = pSrc[(2u * i3) + 1u]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - /* (xb - xd) */ - Xbminusd = xbIn - xdIn; - /* ya - yc */ - Yaminusc = yaIn - ycIn; - /* (yb - yd) */ - Ybminusd = ybIn - ydIn; - - /* xa + xc */ - Xaplusc = xaIn + xcIn; - /* xb + xd */ - Xbplusd = xbIn + xdIn; - /* ya + yc */ - Yaplusc = yaIn + ycIn; - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* (xa - xc) + (yb - yd) */ - Xb12C_out = (Xaminusc + Ybminusd); - /* (ya - yc) - (xb - xd) */ - Yb12C_out = (Yaminusc - Xbminusd); - /* xa + xc -(xb + xd) */ - Xc12C_out = (Xaplusc - Xbplusd); - /* (ya + yc) - (yb + yd) */ - Yc12C_out = (Yaplusc - Ybplusd); - /* (xa - xc) - (yb - yd) */ - Xd12C_out = (Xaminusc - Ybminusd); - /* (ya - yc) + (xb - xd) */ - Yd12C_out = (Xbminusd + Yaminusc); - - pSrc[(2u * i0)] = Xaplusc + Xbplusd; - pSrc[(2u * i0) + 1u] = Yaplusc + Ybplusd; - - Xb12_out = Xb12C_out * co1; - Yb12_out = Yb12C_out * co1; - Xc12_out = Xc12C_out * co2; - Yc12_out = Yc12C_out * co2; - Xd12_out = Xd12C_out * co3; - Yd12_out = Yd12C_out * co3; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - Xb12_out += Yb12C_out * si1; - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - Yb12_out -= Xb12C_out * si1; - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - Xc12_out += Yc12C_out * si2; - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - Yc12_out -= Xc12C_out * si2; - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - Xd12_out += Yd12C_out * si3; - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - Yd12_out -= Xd12C_out * si3; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = Xc12_out; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = Yc12_out; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = Xb12_out; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = Yb12_out; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = Xd12_out; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = Yd12_out; - - } - } - twidCoefModifier <<= 2u; - } - - j = fftLen >> 2; - ptr1 = &pSrc[0]; - - /* Calculations of last stage */ - do - { - - xaIn = ptr1[0]; - xcIn = ptr1[4]; - yaIn = ptr1[1]; - ycIn = ptr1[5]; - - /* xa + xc */ - Xaplusc = xaIn + xcIn; - - xbIn = ptr1[2]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - - xdIn = ptr1[6]; - - /* ya + yc */ - Yaplusc = yaIn + ycIn; - - ybIn = ptr1[3]; - - /* ya - yc */ - Yaminusc = yaIn - ycIn; - - ydIn = ptr1[7]; - - /* xb + xd */ - Xbplusd = xbIn + xdIn; - - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* xa' = xa + xb + xc + xd */ - ptr1[0] = (Xaplusc + Xbplusd); - - /* (xb-xd) */ - Xbminusd = xbIn - xdIn; - - /* ya' = ya + yb + yc + yd */ - ptr1[1] = (Yaplusc + Ybplusd); - - /* (yb-yd) */ - Ybminusd = ybIn - ydIn; - - /* xc' = (xa-xb+xc-xd) */ - ptr1[2] = (Xaplusc - Xbplusd); - /* yc' = (ya-yb+yc-yd) */ - ptr1[3] = (Yaplusc - Ybplusd); - /* xb' = (xa+yb-xc-yd) */ - ptr1[4] = (Xaminusc + Ybminusd); - /* yb' = (ya-xb-yc+xd) */ - ptr1[5] = (Yaminusc - Xbminusd); - /* xd' = (xa-yb-xc+yd)) */ - ptr1[6] = (Xaminusc - Ybminusd); - /* yd' = (ya+xb-yc-xd) */ - ptr1[7] = (Xbminusd + Yaminusc); - - /* increment pointer by 8 */ - ptr1 = ptr1 + 8u; - - } while(--j); - -#else - - float32_t t1, t2, r1, r2, s1, s2; - - /* Run the below code for Cortex-M0 */ - - /* Initializations for the fft calculation */ - n2 = fftLen; - n1 = n2; - for (k = fftLen; k > 1u; k >>= 2u) - { - /* Initializations for the fft calculation */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* FFT Calculation */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) + (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) - (r1 * si2); - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) + (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) - (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) + (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) - (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/* - * @brief Core function for the floating-point CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @param[in] onebyfftLen value of 1/fftLen. - * @return none. - */ - -void arm_radix4_butterfly_inverse_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier, - float32_t onebyfftLen) -{ - float32_t co1, co2, co3, si1, si2, si3; - uint32_t ia1, ia2, ia3; - uint32_t i0, i1, i2, i3; - uint32_t n1, n2, j, k; - -#ifndef ARM_MATH_CM0 - - float32_t xaIn, yaIn, xbIn, ybIn, xcIn, ycIn, xdIn, ydIn; - float32_t Xaplusc, Xbplusd, Yaplusc, Ybplusd, Xaminusc, Xbminusd, Yaminusc, - Ybminusd; - float32_t Xb12C_out, Yb12C_out, Xc12C_out, Yc12C_out, Xd12C_out, Yd12C_out; - float32_t Xb12_out, Yb12_out, Xc12_out, Yc12_out, Xd12_out, Yd12_out; - float32_t *ptr1; - - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - xaIn = pSrc[(2u * i0)]; - yaIn = pSrc[(2u * i0) + 1u]; - - xcIn = pSrc[(2u * i2)]; - ycIn = pSrc[(2u * i2) + 1u]; - - xbIn = pSrc[(2u * i1)]; - ybIn = pSrc[(2u * i1) + 1u]; - - xdIn = pSrc[(2u * i3)]; - ydIn = pSrc[(2u * i3) + 1u]; - - /* xa + xc */ - Xaplusc = xaIn + xcIn; - /* xb + xd */ - Xbplusd = xbIn + xdIn; - /* ya + yc */ - Yaplusc = yaIn + ycIn; - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - /* xb - xd */ - Xbminusd = xbIn - xdIn; - /* ya - yc */ - Yaminusc = yaIn - ycIn; - /* yb - yd */ - Ybminusd = ybIn - ydIn; - - /* xa' = xa + xb + xc + xd */ - pSrc[(2u * i0)] = Xaplusc + Xbplusd; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = Yaplusc + Ybplusd; - - /* (xa - xc) - (yb - yd) */ - Xb12C_out = (Xaminusc - Ybminusd); - /* (ya - yc) + (xb - xd) */ - Yb12C_out = (Yaminusc + Xbminusd); - /* (xa + xc) - (xb + xd) */ - Xc12C_out = (Xaplusc - Xbplusd); - /* (ya + yc) - (yb + yd) */ - Yc12C_out = (Yaplusc - Ybplusd); - /* (xa - xc) + (yb - yd) */ - Xd12C_out = (Xaminusc + Ybminusd); - /* (ya - yc) - (xb - xd) */ - Yd12C_out = (Yaminusc - Xbminusd); - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* index calculation for the coefficients */ - ia3 = ia2 + ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - Xb12_out = Xb12C_out * co1; - Yb12_out = Yb12C_out * co1; - Xc12_out = Xc12C_out * co2; - Yc12_out = Yc12C_out * co2; - Xd12_out = Xd12C_out * co3; - Yd12_out = Yd12C_out * co3; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - Xb12_out -= Yb12C_out * si1; - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - Yb12_out += Xb12C_out * si1; - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - Xc12_out -= Yc12C_out * si2; - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - Yc12_out += Xc12C_out * si2; - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - Xd12_out -= Yd12C_out * si3; - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - Yd12_out += Xd12C_out * si3; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = Xc12_out; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = Yc12_out; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = Xb12_out; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = Yb12_out; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = Xd12_out; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = Yd12_out; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - xaIn = pSrc[(2u * i0)]; - yaIn = pSrc[(2u * i0) + 1u]; - - xbIn = pSrc[(2u * i1)]; - ybIn = pSrc[(2u * i1) + 1u]; - - xcIn = pSrc[(2u * i2)]; - ycIn = pSrc[(2u * i2) + 1u]; - - xdIn = pSrc[(2u * i3)]; - ydIn = pSrc[(2u * i3) + 1u]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - /* (xb - xd) */ - Xbminusd = xbIn - xdIn; - /* ya - yc */ - Yaminusc = yaIn - ycIn; - /* (yb - yd) */ - Ybminusd = ybIn - ydIn; - - /* xa + xc */ - Xaplusc = xaIn + xcIn; - /* xb + xd */ - Xbplusd = xbIn + xdIn; - /* ya + yc */ - Yaplusc = yaIn + ycIn; - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* (xa - xc) - (yb - yd) */ - Xb12C_out = (Xaminusc - Ybminusd); - /* (ya - yc) + (xb - xd) */ - Yb12C_out = (Yaminusc + Xbminusd); - /* xa + xc -(xb + xd) */ - Xc12C_out = (Xaplusc - Xbplusd); - /* (ya + yc) - (yb + yd) */ - Yc12C_out = (Yaplusc - Ybplusd); - /* (xa - xc) + (yb - yd) */ - Xd12C_out = (Xaminusc + Ybminusd); - /* (ya - yc) - (xb - xd) */ - Yd12C_out = (Yaminusc - Xbminusd); - - pSrc[(2u * i0)] = Xaplusc + Xbplusd; - pSrc[(2u * i0) + 1u] = Yaplusc + Ybplusd; - - Xb12_out = Xb12C_out * co1; - Yb12_out = Yb12C_out * co1; - Xc12_out = Xc12C_out * co2; - Yc12_out = Yc12C_out * co2; - Xd12_out = Xd12C_out * co3; - Yd12_out = Yd12C_out * co3; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - Xb12_out -= Yb12C_out * si1; - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - Yb12_out += Xb12C_out * si1; - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - Xc12_out -= Yc12C_out * si2; - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - Yc12_out += Xc12C_out * si2; - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - Xd12_out -= Yd12C_out * si3; - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - Yd12_out += Xd12C_out * si3; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = Xc12_out; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = Yc12_out; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = Xb12_out; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = Yb12_out; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = Xd12_out; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = Yd12_out; - - } - } - twidCoefModifier <<= 2u; - } - /* Initializations of last stage */ - - j = fftLen >> 2; - ptr1 = &pSrc[0]; - - /* Calculations of last stage */ - do - { - - xaIn = ptr1[0]; - xcIn = ptr1[4]; - yaIn = ptr1[1]; - ycIn = ptr1[5]; - - /* Butterfly implementation */ - /* xa + xc */ - Xaplusc = xaIn + xcIn; - - xbIn = ptr1[2]; - - /* xa - xc */ - Xaminusc = xaIn - xcIn; - - xdIn = ptr1[6]; - - /* ya + yc */ - Yaplusc = yaIn + ycIn; - - ybIn = ptr1[3]; - - /* ya - yc */ - Yaminusc = yaIn - ycIn; - - ydIn = ptr1[7]; - - /* xc + xd */ - Xbplusd = xbIn + xdIn; - - /* yb + yd */ - Ybplusd = ybIn + ydIn; - - /* xa' = xa + xb + xc + xd */ - ptr1[0] = (Xaplusc + Xbplusd) * onebyfftLen; - - /* (xb-xd) */ - Xbminusd = xbIn - xdIn; - - /* ya' = ya + yb + yc + yd */ - ptr1[1] = (Yaplusc + Ybplusd) * onebyfftLen; - - /* (yb-yd) */ - Ybminusd = ybIn - ydIn; - - /* xc' = (xa-xb+xc-xd) * onebyfftLen */ - ptr1[2] = (Xaplusc - Xbplusd) * onebyfftLen; - - /* yc' = (ya-yb+yc-yd) * onebyfftLen */ - ptr1[3] = (Yaplusc - Ybplusd) * onebyfftLen; - - /* xb' = (xa-yb-xc+yd) * onebyfftLen */ - ptr1[4] = (Xaminusc - Ybminusd) * onebyfftLen; - - /* yb' = (ya+xb-yc-xd) * onebyfftLen */ - ptr1[5] = (Yaminusc + Xbminusd) * onebyfftLen; - - /* xd' = (xa-yb-xc+yd) * onebyfftLen */ - ptr1[6] = (Xaminusc + Ybminusd) * onebyfftLen; - - /* yd' = (ya-xb-yc+xd) * onebyfftLen */ - ptr1[7] = (Yaminusc - Xbminusd) * onebyfftLen; - - /* increment source pointer by 8 for next calculations */ - ptr1 = ptr1 + 8u; - - } while(--j); - -#else - - float32_t t1, t2, r1, r2, s1, s2; - - /* Run the below code for Cortex-M0 */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* Calculation of first stage */ - for (k = fftLen; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* xa + xc */ - r1 = pSrc[(2u * i0)] + pSrc[(2u * i2)]; - - /* xa - xc */ - r2 = pSrc[(2u * i0)] - pSrc[(2u * i2)]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = r1 + t1; - - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = s1 + t2; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (r1 * co2) - (s1 * si2); - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (s1 * co2) + (r1 * si2); - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (r1 * co1) - (s1 * si1); - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (s1 * co1) + (r1 * si1); - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (r2 * co3) - (s2 * si3); - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (s2 * co3) + (r2 * si3); - } - } - twidCoefModifier <<= 2u; - } - /* Initializations of last stage */ - n1 = n2; - n2 >>= 2u; - - /* Calculations of last stage */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xc + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) * onebyfftLen; - - /* (xa + xb) - (xc + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) * onebyfftLen; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb-yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - - /* (xb-xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = r1 * onebyfftLen; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = s1 * onebyfftLen; - - - /* (xa - xc) - (yb-yd) */ - r1 = r2 - t1; - - /* (xa - xc) + (yb-yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb-xd) */ - s1 = s2 + t2; - - /* (ya - yc) - (xb-xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = r1 * onebyfftLen; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = s1 * onebyfftLen; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = r2 * onebyfftLen; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = s2 * onebyfftLen; - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c deleted file mode 100644 index f354e1dde1..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_f32.c +++ /dev/null @@ -1,161 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_f32.c -* -* Description: Radix-4 Decimation in Frequency Floating-point CFFT & CIFFT Initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - -/** -* @brief Initialization function for the floating-point CFFT/CIFFT. -* @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_f32( - arm_cfft_radix4_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialise the FFT length */ - S->fftLen = fftLen; - - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (float32_t *) twiddleCoef; - - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - - case 4096u: - /* Initializations of structure parameters for 4096 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.000244140625; - break; - - case 1024u: - /* Initializations of structure parameters for 1024 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 4u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 4u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - /* Initialise the 1/fftLen Value */ - S->onebyfftLen = 0.0009765625f; - break; - - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - S->onebyfftLen = 0.00390625f; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - S->onebyfftLen = 0.015625f; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - S->onebyfftLen = 0.0625f; - break; - - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix4_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c deleted file mode 100644 index 5ace3483d8..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q15.c +++ /dev/null @@ -1,149 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_q15.c -* -* Description: Radix-4 Decimation in Frequency Q15 FFT & IFFT initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - - -/** -* @brief Initialization function for the Q15 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_q15( - arm_cfft_radix4_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - /* Initialise the FFT length */ - S->fftLen = fftLen; - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q15_t *) twiddleCoefQ15; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLen) - { - case 4096u: - /* Initializations of structure parameters for 4096 point FFT */ - - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - - break; - - case 1024u: - /* Initializations of structure parameters for 1024 point FFT */ - S->twidCoefModifier = 4u; - S->bitRevFactor = 4u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - - break; - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix4_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c deleted file mode 100644 index 6614994f74..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_init_q31.c +++ /dev/null @@ -1,145 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_init_q31.c -* -* Description: Radix-4 Decimation in Frequency Q31 FFT & IFFT initialization function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" -#include "arm_common_tables.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - -/** -* -* @brief Initialization function for the Q31 CFFT/CIFFT. -* @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. -* @param[in] fftLen length of the FFT. -* @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. -* -* \par Description: -* \par -* The parameter ifftFlag controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlag for calculation of CIFFT otherwise CFFT is calculated -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* The parameter fftLen Specifies length of CFFT/CIFFT process. Supported FFT Lengths are 16, 64, 256, 1024. -* \par -* This Function also initializes Twiddle factor table pointer and Bit reversal table pointer. -*/ - -arm_status arm_cfft_radix4_init_q31( - arm_cfft_radix4_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - /* Initialise the FFT length */ - S->fftLen = fftLen; - /* Initialise the Twiddle coefficient pointer */ - S->pTwiddle = (q31_t *) twiddleCoefQ31; - /* Initialise the Flag for selection of CFFT or CIFFT */ - S->ifftFlag = ifftFlag; - /* Initialise the Flag for calculation Bit reversal or not */ - S->bitReverseFlag = bitReverseFlag; - - /* Initializations of Instance structure depending on the FFT length */ - switch (S->fftLen) - { - /* Initializations of structure parameters for 4096 point FFT */ - case 4096u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 1u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 1u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) armBitRevTable; - break; - - /* Initializations of structure parameters for 1024 point FFT */ - case 1024u: - /* Initialise the twiddle coef modifier value */ - S->twidCoefModifier = 4u; - /* Initialise the bit reversal table modifier */ - S->bitRevFactor = 4u; - /* Initialise the bit reversal table pointer */ - S->pBitRevTable = (uint16_t *) & armBitRevTable[3]; - break; - - case 256u: - /* Initializations of structure parameters for 256 point FFT */ - S->twidCoefModifier = 16u; - S->bitRevFactor = 16u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[15]; - break; - - case 64u: - /* Initializations of structure parameters for 64 point FFT */ - S->twidCoefModifier = 64u; - S->bitRevFactor = 64u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[63]; - break; - - case 16u: - /* Initializations of structure parameters for 16 point FFT */ - S->twidCoefModifier = 256u; - S->bitRevFactor = 256u; - S->pBitRevTable = (uint16_t *) & armBitRevTable[255]; - break; - - default: - /* Reporting argument error if fftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - return (status); -} - -/** - * @} end of Radix4_CFFT_CIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c deleted file mode 100644 index 01d476e6c4..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q15.c +++ /dev/null @@ -1,1896 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_q15.c -* -* Description: This file has function definition of Radix-4 FFT & IFFT function and -* In-place bit reversal using bit reversal table -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - - -/** - * @details - * @brief Processing function for the Q15 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - * - * \par Input and output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different FFT sizes. - * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: - * \par - * \image html CFFTQ15.gif "Input and Output Formats for Q15 CFFT" - * \image html CIFFTQ15.gif "Input and Output Formats for Q15 CIFFT" - */ - -void arm_cfft_radix4_q15( - const arm_cfft_radix4_instance_q15 * S, - q15_t * pSrc) -{ - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_q15(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_q15(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_q15(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - -/** - * @} end of Radix4_CFFT_CIFFT group - */ - -/* -* Radix-4 FFT algorithm used is : -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 FFT: -* Wn = co1 + j * (- si1) -* W2n = co2 + j * (- si2) -* W3n = co3 + j * (- si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) -* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) -* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) -* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) -* -*/ - -/** - * @brief Core function for the Q15 CFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t R, S, T, U; - q31_t C1, C2, C3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - q15_t in; - - q15_t *ptr1; - - - - q31_t xaya, xbyb, xcyc, xdyd; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - j = n2; - - /* Input is in 1.15(q15) format */ - - /* start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i0)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* Read yc (real), xc(imag) input */ - S = _SIMD32_OFFSET(pSrc16 + (2u * i2)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* R = packed((ya + yc), (xa + xc) ) */ - R = __QADD16(T, S); - - /* S = packed((ya - yc), (xa - xc) ) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed((yb + yd), (xb + xd) ) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - _SIMD32_OFFSET(pSrc16 + (2u * i0)) = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ - R = __QSUB16(R, T); - - /* co2 & si2 are read from SIMD Coefficient pointer */ - C2 = _SIMD32_OFFSET(pCoef16 + (4u * ic)); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out1 = __SMUAD(C2, R) >> 16u; - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUSDX(C2, R); - -#else - - /* xc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUSDX(R, C2) >> 16u; - /* yc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out2 = __SMUAD(C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+fftLen/4 */ - /* T = packed(yb, xb) */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i1)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - /* U = packed(yd, xd) */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QASX(S, T); - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __QSAX(S, T); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QSAX(S, T); - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __QASX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* co1 & si1 are read from SIMD Coefficient pointer */ - C1 = _SIMD32_OFFSET(pCoef16 + (2u * ic)); - /* Butterfly process for the i0+fftLen/2 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out1 = __SMUAD(C1, S) >> 16u; - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out2 = __SMUSDX(C1, S); - -#else - - /* xb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out1 = __SMUSDX(S, C1) >> 16u; - /* yb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out2 = __SMUAD(C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xb', yb') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i2)) = - ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); - - - /* co3 & si3 are read from SIMD Coefficient pointer */ - C3 = _SIMD32_OFFSET(pCoef16 + (6u * ic)); - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out1 = __SMUAD(C3, R) >> 16u; - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out2 = __SMUSDX(C3, R); - -#else - - /* xd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out1 = __SMUSDX(R, C3) >> 16u; - /* yd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out2 = __SMUAD(C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xd', yd') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i3)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - /* data is in 4.11(q11) format */ - - /* end of first stage process */ - - - /* start of middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - C1 = _SIMD32_OFFSET(pCoef16 + (2u * ic)); - C2 = _SIMD32_OFFSET(pCoef16 + (4u * ic)); - C3 = _SIMD32_OFFSET(pCoef16 + (6u * ic)); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i0)); - - /* Read yc (real), xc(imag) input */ - S = _SIMD32_OFFSET(pSrc16 + (2u * i2)); - - /* R = packed( (ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - - /* T = packed( (yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = __SHADD16(R, T); - in = ((int16_t) (out1 & 0xFFFF)) >> 1; - out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); - _SIMD32_OFFSET(pSrc16 + (2u * i0)) = out1; - - /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out1 = __SMUAD(C2, R) >> 16u; - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUSDX(C2, R); - -#else - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUSDX(R, C2) >> 16u; - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out2 = __SMUAD(C2, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - _SIMD32_OFFSET(pSrc16 + (2u * i1)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHASX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHSAX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUAD(C1, S) >> 16u; - out2 = __SMUSDX(C1, S); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHSAX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHASX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUSDX(S, C1) >> 16u; - out2 = __SMUAD(C1, S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - _SIMD32_OFFSET(pSrc16 + (2u * i2)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUAD(C3, R) >> 16u; - out2 = __SMUSDX(C3, R); - -#else - - out1 = __SMUSDX(R, C3) >> 16u; - out2 = __SMUAD(C3, R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - _SIMD32_OFFSET(pSrc16 + (2u * i3)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* end of middle stage process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* Initializations for the last stage */ - j = fftLen >> 2; - - ptr1 = &pSrc16[0]; - - /* start of last stage process */ - - /* Butterfly implementation */ - do - { - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD32(ptr1)++; - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD32(ptr1)++; - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD32(ptr1)++; - - /* Read xd (real), yd(imag) input */ - xdyd = *__SIMD32(ptr1)++; - - /* R = packed((ya + yc), (xa + xc)) */ - R = __QADD16(xaya, xcyc); - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(xbyb, xdyd); - - /* pointer updation for writing */ - ptr1 = ptr1 - 8u; - - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - *__SIMD32(ptr1)++ = __SHADD16(R, T); - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(xbyb, xdyd); - - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - *__SIMD32(ptr1)++ = __SHSUB16(R, T); - - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(xaya, xcyc); - - /* Read yd (real), xd(imag) input */ - /* T = packed( (yb - yd), (xb - xd)) */ - U = __QSUB16(xbyb, xdyd); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - *__SIMD32(ptr1)++ = __SHSAX(S, U); - - - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - *__SIMD32(ptr1)++ = __SHASX(S, U); - -#else - - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - *__SIMD32(ptr1)++ = __SHASX(S, U); - - - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - *__SIMD32(ptr1)++ = __SHSAX(S, U); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } while(--j); - - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t R0, R1, S0, S1, T0, T1, U0, U1; - q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - j = n2; - - /* Input is in 1.15(q15) format */ - - /* start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - - /* input is down scale by 4 to avoid overflow */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u] >> 2u; - T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; - - /* input is down scale by 4 to avoid overflow */ - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u] >> 2u; - S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; - - /* R0 = (ya + yc) */ - R0 = __SSAT(T0 + S0, 16u); - /* R1 = (xa + xc) */ - R1 = __SSAT(T1 + S1, 16u); - - /* S0 = (ya - yc) */ - S0 = __SSAT(T0 - S0, 16); - /* S1 = (xa - xc) */ - S1 = __SSAT(T1 - S1, 16); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - - /* input is down scale by 4 to avoid overflow */ - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1] >> 2u; - - /* T0 = (yb + yd) */ - T0 = __SSAT(T0 + U0, 16u); - /* T1 = (xb + xd) */ - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* ya' = ya + yb + yc + yd */ - /* xa' = xa + xb + xc + xd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd) */ - /* R1 = (xa + xc) - (xb + xd) */ - R0 = __SSAT(R0 - T0, 16u); - R1 = __SSAT(R1 - T1, 16u); - - /* co2 & si2 are read from Coefficient pointer */ - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[(2u * ic * 2u) + 1]; - - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+fftLen/4 */ - /* input is down scale by 4 to avoid overflow */ - /* T0 = yb, T1 = xb */ - T0 = pSrc16[i1 * 2u] >> 2; - T1 = pSrc16[(i1 * 2u) + 1] >> 2; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1] = out2; - - /* Butterfly calculations */ - /* input is down scale by 4 to avoid overflow */ - /* U0 = yd, U1 = xd */ - U0 = pSrc16[i3 * 2u] >> 2; - U1 = pSrc16[(i3 * 2u) + 1] >> 2; - /* T0 = yb-yd */ - T0 = __SSAT(T0 - U0, 16); - /* T1 = xb-xd */ - T1 = __SSAT(T1 - U1, 16); - - /* R1 = (ya-yc) + (xb- xd), R0 = (xa-xc) - (yb-yd)) */ - R0 = (short) __SSAT((q31_t) (S0 - T1), 16); - R1 = (short) __SSAT((q31_t) (S1 + T0), 16); - - /* S1 = (ya-yc) - (xb- xd), S0 = (xa-xc) + (yb-yd)) */ - S0 = (short) __SSAT(((q31_t) S0 + T1), 16u); - S1 = (short) __SSAT(((q31_t) S1 - T0), 16u); - - /* co1 & si1 are read from Coefficient pointer */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1]; - /* Butterfly process for the i0+fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out1 = (short) ((Si1 * S1 + Co1 * S0) >> 16); - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16); - - /* writing output(xb', yb') in little endian format */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1] = out2; - - /* Co3 & si3 are read from Coefficient pointer */ - Co3 = pCoef16[3u * (ic * 2u)]; - Si3 = pCoef16[(3u * (ic * 2u)) + 1]; - /* Butterfly process for the i0+3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ - out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); - /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ - out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); - /* writing output(xd', yd') in little endian format */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1] = out2; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - /* data is in 4.11(q11) format */ - - /* end of first stage process */ - - - /* start of middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - Co2 = pCoef16[2u * (ic * 2u)]; - Si2 = pCoef16[(2u * (ic * 2u)) + 1u]; - Co3 = pCoef16[3u * (ic * 2u)]; - Si3 = pCoef16[(3u * (ic * 2u)) + 1u]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16); - R1 = __SSAT(T1 + S1, 16); - - /* S0 = (ya - yc), S1 =(xa - xc) */ - S0 = __SSAT(T0 - S0, 16); - S1 = __SSAT(T1 - S1, 16); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16); - T1 = __SSAT(T1 + U1, 16); - - /* writing the butterfly processed i0 sample */ - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; - out2 = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; - - pSrc16[i0 * 2u] = out1; - pSrc16[(2u * i0) + 1u] = out2; - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out1 = (short) ((Co2 * R0 + Si2 * R1) >> 16u); - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((-Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = yb-yd, T1 = xb-xd */ - T0 = __SSAT(T0 - U0, 16); - T1 = __SSAT(T1 - U1, 16); - - /* R0 = (ya-yc) + (xb- xd), R1 = (xa-xc) - (yb-yd)) */ - R0 = (S0 >> 1u) - (T1 >> 1u); - R1 = (S1 >> 1u) + (T0 >> 1u); - - /* S0 = (ya-yc) - (xb- xd), S1 = (xa-xc) + (yb-yd)) */ - S0 = (S0 >> 1u) + (T1 >> 1u); - S1 = (S1 >> 1u) - (T0 >> 1u); - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = (short) ((Co1 * S0 + Si1 * S1) >> 16u); - - out2 = (short) ((-Si1 * S0 + Co1 * S1) >> 16u); - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Butterfly process for the i0+3fftLen/4 sample */ - out1 = (short) ((Si3 * R1 + Co3 * R0) >> 16u); - - out2 = (short) ((-Si3 * R0 + Co3 * R1) >> 16u); - /* xd' = (xa-yb-xc+yd)* Co3 + (ya+xb-yc-xd)* (si3) */ - /* yd' = (ya+xb-yc-xd)* Co3 - (xa-yb-xc+yd)* (si3) */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* end of middle stage process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* start of last stage process */ - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd)) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc16[i1 * 2u] = R0; - pSrc16[(i1 * 2u) + 1u] = R1; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - /* T0 = (yb - yd), T1 = (xb - xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - pSrc16[i2 * 2u] = (S0 >> 1u) + (T1 >> 1u); - pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - pSrc16[i3 * 2u] = (S0 >> 1u) - (T1 >> 1u); - pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); - - } - - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @brief Core function for the Q15 CIFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -/* -* Radix-4 IFFT algorithm used is : -* -* CIFFT uses same twiddle coefficients as CFFT function -* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] -* -* -* IFFT is implemented with following changes in equations from FFT -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 IFFT: -* Wn = co1 + j * (si1) -* W2n = co2 + j * (si2) -* W3n = co3 + j * (si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) -* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) -* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) -* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) -* -*/ - -void arm_radix4_butterfly_inverse_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier) -{ - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - q31_t R, S, T, U; - q31_t C1, C2, C3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - q15_t in; - - q15_t *ptr1; - - - - q31_t xaya, xbyb, xcyc, xdyd; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - j = n2; - - /* Input is in 1.15(q15) format */ - - /* start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i0)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* Read yc (real), xc(imag) input */ - S = _SIMD32_OFFSET(pSrc16 + (2u * i2)); - in = ((int16_t) (S & 0xFFFF)) >> 2; - S = ((S >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* R = packed((ya + yc), (xa + xc) ) */ - R = __QADD16(T, S); - - /* S = packed((ya - yc), (xa - xc) ) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed((yb + yd), (xb + xd) ) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - _SIMD32_OFFSET(pSrc16 + (2u * i0)) = __SHADD16(R, T); - - /* R = packed((ya + yc) - (yb + yd), (xa + xc)- (xb + xd)) */ - R = __QSUB16(R, T); - - /* co2 & si2 are read from SIMD Coefficient pointer */ - C2 = _SIMD32_OFFSET(pCoef16 + (4u * ic)); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out1 = __SMUSD(C2, R) >> 16u; - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUADX(C2, R); - -#else - - /* xc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUADX(C2, R) >> 16u; - /* yc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - out2 = __SMUSD(__QSUB16(0, C2), R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+fftLen/4 */ - /* T = packed(yb, xb) */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - in = ((int16_t) (T & 0xFFFF)) >> 2; - T = ((T >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i1)) = - (q31_t) ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - /* U = packed(yd, xd) */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - in = ((int16_t) (U & 0xFFFF)) >> 2; - U = ((U >> 2) & 0xFFFF0000) | (in & 0xFFFF); - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QSAX(S, T); - /* S = packed((ya-yc) + (xb- xd), (xa-xc) - (yb-yd)) */ - S = __QASX(S, T); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __QASX(S, T); - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __QSAX(S, T); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* co1 & si1 are read from SIMD Coefficient pointer */ - C1 = _SIMD32_OFFSET(pCoef16 + (2u * ic)); - /* Butterfly process for the i0+fftLen/2 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out1 = __SMUSD(C1, S) >> 16u; - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out2 = __SMUADX(C1, S); - -#else - - /* xb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - out1 = __SMUADX(C1, S) >> 16u; - /* yb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - out2 = __SMUSD(__QSUB16(0, C1), S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xb', yb') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i2)) = - ((out2) & 0xFFFF0000) | ((out1) & 0x0000FFFF); - - - /* co3 & si3 are read from SIMD Coefficient pointer */ - C3 = _SIMD32_OFFSET(pCoef16 + (6u * ic)); - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out1 = __SMUSD(C3, R) >> 16u; - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out2 = __SMUADX(C3, R); - -#else - - /* xd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - out1 = __SMUADX(C3, R) >> 16u; - /* yd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - out2 = __SMUSD(__QSUB16(0, C3), R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* writing output(xd', yd') in little endian format */ - _SIMD32_OFFSET(pSrc16 + (2u * i3)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - /* data is in 4.11(q11) format */ - - /* end of first stage process */ - - - /* start of middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - C1 = _SIMD32_OFFSET(pCoef16 + (2u * ic)); - C2 = _SIMD32_OFFSET(pCoef16 + (4u * ic)); - C3 = _SIMD32_OFFSET(pCoef16 + (6u * ic)); - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i0)); - - /* Read yc (real), xc(imag) input */ - S = _SIMD32_OFFSET(pSrc16 + (2u * i2)); - - /* R = packed( (ya + yc), (xa + xc)) */ - R = __QADD16(T, S); - - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(T, S); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - - /* T = packed( (yb + yd), (xb + xd)) */ - T = __QADD16(T, U); - - /* writing the butterfly processed i0 sample */ - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - out1 = __SHADD16(R, T); - in = ((int16_t) (out1 & 0xFFFF)) >> 1; - out1 = ((out1 >> 1) & 0xFFFF0000) | (in & 0xFFFF); - _SIMD32_OFFSET(pSrc16 + (2u * i0)) = out1; - - /* R = packed( (ya + yc) - (yb + yd), (xa + xc) - (xb + xd)) */ - R = __SHSUB16(R, T); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out1 = __SMUSD(C2, R) >> 16u; - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out2 = __SMUADX(C2, R); - -#else - - /* (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - out1 = __SMUADX(R, C2) >> 16u; - - /* (ya-yb+yc-yd)* (si2) + (xa-xb+xc-xd)* co2 */ - out2 = __SMUSD(__QSUB16(0, C2), R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T = _SIMD32_OFFSET(pSrc16 + (2u * i1)); - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) */ - _SIMD32_OFFSET(pSrc16 + (2u * i1)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly calculations */ - - /* Read yd (real), xd(imag) input */ - U = _SIMD32_OFFSET(pSrc16 + (2u * i3)); - - /* T = packed(yb-yd, xb-xd) */ - T = __QSUB16(T, U); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHSAX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHASX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUSD(C1, S) >> 16u; - out2 = __SMUADX(C1, S); - -#else - - /* R = packed((ya-yc) + (xb- xd) , (xa-xc) - (yb-yd)) */ - R = __SHASX(S, T); - - /* S = packed((ya-yc) - (xb- xd), (xa-xc) + (yb-yd)) */ - S = __SHSAX(S, T); - - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = __SMUADX(S, C1) >> 16u; - out2 = __SMUSD(__QSUB16(0, C1), S); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) */ - /* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) */ - _SIMD32_OFFSET(pSrc16 + (2u * i2)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - - /* Butterfly process for the i0+3fftLen/4 sample */ - -#ifndef ARM_MATH_BIG_ENDIAN - - out1 = __SMUSD(C3, R) >> 16u; - out2 = __SMUADX(C3, R); - -#else - - out1 = __SMUADX(C3, R) >> 16u; - out2 = __SMUSD(__QSUB16(0, C3), R); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) */ - /* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) */ - _SIMD32_OFFSET(pSrc16 + (2u * i3)) = - ((out2) & 0xFFFF0000) | (out1 & 0x0000FFFF); - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* end of middle stage process */ - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* Initializations for the last stage */ - j = fftLen >> 2; - - ptr1 = &pSrc16[0]; - - /* start of last stage process */ - - /* Butterfly implementation */ - do - { - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD32(ptr1)++; - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD32(ptr1)++; - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD32(ptr1)++; - - /* Read xd (real), yd(imag) input */ - xdyd = *__SIMD32(ptr1)++; - - /* R = packed((ya + yc), (xa + xc)) */ - R = __QADD16(xaya, xcyc); - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(xbyb, xdyd); - - /* pointer updation for writing */ - ptr1 = ptr1 - 8u; - - - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - *__SIMD32(ptr1)++ = __SHADD16(R, T); - - /* T = packed((yb + yd), (xb + xd)) */ - T = __QADD16(xbyb, xdyd); - - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - *__SIMD32(ptr1)++ = __SHSUB16(R, T); - - /* S = packed((ya - yc), (xa - xc)) */ - S = __QSUB16(xaya, xcyc); - - /* Read yd (real), xd(imag) input */ - /* T = packed( (yb - yd), (xb - xd)) */ - U = __QSUB16(xbyb, xdyd); - -#ifndef ARM_MATH_BIG_ENDIAN - - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - *__SIMD32(ptr1)++ = __SHASX(S, U); - - - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - *__SIMD32(ptr1)++ = __SHSAX(S, U); - -#else - - /* xb' = (xa+yb-xc-yd) */ - /* yb' = (ya-xb-yc+xd) */ - *__SIMD32(ptr1)++ = __SHSAX(S, U); - - - /* xd' = (xa-yb-xc+yd) */ - /* yd' = (ya+xb-yc-xd) */ - *__SIMD32(ptr1)++ = __SHASX(S, U); - - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - } while(--j); - - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - - -#else - - /* Run the below code for Cortex-M0 */ - - q15_t R0, R1, S0, S1, T0, T1, U0, U1; - q15_t Co1, Si1, Co2, Si2, Co3, Si3, out1, out2; - uint32_t n1, n2, ic, i0, i1, i2, i3, j, k; - - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - - /* n2 = fftLen/4 */ - n2 >>= 2u; - - /* Index for twiddle coefficient */ - ic = 0u; - - /* Index for input read and output write */ - i0 = 0u; - - j = n2; - - /* Input is in 1.15(q15) format */ - - /* Start of first stage process */ - do - { - /* Butterfly implementation */ - - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u] >> 2u; - T1 = pSrc16[(i0 * 2u) + 1u] >> 2u; - /* input is down scale by 4 to avoid overflow */ - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u] >> 2u; - S1 = pSrc16[(i2 * 2u) + 1u] >> 2u; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* input is down scale by 4 to avoid overflow */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - /* Read yd (real), xd(imag) input */ - /* input is down scale by 4 to avoid overflow */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc)- (xb + xd) */ - R0 = __SSAT(R0 - T0, 16u); - R1 = __SSAT(R1 - T1, 16u); - /* co2 & si2 are read from Coefficient pointer */ - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[(2u * ic * 2u) + 1u]; - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16u); - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16u); - - /* Reading i0+fftLen/4 */ - /* input is down scale by 4 to avoid overflow */ - /* T0 = yb, T1 = xb */ - T0 = pSrc16[i1 * 2u] >> 2u; - T1 = pSrc16[(i1 * 2u) + 1u] >> 2u; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* writing output(xc', yc') in little endian format */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - /* input is down scale by 4 to avoid overflow */ - /* U0 = yd, U1 = xd) */ - U0 = pSrc16[i3 * 2u] >> 2u; - U1 = pSrc16[(i3 * 2u) + 1u] >> 2u; - - /* T0 = yb-yd, T1 = xb-xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ - R0 = (short) __SSAT((q31_t) (S0 + T1), 16); - R1 = (short) __SSAT((q31_t) (S1 - T0), 16); - /* S = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ - S0 = (short) __SSAT((q31_t) (S0 - T1), 16); - S1 = (short) __SSAT((q31_t) (S1 + T0), 16); - - /* co1 & si1 are read from Coefficient pointer */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - /* Butterfly process for the i0+fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); - /* writing output(xb', yb') in little endian format */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Co3 & si3 are read from Coefficient pointer */ - Co3 = pCoef16[3u * ic * 2u]; - Si3 = pCoef16[(3u * ic * 2u) + 1u]; - /* Butterfly process for the i0+3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ - out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); - /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ - out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); - /* writing output(xd', yd') in little endian format */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* End of first stage process */ - - /* data is in 4.11(q11) format */ - - - /* Start of Middle stage process */ - - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - - /* Calculation of Middle stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the middle stage */ - n1 = n2; - n2 >>= 2u; - ic = 0u; - - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - Co1 = pCoef16[ic * 2u]; - Si1 = pCoef16[(ic * 2u) + 1u]; - Co2 = pCoef16[2u * ic * 2u]; - Si2 = pCoef16[2u * ic * 2u + 1u]; - Co3 = pCoef16[3u * ic * 2u]; - Si3 = pCoef16[(3u * ic * 2u) + 1u]; - - /* Twiddle coefficients index modifier */ - ic = ic + twidCoefModifier; - - /* Butterfly implementation */ - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = ((R0 >> 1u) + (T0 >> 1u)) >> 1u; - pSrc16[(i0 * 2u) + 1u] = ((R1 >> 1u) + (T1 >> 1u)) >> 1u; - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* (ya-yb+yc-yd)* (si2) - (xa-xb+xc-xd)* co2 */ - out1 = (short) ((Co2 * R0 - Si2 * R1) >> 16); - /* (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - out2 = (short) ((Si2 * R0 + Co2 * R1) >> 16); - - /* Reading i0+3fftLen/4 */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) */ - /* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) */ - pSrc16[i1 * 2u] = out1; - pSrc16[(i1 * 2u) + 1u] = out2; - - /* Butterfly calculations */ - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = yb-yd, T1 = xb-xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* R0 = (ya-yc) - (xb- xd) , R1 = (xa-xc) + (yb-yd) */ - R0 = (S0 >> 1u) + (T1 >> 1u); - R1 = (S1 >> 1u) - (T0 >> 1u); - - /* S1 = (ya-yc) + (xb- xd), S1 = (xa-xc) - (yb-yd) */ - S0 = (S0 >> 1u) - (T1 >> 1u); - S1 = (S1 >> 1u) + (T0 >> 1u); - - /* Butterfly process for the i0+fftLen/2 sample */ - out1 = (short) ((Co1 * S0 - Si1 * S1) >> 16u); - out2 = (short) ((Si1 * S0 + Co1 * S1) >> 16u); - /* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) */ - /* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) */ - pSrc16[i2 * 2u] = out1; - pSrc16[(i2 * 2u) + 1u] = out2; - - /* Butterfly process for the i0+3fftLen/4 sample */ - out1 = (short) ((Co3 * R0 - Si3 * R1) >> 16u); - - out2 = (short) ((Si3 * R0 + Co3 * R1) >> 16u); - /* xd' = (xa+yb-xc-yd)* Co3 - (ya-xb-yc+xd)* (si3) */ - /* yd' = (ya-xb-yc+xd)* Co3 + (xa+yb-xc-yd)* (si3) */ - pSrc16[i3 * 2u] = out1; - pSrc16[(i3 * 2u) + 1u] = out2; - - - } - } - /* Twiddle coefficients index modifier */ - twidCoefModifier <<= 2u; - } - /* End of Middle stages process */ - - - /* data is in 10.6(q6) format for the 1024 point */ - /* data is in 8.8(q8) format for the 256 point */ - /* data is in 6.10(q10) format for the 64 point */ - /* data is in 4.12(q12) format for the 16 point */ - - /* start of last stage process */ - - - /* Initializations for the last stage */ - n1 = n2; - n2 >>= 2u; - - /* Butterfly implementation */ - for (i0 = 0u; i0 <= (fftLen - n1); i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc16[i0 + 0], pSrc16[i0 + fftLen/4], pSrc16[i0 + fftLen/2], pSrc16[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Reading i0, i0+fftLen/2 inputs */ - /* Read ya (real), xa(imag) input */ - T0 = pSrc16[i0 * 2u]; - T1 = pSrc16[(i0 * 2u) + 1u]; - /* Read yc (real), xc(imag) input */ - S0 = pSrc16[i2 * 2u]; - S1 = pSrc16[(i2 * 2u) + 1u]; - - /* R0 = (ya + yc), R1 = (xa + xc) */ - R0 = __SSAT(T0 + S0, 16u); - R1 = __SSAT(T1 + S1, 16u); - /* S0 = (ya - yc), S1 = (xa - xc) */ - S0 = __SSAT(T0 - S0, 16u); - S1 = __SSAT(T1 - S1, 16u); - - /* Reading i0+fftLen/4 , i0+3fftLen/4 inputs */ - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - - /* T0 = (yb + yd), T1 = (xb + xd) */ - T0 = __SSAT(T0 + U0, 16u); - T1 = __SSAT(T1 + U1, 16u); - - /* writing the butterfly processed i0 sample */ - /* xa' = xa + xb + xc + xd */ - /* ya' = ya + yb + yc + yd */ - pSrc16[i0 * 2u] = (R0 >> 1u) + (T0 >> 1u); - pSrc16[(i0 * 2u) + 1u] = (R1 >> 1u) + (T1 >> 1u); - - /* R0 = (ya + yc) - (yb + yd), R1 = (xa + xc) - (xb + xd) */ - R0 = (R0 >> 1u) - (T0 >> 1u); - R1 = (R1 >> 1u) - (T1 >> 1u); - - /* Read yb (real), xb(imag) input */ - T0 = pSrc16[i1 * 2u]; - T1 = pSrc16[(i1 * 2u) + 1u]; - - /* writing the butterfly processed i0 + fftLen/4 sample */ - /* xc' = (xa-xb+xc-xd) */ - /* yc' = (ya-yb+yc-yd) */ - pSrc16[i1 * 2u] = R0; - pSrc16[(i1 * 2u) + 1u] = R1; - - /* Read yd (real), xd(imag) input */ - U0 = pSrc16[i3 * 2u]; - U1 = pSrc16[(i3 * 2u) + 1u]; - /* T0 = (yb - yd), T1 = (xb - xd) */ - T0 = __SSAT(T0 - U0, 16u); - T1 = __SSAT(T1 - U1, 16u); - - /* writing the butterfly processed i0 + fftLen/2 sample */ - /* xb' = (xa-yb-xc+yd) */ - /* yb' = (ya+xb-yc-xd) */ - pSrc16[i2 * 2u] = (S0 >> 1u) - (T1 >> 1u); - pSrc16[(i2 * 2u) + 1u] = (S1 >> 1u) + (T0 >> 1u); - - - /* writing the butterfly processed i0 + 3fftLen/4 sample */ - /* xd' = (xa+yb-xc-yd) */ - /* yd' = (ya-xb-yc+xd) */ - pSrc16[i3 * 2u] = (S0 >> 1u) + (T1 >> 1u); - pSrc16[(i3 * 2u) + 1u] = (S1 >> 1u) - (T0 >> 1u); - } - /* end of last stage process */ - - /* output is in 11.5(q5) format for the 1024 point */ - /* output is in 9.7(q7) format for the 256 point */ - /* output is in 7.9(q9) format for the 64 point */ - /* output is in 5.11(q11) format for the 16 point */ - -#endif /* #ifndef ARM_MATH_CM0 */ - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c deleted file mode 100644 index 3a5c523dff..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_cfft_radix4_q31.c +++ /dev/null @@ -1,891 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_cfft_radix4_q31.c -* -* Description: This file has function definition of Radix-4 FFT & IFFT function and -* In-place bit reversal using bit reversal table -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.5 2010/04/26 -* incorporated review comments and updated with latest CMSIS layer -* -* Version 0.0.3 2010/03/10 -* Initial version -* -------------------------------------------------------------------- */ -#include "arm_math.h" - - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup Radix4_CFFT_CIFFT - * @{ - */ - -/** - * @details - * @brief Processing function for the Q31 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q31 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer of size 2*fftLen. Processing occurs in-place. - * @return none. - * - * \par Input and output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different FFT sizes. - * The input and output formats for different FFT sizes and number of bits to upscale are mentioned in the tables below for CFFT and CIFFT: - * \par - * \image html CFFTQ31.gif "Input and Output Formats for Q31 CFFT" - * \image html CIFFTQ31.gif "Input and Output Formats for Q31 CIFFT" - * - */ - -void arm_cfft_radix4_q31( - const arm_cfft_radix4_instance_q31 * S, - q31_t * pSrc) -{ - if(S->ifftFlag == 1u) - { - /* Complex IFFT radix-4 */ - arm_radix4_butterfly_inverse_q31(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - else - { - /* Complex FFT radix-4 */ - arm_radix4_butterfly_q31(pSrc, S->fftLen, S->pTwiddle, - S->twidCoefModifier); - } - - - if(S->bitReverseFlag == 1u) - { - /* Bit Reversal */ - arm_bitreversal_q31(pSrc, S->fftLen, S->bitRevFactor, S->pBitRevTable); - } - -} - -/** - * @} end of Radix4_CFFT_CIFFT group - */ - -/* -* Radix-4 FFT algorithm used is : -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 FFT: -* Wn = co1 + j * (- si1) -* W2n = co2 + j * (- si2) -* W3n = co3 + j * (- si3) -* -* Butterfly implementation: -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa+yb-xc-yd)* co1 + (ya-xb-yc+xd)* (si1) -* yb' = (ya-xb-yc+xd)* co1 - (xa+yb-xc-yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 + (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 - (xa-xb+xc-xd)* (si2) -* xd' = (xa-yb-xc+yd)* co3 + (ya+xb-yc-xd)* (si3) -* yd' = (ya+xb-yc-xd)* co3 - (xa-yb-xc+yd)* (si3) -* -*/ - -/** - * @brief Core function for the Q31 CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_radix4_butterfly_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier) -{ - uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; - q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; - - q31_t xa, xb, xc, xd; - q31_t ya, yb, yc, yd; - q31_t xa_out, xb_out, xc_out, xd_out; - q31_t ya_out, yb_out, yc_out, yd_out; - - q31_t *ptr1; - q63_t xaya, xbyb, xcyc, xdyd; - /* Total process is divided into three stages */ - - /* process first stage, middle stages, & last stage */ - - - /* start of first stage process */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - /* Calculation of first stage */ - do - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* input is in 1.31(q31) format and provide 4 guard bits for the input */ - - /* Butterfly implementation */ - /* xa + xc */ - r1 = (pSrc[(2u * i0)] >> 4u) + (pSrc[(2u * i2)] >> 4u); - /* xa - xc */ - r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); - - /* xb + xd */ - t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); - - /* ya + yc */ - s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); - /* ya - yc */ - s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); - - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); - /* xb - xd */ - t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); - - /* index calculation for the coefficients */ - ia2 = 2u * ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + - ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - - ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + - ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - - ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; - - /* index calculation for the coefficients */ - ia3 = 3u * ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + - ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - - ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* end of first stage process */ - - /* data is in 5.27(q27) format */ - - - /* start of Middle stages process */ - - - /* each stage in middle stages provides two down scaling of the input */ - - twidCoefModifier <<= 2u; - - - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - /* Calculation of first stage */ - for (j = 0u; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) >> 2u; - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 + (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) + - ((int32_t) (((q63_t) s1 * si2) >> 32))) >> 1u; - - /* yc' = (ya-yb+yc-yd)co2 - (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) - - ((int32_t) (((q63_t) r1 * si2) >> 32))) >> 1u; - - /* (xa - xc) + (yb - yd) */ - r1 = r2 + t1; - /* (xa - xc) - (yb - yd) */ - r2 = r2 - t1; - - /* (ya - yc) - (xb - xd) */ - s1 = s2 - t2; - /* (ya - yc) + (xb - xd) */ - s2 = s2 + t2; - - /* xb' = (xa+yb-xc-yd)co1 + (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) + - ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; - - /* yb' = (ya-xb-yc+xd)co1 - (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) - - ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; - - /* xd' = (xa-yb-xc+yd)co3 + (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) + - ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; - - /* yd' = (ya+xb-yc-xd)co3 - (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) - - ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; - } - } - twidCoefModifier <<= 2u; - } - - /* End of Middle stages process */ - - /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ - /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ - /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ - /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ - - - /* start of Last stage process */ - /* Initializations for the last stage */ - j = fftLen >> 2; - ptr1 = &pSrc[0]; - - /* Calculations of last stage */ - do - { - -#ifndef ARM_MATH_BIG_ENDIAN - - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD64(ptr1)++; - xa = (q31_t) xaya; - ya = (q31_t) (xaya >> 32); - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD64(ptr1)++; - xb = (q31_t) xbyb; - yb = (q31_t) (xbyb >> 32); - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD64(ptr1)++; - xc = (q31_t) xcyc; - yc = (q31_t) (xcyc >> 32); - - /* Read xc (real), yc(imag) input */ - xdyd = *__SIMD64(ptr1)++; - xd = (q31_t) xdyd; - yd = (q31_t) (xdyd >> 32); - -#else - - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD64(ptr1)++; - ya = (q31_t) xaya; - xa = (q31_t) (xaya >> 32); - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD64(ptr1)++; - yb = (q31_t) xbyb; - xb = (q31_t) (xbyb >> 32); - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD64(ptr1)++; - yc = (q31_t) xcyc; - xc = (q31_t) (xcyc >> 32); - - /* Read xc (real), yc(imag) input */ - xdyd = *__SIMD64(ptr1)++; - yd = (q31_t) xdyd; - xd = (q31_t) (xdyd >> 32); - - -#endif - - /* xa' = xa + xb + xc + xd */ - xa_out = xa + xb + xc + xd; - - /* ya' = ya + yb + yc + yd */ - ya_out = ya + yb + yc + yd; - - /* pointer updation for writing */ - ptr1 = ptr1 - 8u; - - /* writing xa' and ya' */ - *ptr1++ = xa_out; - *ptr1++ = ya_out; - - xc_out = (xa - xb + xc - xd); - yc_out = (ya - yb + yc - yd); - - /* writing xc' and yc' */ - *ptr1++ = xc_out; - *ptr1++ = yc_out; - - xb_out = (xa + yb - xc - yd); - yb_out = (ya - xb - yc + xd); - - /* writing xb' and yb' */ - *ptr1++ = xb_out; - *ptr1++ = yb_out; - - xd_out = (xa - yb - xc + yd); - yd_out = (ya + xb - yc - xd); - - /* writing xd' and yd' */ - *ptr1++ = xd_out; - *ptr1++ = yd_out; - - - } while(--j); - - /* output is in 11.21(q21) format for the 1024 point */ - /* output is in 9.23(q23) format for the 256 point */ - /* output is in 7.25(q25) format for the 64 point */ - /* output is in 5.27(q27) format for the 16 point */ - - /* End of last stage process */ - -} - - -/** - * @brief Core function for the Q31 CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - -/* -* Radix-4 IFFT algorithm used is : -* -* CIFFT uses same twiddle coefficients as CFFT Function -* x[k] = x[n] + (j)k * x[n + fftLen/4] + (-1)k * x[n+fftLen/2] + (-j)k * x[n+3*fftLen/4] -* -* -* IFFT is implemented with following changes in equations from FFT -* -* Input real and imaginary data: -* x(n) = xa + j * ya -* x(n+N/4 ) = xb + j * yb -* x(n+N/2 ) = xc + j * yc -* x(n+3N 4) = xd + j * yd -* -* -* Output real and imaginary data: -* x(4r) = xa'+ j * ya' -* x(4r+1) = xb'+ j * yb' -* x(4r+2) = xc'+ j * yc' -* x(4r+3) = xd'+ j * yd' -* -* -* Twiddle factors for radix-4 IFFT: -* Wn = co1 + j * (si1) -* W2n = co2 + j * (si2) -* W3n = co3 + j * (si3) - -* The real and imaginary output values for the radix-4 butterfly are -* xa' = xa + xb + xc + xd -* ya' = ya + yb + yc + yd -* xb' = (xa-yb-xc+yd)* co1 - (ya+xb-yc-xd)* (si1) -* yb' = (ya+xb-yc-xd)* co1 + (xa-yb-xc+yd)* (si1) -* xc' = (xa-xb+xc-xd)* co2 - (ya-yb+yc-yd)* (si2) -* yc' = (ya-yb+yc-yd)* co2 + (xa-xb+xc-xd)* (si2) -* xd' = (xa+yb-xc-yd)* co3 - (ya-xb-yc+xd)* (si3) -* yd' = (ya-xb-yc+xd)* co3 + (xa+yb-xc-yd)* (si3) -* -*/ - -void arm_radix4_butterfly_inverse_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier) -{ - uint32_t n1, n2, ia1, ia2, ia3, i0, i1, i2, i3, j, k; - q31_t t1, t2, r1, r2, s1, s2, co1, co2, co3, si1, si2, si3; - q31_t xa, xb, xc, xd; - q31_t ya, yb, yc, yd; - q31_t xa_out, xb_out, xc_out, xd_out; - q31_t ya_out, yb_out, yc_out, yd_out; - - q31_t *ptr1; - q63_t xaya, xbyb, xcyc, xdyd; - - /* input is be 1.31(q31) format for all FFT sizes */ - /* Total process is divided into three stages */ - /* process first stage, middle stages, & last stage */ - - /* Start of first stage process */ - - /* Initializations for the first stage */ - n2 = fftLen; - n1 = n2; - /* n2 = fftLen/4 */ - n2 >>= 2u; - i0 = 0u; - ia1 = 0u; - - j = n2; - - do - { - - /* input is in 1.31(q31) format and provide 4 guard bits for the input */ - - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = (pSrc[2u * i0] >> 4u) + (pSrc[2u * i2] >> 4u); - /* xa - xc */ - r2 = (pSrc[2u * i0] >> 4u) - (pSrc[2u * i2] >> 4u); - - /* xb + xd */ - t1 = (pSrc[2u * i1] >> 4u) + (pSrc[2u * i3] >> 4u); - - /* ya + yc */ - s1 = (pSrc[(2u * i0) + 1u] >> 4u) + (pSrc[(2u * i2) + 1u] >> 4u); - /* ya - yc */ - s2 = (pSrc[(2u * i0) + 1u] >> 4u) - (pSrc[(2u * i2) + 1u] >> 4u); - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1); - /* (xa + xc) - (xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = (pSrc[(2u * i1) + 1u] >> 4u) + (pSrc[(2u * i3) + 1u] >> 4u); - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2); - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* yb - yd */ - t1 = (pSrc[(2u * i1) + 1u] >> 4u) - (pSrc[(2u * i3) + 1u] >> 4u); - /* xb - xd */ - t2 = (pSrc[2u * i1] >> 4u) - (pSrc[2u * i3] >> 4u); - - /* index calculation for the coefficients */ - ia2 = 2u * ia1; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32)) - - ((int32_t) (((q63_t) s1 * si2) >> 32))) << 1u; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[2u * i1 + 1u] = (((int32_t) (((q63_t) s1 * co2) >> 32)) + - ((int32_t) (((q63_t) r1 * si2) >> 32))) << 1u; - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - - ((int32_t) (((q63_t) s1 * si1) >> 32))) << 1u; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + - ((int32_t) (((q63_t) r1 * si1) >> 32))) << 1u; - - /* index calculation for the coefficients */ - ia3 = 3u * ia1; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[2u * i3] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - - ((int32_t) (((q63_t) s2 * si3) >> 32))) << 1u; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + - ((int32_t) (((q63_t) r2 * si3) >> 32))) << 1u; - - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - /* Updating input index */ - i0 = i0 + 1u; - - } while(--j); - - /* data is in 5.27(q27) format */ - /* each stage provides two down scaling of the input */ - - - /* Start of Middle stages process */ - - twidCoefModifier <<= 2u; - - /* Calculation of second stage to excluding last stage */ - for (k = fftLen / 4u; k > 4u; k >>= 2u) - { - /* Initializations for the first stage */ - n1 = n2; - n2 >>= 2u; - ia1 = 0u; - - for (j = 0; j <= (n2 - 1u); j++) - { - /* index calculation for the coefficients */ - ia2 = ia1 + ia1; - ia3 = ia2 + ia1; - co1 = pCoef[ia1 * 2u]; - si1 = pCoef[(ia1 * 2u) + 1u]; - co2 = pCoef[ia2 * 2u]; - si2 = pCoef[(ia2 * 2u) + 1u]; - co3 = pCoef[ia3 * 2u]; - si3 = pCoef[(ia3 * 2u) + 1u]; - /* Twiddle coefficients index modifier */ - ia1 = ia1 + twidCoefModifier; - - for (i0 = j; i0 < fftLen; i0 += n1) - { - /* index calculation for the input as, */ - /* pSrc[i0 + 0], pSrc[i0 + fftLen/4], pSrc[i0 + fftLen/2u], pSrc[i0 + 3fftLen/4] */ - i1 = i0 + n2; - i2 = i1 + n2; - i3 = i2 + n2; - - /* Butterfly implementation */ - /* xa + xc */ - r1 = pSrc[2u * i0] + pSrc[2u * i2]; - /* xa - xc */ - r2 = pSrc[2u * i0] - pSrc[2u * i2]; - - /* ya + yc */ - s1 = pSrc[(2u * i0) + 1u] + pSrc[(2u * i2) + 1u]; - /* ya - yc */ - s2 = pSrc[(2u * i0) + 1u] - pSrc[(2u * i2) + 1u]; - - /* xb + xd */ - t1 = pSrc[2u * i1] + pSrc[2u * i3]; - - /* xa' = xa + xb + xc + xd */ - pSrc[2u * i0] = (r1 + t1) >> 2u; - /* xa + xc -(xb + xd) */ - r1 = r1 - t1; - /* yb + yd */ - t2 = pSrc[(2u * i1) + 1u] + pSrc[(2u * i3) + 1u]; - /* ya' = ya + yb + yc + yd */ - pSrc[(2u * i0) + 1u] = (s1 + t2) >> 2u; - - /* (ya + yc) - (yb + yd) */ - s1 = s1 - t2; - - /* (yb - yd) */ - t1 = pSrc[(2u * i1) + 1u] - pSrc[(2u * i3) + 1u]; - /* (xb - xd) */ - t2 = pSrc[2u * i1] - pSrc[2u * i3]; - - /* xc' = (xa-xb+xc-xd)co2 - (ya-yb+yc-yd)(si2) */ - pSrc[2u * i1] = (((int32_t) (((q63_t) r1 * co2) >> 32u)) - - ((int32_t) (((q63_t) s1 * si2) >> 32u))) >> 1u; - - /* yc' = (ya-yb+yc-yd)co2 + (xa-xb+xc-xd)(si2) */ - pSrc[(2u * i1) + 1u] = - (((int32_t) (((q63_t) s1 * co2) >> 32u)) + - ((int32_t) (((q63_t) r1 * si2) >> 32u))) >> 1u; - - /* (xa - xc) - (yb - yd) */ - r1 = r2 - t1; - /* (xa - xc) + (yb - yd) */ - r2 = r2 + t1; - - /* (ya - yc) + (xb - xd) */ - s1 = s2 + t2; - /* (ya - yc) - (xb - xd) */ - s2 = s2 - t2; - - /* xb' = (xa+yb-xc-yd)co1 - (ya-xb-yc+xd)(si1) */ - pSrc[2u * i2] = (((int32_t) (((q63_t) r1 * co1) >> 32)) - - ((int32_t) (((q63_t) s1 * si1) >> 32))) >> 1u; - - /* yb' = (ya-xb-yc+xd)co1 + (xa+yb-xc-yd)(si1) */ - pSrc[(2u * i2) + 1u] = (((int32_t) (((q63_t) s1 * co1) >> 32)) + - ((int32_t) (((q63_t) r1 * si1) >> 32))) >> 1u; - - /* xd' = (xa-yb-xc+yd)co3 - (ya+xb-yc-xd)(si3) */ - pSrc[(2u * i3)] = (((int32_t) (((q63_t) r2 * co3) >> 32)) - - ((int32_t) (((q63_t) s2 * si3) >> 32))) >> 1u; - - /* yd' = (ya+xb-yc-xd)co3 + (xa-yb-xc+yd)(si3) */ - pSrc[(2u * i3) + 1u] = (((int32_t) (((q63_t) s2 * co3) >> 32)) + - ((int32_t) (((q63_t) r2 * si3) >> 32))) >> 1u; - } - } - twidCoefModifier <<= 2u; - } - - /* End of Middle stages process */ - - /* data is in 11.21(q21) format for the 1024 point as there are 3 middle stages */ - /* data is in 9.23(q23) format for the 256 point as there are 2 middle stages */ - /* data is in 7.25(q25) format for the 64 point as there are 1 middle stage */ - /* data is in 5.27(q27) format for the 16 point as there are no middle stages */ - - - /* Start of last stage process */ - - - /* Initializations for the last stage */ - j = fftLen >> 2; - ptr1 = &pSrc[0]; - - /* Calculations of last stage */ - do - { -#ifndef ARM_MATH_BIG_ENDIAN - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD64(ptr1)++; - xa = (q31_t) xaya; - ya = (q31_t) (xaya >> 32); - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD64(ptr1)++; - xb = (q31_t) xbyb; - yb = (q31_t) (xbyb >> 32); - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD64(ptr1)++; - xc = (q31_t) xcyc; - yc = (q31_t) (xcyc >> 32); - - /* Read xc (real), yc(imag) input */ - xdyd = *__SIMD64(ptr1)++; - xd = (q31_t) xdyd; - yd = (q31_t) (xdyd >> 32); - -#else - - /* Read xa (real), ya(imag) input */ - xaya = *__SIMD64(ptr1)++; - ya = (q31_t) xaya; - xa = (q31_t) (xaya >> 32); - - /* Read xb (real), yb(imag) input */ - xbyb = *__SIMD64(ptr1)++; - yb = (q31_t) xbyb; - xb = (q31_t) (xbyb >> 32); - - /* Read xc (real), yc(imag) input */ - xcyc = *__SIMD64(ptr1)++; - yc = (q31_t) xcyc; - xc = (q31_t) (xcyc >> 32); - - /* Read xc (real), yc(imag) input */ - xdyd = *__SIMD64(ptr1)++; - yd = (q31_t) xdyd; - xd = (q31_t) (xdyd >> 32); - - -#endif - - /* xa' = xa + xb + xc + xd */ - xa_out = xa + xb + xc + xd; - - /* ya' = ya + yb + yc + yd */ - ya_out = ya + yb + yc + yd; - - /* pointer updation for writing */ - ptr1 = ptr1 - 8u; - - /* writing xa' and ya' */ - *ptr1++ = xa_out; - *ptr1++ = ya_out; - - xc_out = (xa - xb + xc - xd); - yc_out = (ya - yb + yc - yd); - - /* writing xc' and yc' */ - *ptr1++ = xc_out; - *ptr1++ = yc_out; - - xb_out = (xa - yb - xc + yd); - yb_out = (ya + xb - yc - xd); - - /* writing xb' and yb' */ - *ptr1++ = xb_out; - *ptr1++ = yb_out; - - xd_out = (xa + yb - xc - yd); - yd_out = (ya - xb - yc + xd); - - /* writing xd' and yd' */ - *ptr1++ = xd_out; - *ptr1++ = yd_out; - - - } while(--j); - - /* output is in 11.21(q21) format for the 1024 point */ - /* output is in 9.23(q23) format for the 256 point */ - /* output is in 7.25(q25) format for the 64 point */ - /* output is in 5.27(q27) format for the 16 point */ - - /* End of last stage process */ -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c deleted file mode 100644 index fb79e31726..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_f32.c +++ /dev/null @@ -1,453 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_f32.c -* -* Description: Processing function of DCT4 & IDCT4 F32. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup DCT4_IDCT4 DCT Type IV Functions - * Representation of signals by minimum number of values is important for storage and transmission. - * The possibility of large discontinuity between the beginning and end of a period of a signal - * in DFT can be avoided by extending the signal so that it is even-symmetric. - * Discrete Cosine Transform (DCT) is constructed such that its energy is heavily concentrated in the lower part of the - * spectrum and is very widely used in signal and image coding applications. - * The family of DCTs (DCT type- 1,2,3,4) is the outcome of different combinations of homogeneous boundary conditions. - * DCT has an excellent energy-packing capability, hence has many applications and in data compression in particular. - * - * DCT is essentially the Discrete Fourier Transform(DFT) of an even-extended real signal. - * Reordering of the input data makes the computation of DCT just a problem of - * computing the DFT of a real signal with a few additional operations. - * This approach provides regular, simple, and very efficient DCT algorithms for practical hardware and software implementations. - * - * DCT type-II can be implemented using Fast fourier transform (FFT) internally, as the transform is applied on real values, Real FFT can be used. - * DCT4 is implemented using DCT2 as their implementations are similar except with some added pre-processing and post-processing. - * DCT2 implementation can be described in the following steps: - * - Re-ordering input - * - Calculating Real FFT - * - Multiplication of weights and Real FFT output and getting real part from the product. - * - * This process is explained by the block diagram below: - * \image html DCT4.gif "Discrete Cosine Transform - type-IV" - * - * \par Algorithm: - * The N-point type-IV DCT is defined as a real, linear transformation by the formula: - * \image html DCT4Equation.gif - * where k = 0,1,2,.....N-1 - *\par - * Its inverse is defined as follows: - * \image html IDCT4Equation.gif - * where n = 0,1,2,.....N-1 - *\par - * The DCT4 matrices become involutory (i.e. they are self-inverse) by multiplying with an overall scale factor of sqrt(2/N). - * The symmetry of the transform matrix indicates that the fast algorithms for the forward - * and inverse transform computation are identical. - * Note that the implementation of Inverse DCT4 and DCT4 is same, hence same process function can be used for both. - * - * \par Lengths supported by the transform: - * As DCT4 internally uses Real FFT, it supports all the lengths supported by arm_rfft_f32(). - * The library provides separate functions for Q15, Q31, and floating-point data types. - * \par Instance Structure - * The instances for Real FFT and FFT, cosine values table and twiddle factor table are stored in an instance data structure. - * A separate instance structure must be defined for each transform. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes Real FFT as its process function is used internally in DCT4, by calling arm_rfft_init_f32(). - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
    
- *arm_dct4_instance_f32 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};    
- *arm_dct4_instance_q31 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};   
- *arm_dct4_instance_q15 S = {N, Nby2, normalize, pTwiddle, pCosFactor, pRfft, pCfft};   
- * 
- * where \c N is the length of the DCT4; \c Nby2 is half of the length of the DCT4; - * \c normalize is normalizing factor used and is equal to sqrt(2/N); - * \c pTwiddle points to the twiddle factor table; - * \c pCosFactor points to the cosFactor table; - * \c pRfft points to the real FFT instance; - * \c pCfft points to the complex FFT instance; - * The CFFT and RFFT structures also needs to be initialized, refer to arm_cfft_radix4_f32() - * and arm_rfft_f32() respectively for details regarding static initialization. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the DCT4 transform functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the floating-point DCT4/IDCT4. - * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - */ - -void arm_dct4_f32( - const arm_dct4_instance_f32 * S, - float32_t * pState, - float32_t * pInlineBuffer) -{ - uint32_t i; /* Loop counter */ - float32_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - float32_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - float32_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - float32_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_scale_f32(pInlineBuffer, 2.0f, pInlineBuffer, S->N); - arm_mult_f32(pInlineBuffer, cosFact, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as, - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = (uint32_t) S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_f32(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = ((uint32_t) S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ * (float32_t) 0.5; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = ((uint32_t) S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - in = *pbuff; - *pbuff++ = in * S->normalize; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = (uint32_t) S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_f32(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_f32(pState, weights, pState, S->N); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ * (float32_t) 0.5; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* Initializing the loop counter */ - i = ((uint32_t) S->N - 1u); - - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = in * S->normalize; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c deleted file mode 100644 index b5f91ea325..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_f32.c +++ /dev/null @@ -1,16511 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_f32.c -* -* Description: Initialization function of DCT-4 & IDCT4 F32 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
    
-* for(i = 0; i< N; i++)    
-* {    
-*    weights[2*i]= cos(i*c);    
-*    weights[(2*i)+1]= -sin(i * c);    
-* } 
-* \par -* Where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const float32_t Weights_128[256] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999924701839144500f, - -0.012271538285719925f, - 0.999698818696204250f, -0.024541228522912288f, 0.999322384588349540f, - -0.036807222941358832f, - 0.998795456205172410f, -0.049067674327418015f, 0.998118112900149180f, - -0.061320736302208578f, - 0.997290456678690210f, -0.073564563599667426f, 0.996312612182778000f, - -0.085797312344439894f, - 0.995184726672196930f, -0.098017140329560604f, 0.993906970002356060f, - -0.110222207293883060f, - 0.992479534598709970f, -0.122410675199216200f, 0.990902635427780010f, - -0.134580708507126170f, - 0.989176509964781010f, -0.146730474455361750f, 0.987301418157858430f, - -0.158858143333861450f, - 0.985277642388941220f, -0.170961888760301220f, 0.983105487431216290f, - -0.183039887955140950f, - 0.980785280403230430f, -0.195090322016128250f, 0.978317370719627650f, - -0.207111376192218560f, - 0.975702130038528570f, -0.219101240156869800f, 0.972939952205560180f, - -0.231058108280671110f, - 0.970031253194543970f, -0.242980179903263870f, 0.966976471044852070f, - -0.254865659604514570f, - 0.963776065795439840f, -0.266712757474898370f, 0.960430519415565790f, - -0.278519689385053060f, - 0.956940335732208820f, -0.290284677254462330f, 0.953306040354193860f, - -0.302005949319228080f, - 0.949528180593036670f, -0.313681740398891520f, 0.945607325380521280f, - -0.325310292162262930f, - 0.941544065183020810f, -0.336889853392220050f, 0.937339011912574960f, - -0.348418680249434560f, - 0.932992798834738960f, -0.359895036534988110f, 0.928506080473215590f, - -0.371317193951837540f, - 0.923879532511286740f, -0.382683432365089780f, 0.919113851690057770f, - -0.393992040061048100f, - 0.914209755703530690f, -0.405241314004989860f, 0.909167983090522380f, - -0.416429560097637150f, - 0.903989293123443340f, -0.427555093430282080f, 0.898674465693953820f, - -0.438616238538527660f, - 0.893224301195515320f, -0.449611329654606540f, 0.887639620402853930f, - -0.460538710958240010f, - 0.881921264348355050f, -0.471396736825997640f, 0.876070094195406600f, - -0.482183772079122720f, - 0.870086991108711460f, -0.492898192229784040f, 0.863972856121586810f, - -0.503538383725717580f, - 0.857728610000272120f, -0.514102744193221660f, 0.851355193105265200f, - -0.524589682678468950f, - 0.844853565249707120f, -0.534997619887097150f, 0.838224705554838080f, - -0.545324988422046460f, - 0.831469612302545240f, -0.555570233019602180f, 0.824589302785025290f, - -0.565731810783613120f, - 0.817584813151583710f, -0.575808191417845340f, 0.810457198252594770f, - -0.585797857456438860f, - 0.803207531480644940f, -0.595699304492433360f, 0.795836904608883570f, - -0.605511041404325550f, - 0.788346427626606340f, -0.615231590580626820f, 0.780737228572094490f, - -0.624859488142386340f, - 0.773010453362736990f, -0.634393284163645490f, 0.765167265622458960f, - -0.643831542889791390f, - 0.757208846506484570f, -0.653172842953776760f, 0.749136394523459370f, - -0.662415777590171780f, - 0.740951125354959110f, -0.671558954847018330f, 0.732654271672412820f, - -0.680600997795453020f, - 0.724247082951467000f, -0.689540544737066830f, 0.715730825283818590f, - -0.698376249408972920f, - 0.707106781186547570f, -0.707106781186547460f, 0.698376249408972920f, - -0.715730825283818590f, - 0.689540544737066940f, -0.724247082951466890f, 0.680600997795453130f, - -0.732654271672412820f, - 0.671558954847018330f, -0.740951125354959110f, 0.662415777590171780f, - -0.749136394523459260f, - 0.653172842953776760f, -0.757208846506484460f, 0.643831542889791500f, - -0.765167265622458960f, - 0.634393284163645490f, -0.773010453362736990f, 0.624859488142386450f, - -0.780737228572094380f, - 0.615231590580626820f, -0.788346427626606230f, 0.605511041404325550f, - -0.795836904608883460f, - 0.595699304492433470f, -0.803207531480644830f, 0.585797857456438860f, - -0.810457198252594770f, - 0.575808191417845340f, -0.817584813151583710f, 0.565731810783613230f, - -0.824589302785025290f, - 0.555570233019602290f, -0.831469612302545240f, 0.545324988422046460f, - -0.838224705554837970f, - 0.534997619887097260f, -0.844853565249707010f, 0.524589682678468840f, - -0.851355193105265200f, - 0.514102744193221660f, -0.857728610000272120f, 0.503538383725717580f, - -0.863972856121586700f, - 0.492898192229784090f, -0.870086991108711350f, 0.482183772079122830f, - -0.876070094195406600f, - 0.471396736825997810f, -0.881921264348354940f, 0.460538710958240010f, - -0.887639620402853930f, - 0.449611329654606600f, -0.893224301195515320f, 0.438616238538527710f, - -0.898674465693953820f, - 0.427555093430282200f, -0.903989293123443340f, 0.416429560097637320f, - -0.909167983090522270f, - 0.405241314004989860f, -0.914209755703530690f, 0.393992040061048100f, - -0.919113851690057770f, - 0.382683432365089840f, -0.923879532511286740f, 0.371317193951837600f, - -0.928506080473215480f, - 0.359895036534988280f, -0.932992798834738850f, 0.348418680249434510f, - -0.937339011912574960f, - 0.336889853392220050f, -0.941544065183020810f, 0.325310292162262980f, - -0.945607325380521280f, - 0.313681740398891570f, -0.949528180593036670f, 0.302005949319228200f, - -0.953306040354193750f, - 0.290284677254462330f, -0.956940335732208940f, 0.278519689385053060f, - -0.960430519415565790f, - 0.266712757474898420f, -0.963776065795439840f, 0.254865659604514630f, - -0.966976471044852070f, - 0.242980179903263980f, -0.970031253194543970f, 0.231058108280671280f, - -0.972939952205560070f, - 0.219101240156869770f, -0.975702130038528570f, 0.207111376192218560f, - -0.978317370719627650f, - 0.195090322016128330f, -0.980785280403230430f, 0.183039887955141060f, - -0.983105487431216290f, - 0.170961888760301360f, -0.985277642388941220f, 0.158858143333861390f, - -0.987301418157858430f, - 0.146730474455361750f, -0.989176509964781010f, 0.134580708507126220f, - -0.990902635427780010f, - 0.122410675199216280f, -0.992479534598709970f, 0.110222207293883180f, - -0.993906970002356060f, - 0.098017140329560770f, -0.995184726672196820f, 0.085797312344439880f, - -0.996312612182778000f, - 0.073564563599667454f, -0.997290456678690210f, 0.061320736302208648f, - -0.998118112900149180f, - 0.049067674327418126f, -0.998795456205172410f, 0.036807222941358991f, - -0.999322384588349540f, - 0.024541228522912264f, -0.999698818696204250f, 0.012271538285719944f, - -0.999924701839144500f -}; - -static const float32_t Weights_512[1024] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999995293809576190f, - -0.003067956762965976f, - 0.999981175282601110f, -0.006135884649154475f, 0.999957644551963900f, - -0.009203754782059819f, - 0.999924701839144500f, -0.012271538285719925f, 0.999882347454212560f, - -0.015339206284988100f, - 0.999830581795823400f, -0.018406729905804820f, 0.999769405351215280f, - -0.021474080275469508f, - 0.999698818696204250f, -0.024541228522912288f, 0.999618822495178640f, - -0.027608145778965740f, - 0.999529417501093140f, -0.030674803176636626f, 0.999430604555461730f, - -0.033741171851377580f, - 0.999322384588349540f, -0.036807222941358832f, 0.999204758618363890f, - -0.039872927587739811f, - 0.999077727752645360f, -0.042938256934940820f, 0.998941293186856870f, - -0.046003182130914623f, - 0.998795456205172410f, -0.049067674327418015f, 0.998640218180265270f, - -0.052131704680283324f, - 0.998475580573294770f, -0.055195244349689934f, 0.998301544933892890f, - -0.058258264500435752f, - 0.998118112900149180f, -0.061320736302208578f, 0.997925286198596000f, - -0.064382630929857465f, - 0.997723066644191640f, -0.067443919563664051f, 0.997511456140303450f, - -0.070504573389613856f, - 0.997290456678690210f, -0.073564563599667426f, 0.997060070339482960f, - -0.076623861392031492f, - 0.996820299291165670f, -0.079682437971430126f, 0.996571145790554840f, - -0.082740264549375692f, - 0.996312612182778000f, -0.085797312344439894f, 0.996044700901251970f, - -0.088853552582524600f, - 0.995767414467659820f, -0.091908956497132724f, 0.995480755491926940f, - -0.094963495329638992f, - 0.995184726672196930f, -0.098017140329560604f, 0.994879330794805620f, - -0.101069862754827820f, - 0.994564570734255420f, -0.104121633872054590f, 0.994240449453187900f, - -0.107172424956808840f, - 0.993906970002356060f, -0.110222207293883060f, 0.993564135520595300f, - -0.113270952177564350f, - 0.993211949234794500f, -0.116318630911904750f, 0.992850414459865100f, - -0.119365214810991350f, - 0.992479534598709970f, -0.122410675199216200f, 0.992099313142191800f, - -0.125454983411546230f, - 0.991709753669099530f, -0.128498110793793170f, 0.991310859846115440f, - -0.131540028702883120f, - 0.990902635427780010f, -0.134580708507126170f, 0.990485084256457090f, - -0.137620121586486040f, - 0.990058210262297120f, -0.140658239332849210f, 0.989622017463200890f, - -0.143695033150294470f, - 0.989176509964781010f, -0.146730474455361750f, 0.988721691960323780f, - -0.149764534677321510f, - 0.988257567730749460f, -0.152797185258443440f, 0.987784141644572180f, - -0.155828397654265230f, - 0.987301418157858430f, -0.158858143333861450f, 0.986809401814185530f, - -0.161886393780111830f, - 0.986308097244598670f, -0.164913120489969890f, 0.985797509167567480f, - -0.167938294974731170f, - 0.985277642388941220f, -0.170961888760301220f, 0.984748501801904210f, - -0.173983873387463820f, - 0.984210092386929030f, -0.177004220412148750f, 0.983662419211730250f, - -0.180022901405699510f, - 0.983105487431216290f, -0.183039887955140950f, 0.982539302287441240f, - -0.186055151663446630f, - 0.981963869109555240f, -0.189068664149806190f, 0.981379193313754560f, - -0.192080397049892440f, - 0.980785280403230430f, -0.195090322016128250f, 0.980182135968117430f, - -0.198098410717953560f, - 0.979569765685440520f, -0.201104634842091900f, 0.978948175319062200f, - -0.204108966092816870f, - 0.978317370719627650f, -0.207111376192218560f, 0.977677357824509930f, - -0.210111836880469610f, - 0.977028142657754390f, -0.213110319916091360f, 0.976369731330021140f, - -0.216106797076219520f, - 0.975702130038528570f, -0.219101240156869800f, 0.975025345066994120f, - -0.222093620973203510f, - 0.974339382785575860f, -0.225083911359792830f, 0.973644249650811980f, - -0.228072083170885730f, - 0.972939952205560180f, -0.231058108280671110f, 0.972226497078936270f, - -0.234041958583543430f, - 0.971503890986251780f, -0.237023605994367200f, 0.970772140728950350f, - -0.240003022448741500f, - 0.970031253194543970f, -0.242980179903263870f, 0.969281235356548530f, - -0.245955050335794590f, - 0.968522094274417380f, -0.248927605745720150f, 0.967753837093475510f, - -0.251897818154216970f, - 0.966976471044852070f, -0.254865659604514570f, 0.966190003445412500f, - -0.257831102162158990f, - 0.965394441697689400f, -0.260794117915275510f, 0.964589793289812760f, - -0.263754678974831350f, - 0.963776065795439840f, -0.266712757474898370f, 0.962953266873683880f, - -0.269668325572915090f, - 0.962121404269041580f, -0.272621355449948980f, 0.961280485811320640f, - -0.275571819310958140f, - 0.960430519415565790f, -0.278519689385053060f, 0.959571513081984520f, - -0.281464937925757940f, - 0.958703474895871600f, -0.284407537211271880f, 0.957826413027532910f, - -0.287347459544729510f, - 0.956940335732208820f, -0.290284677254462330f, 0.956045251349996410f, - -0.293219162694258630f, - 0.955141168305770780f, -0.296150888243623790f, 0.954228095109105670f, - -0.299079826308040480f, - 0.953306040354193860f, -0.302005949319228080f, 0.952375012719765880f, - -0.304929229735402370f, - 0.951435020969008340f, -0.307849640041534870f, 0.950486073949481700f, - -0.310767152749611470f, - 0.949528180593036670f, -0.313681740398891520f, 0.948561349915730270f, - -0.316593375556165850f, - 0.947585591017741090f, -0.319502030816015690f, 0.946600913083283530f, - -0.322407678801069850f, - 0.945607325380521280f, -0.325310292162262930f, 0.944604837261480260f, - -0.328209843579092500f, - 0.943593458161960390f, -0.331106305759876430f, 0.942573197601446870f, - -0.333999651442009380f, - 0.941544065183020810f, -0.336889853392220050f, 0.940506070593268300f, - -0.339776884406826850f, - 0.939459223602189920f, -0.342660717311994380f, 0.938403534063108060f, - -0.345541324963989090f, - 0.937339011912574960f, -0.348418680249434560f, 0.936265667170278260f, - -0.351292756085567090f, - 0.935183509938947610f, -0.354163525420490340f, 0.934092550404258980f, - -0.357030961233429980f, - 0.932992798834738960f, -0.359895036534988110f, 0.931884265581668150f, - -0.362755724367397230f, - 0.930766961078983710f, -0.365612997804773850f, 0.929640895843181330f, - -0.368466829953372320f, - 0.928506080473215590f, -0.371317193951837540f, 0.927362525650401110f, - -0.374164062971457930f, - 0.926210242138311380f, -0.377007410216418260f, 0.925049240782677580f, - -0.379847208924051160f, - 0.923879532511286740f, -0.382683432365089780f, 0.922701128333878630f, - -0.385516053843918850f, - 0.921514039342042010f, -0.388345046698826250f, 0.920318276709110590f, - -0.391170384302253870f, - 0.919113851690057770f, -0.393992040061048100f, 0.917900775621390500f, - -0.396809987416710310f, - 0.916679059921042700f, -0.399624199845646790f, 0.915448716088267830f, - -0.402434650859418430f, - 0.914209755703530690f, -0.405241314004989860f, 0.912962190428398210f, - -0.408044162864978690f, - 0.911706032005429880f, -0.410843171057903910f, 0.910441292258067250f, - -0.413638312238434500f, - 0.909167983090522380f, -0.416429560097637150f, 0.907886116487666260f, - -0.419216888363223910f, - 0.906595704514915330f, -0.422000270799799680f, 0.905296759318118820f, - -0.424779681209108810f, - 0.903989293123443340f, -0.427555093430282080f, 0.902673318237258830f, - -0.430326481340082610f, - 0.901348847046022030f, -0.433093818853151960f, 0.900015892016160280f, - -0.435857079922255470f, - 0.898674465693953820f, -0.438616238538527660f, 0.897324580705418320f, - -0.441371268731716670f, - 0.895966249756185220f, -0.444122144570429200f, 0.894599485631382700f, - -0.446868840162374160f, - 0.893224301195515320f, -0.449611329654606540f, 0.891840709392342720f, - -0.452349587233770890f, - 0.890448723244757880f, -0.455083587126343840f, 0.889048355854664570f, - -0.457813303598877170f, - 0.887639620402853930f, -0.460538710958240010f, 0.886222530148880640f, - -0.463259783551860150f, - 0.884797098430937790f, -0.465976495767966180f, 0.883363338665731580f, - -0.468688822035827900f, - 0.881921264348355050f, -0.471396736825997640f, 0.880470889052160750f, - -0.474100214650549970f, - 0.879012226428633530f, -0.476799230063322090f, 0.877545290207261350f, - -0.479493757660153010f, - 0.876070094195406600f, -0.482183772079122720f, 0.874586652278176110f, - -0.484869248000791060f, - 0.873094978418290090f, -0.487550160148436000f, 0.871595086655950980f, - -0.490226483288291160f, - 0.870086991108711460f, -0.492898192229784040f, 0.868570705971340900f, - -0.495565261825772540f, - 0.867046245515692650f, -0.498227666972781870f, 0.865513624090569090f, - -0.500885382611240710f, - 0.863972856121586810f, -0.503538383725717580f, 0.862423956111040610f, - -0.506186645345155230f, - 0.860866938637767310f, -0.508830142543106990f, 0.859301818357008470f, - -0.511468850437970300f, - 0.857728610000272120f, -0.514102744193221660f, 0.856147328375194470f, - -0.516731799017649870f, - 0.854557988365400530f, -0.519355990165589640f, 0.852960604930363630f, - -0.521975292937154390f, - 0.851355193105265200f, -0.524589682678468950f, 0.849741768000852550f, - -0.527199134781901280f, - 0.848120344803297230f, -0.529803624686294610f, 0.846490938774052130f, - -0.532403127877197900f, - 0.844853565249707120f, -0.534997619887097150f, 0.843208239641845440f, - -0.537587076295645390f, - 0.841554977436898440f, -0.540171472729892850f, 0.839893794195999520f, - -0.542750784864515890f, - 0.838224705554838080f, -0.545324988422046460f, 0.836547727223512010f, - -0.547894059173100190f, - 0.834862874986380010f, -0.550457972936604810f, 0.833170164701913190f, - -0.553016705580027470f, - 0.831469612302545240f, -0.555570233019602180f, 0.829761233794523050f, - -0.558118531220556100f, - 0.828045045257755800f, -0.560661576197336030f, 0.826321062845663530f, - -0.563199344013834090f, - 0.824589302785025290f, -0.565731810783613120f, 0.822849781375826430f, - -0.568258952670131490f, - 0.821102514991104650f, -0.570780745886967260f, 0.819347520076796900f, - -0.573297166698042200f, - 0.817584813151583710f, -0.575808191417845340f, 0.815814410806733780f, - -0.578313796411655590f, - 0.814036329705948410f, -0.580813958095764530f, 0.812250586585203880f, - -0.583308652937698290f, - 0.810457198252594770f, -0.585797857456438860f, 0.808656181588174980f, - -0.588281548222645220f, - 0.806847553543799330f, -0.590759701858874160f, 0.805031331142963660f, - -0.593232295039799800f, - 0.803207531480644940f, -0.595699304492433360f, 0.801376171723140240f, - -0.598160706996342270f, - 0.799537269107905010f, -0.600616479383868970f, 0.797690840943391160f, - -0.603066598540348160f, - 0.795836904608883570f, -0.605511041404325550f, 0.793975477554337170f, - -0.607949784967773630f, - 0.792106577300212390f, -0.610382806276309480f, 0.790230221437310030f, - -0.612810082429409710f, - 0.788346427626606340f, -0.615231590580626820f, 0.786455213599085770f, - -0.617647307937803870f, - 0.784556597155575240f, -0.620057211763289100f, 0.782650596166575730f, - -0.622461279374149970f, - 0.780737228572094490f, -0.624859488142386340f, 0.778816512381475980f, - -0.627251815495144080f, - 0.776888465673232440f, -0.629638238914926980f, 0.774953106594873930f, - -0.632018735939809060f, - 0.773010453362736990f, -0.634393284163645490f, 0.771060524261813820f, - -0.636761861236284200f, - 0.769103337645579700f, -0.639124444863775730f, 0.767138911935820400f, - -0.641481012808583160f, - 0.765167265622458960f, -0.643831542889791390f, 0.763188417263381270f, - -0.646176012983316280f, - 0.761202385484261780f, -0.648514401022112440f, 0.759209188978388070f, - -0.650846684996380880f, - 0.757208846506484570f, -0.653172842953776760f, 0.755201376896536550f, - -0.655492852999615350f, - 0.753186799043612520f, -0.657806693297078640f, 0.751165131909686480f, - -0.660114342067420480f, - 0.749136394523459370f, -0.662415777590171780f, 0.747100605980180130f, - -0.664710978203344790f, - 0.745057785441466060f, -0.666999922303637470f, 0.743007952135121720f, - -0.669282588346636010f, - 0.740951125354959110f, -0.671558954847018330f, 0.738887324460615110f, - -0.673829000378756040f, - 0.736816568877369900f, -0.676092703575315920f, 0.734738878095963500f, - -0.678350043129861470f, - 0.732654271672412820f, -0.680600997795453020f, 0.730562769227827590f, - -0.682845546385248080f, - 0.728464390448225200f, -0.685083667772700360f, 0.726359155084346010f, - -0.687315340891759050f, - 0.724247082951467000f, -0.689540544737066830f, 0.722128193929215350f, - -0.691759258364157750f, - 0.720002507961381650f, -0.693971460889654000f, 0.717870045055731710f, - -0.696177131491462990f, - 0.715730825283818590f, -0.698376249408972920f, 0.713584868780793640f, - -0.700568793943248340f, - 0.711432195745216430f, -0.702754744457225300f, 0.709272826438865690f, - -0.704934080375904880f, - 0.707106781186547570f, -0.707106781186547460f, 0.704934080375904990f, - -0.709272826438865580f, - 0.702754744457225300f, -0.711432195745216430f, 0.700568793943248450f, - -0.713584868780793520f, - 0.698376249408972920f, -0.715730825283818590f, 0.696177131491462990f, - -0.717870045055731710f, - 0.693971460889654000f, -0.720002507961381650f, 0.691759258364157750f, - -0.722128193929215350f, - 0.689540544737066940f, -0.724247082951466890f, 0.687315340891759160f, - -0.726359155084346010f, - 0.685083667772700360f, -0.728464390448225200f, 0.682845546385248080f, - -0.730562769227827590f, - 0.680600997795453130f, -0.732654271672412820f, 0.678350043129861580f, - -0.734738878095963390f, - 0.676092703575316030f, -0.736816568877369790f, 0.673829000378756150f, - -0.738887324460615110f, - 0.671558954847018330f, -0.740951125354959110f, 0.669282588346636010f, - -0.743007952135121720f, - 0.666999922303637470f, -0.745057785441465950f, 0.664710978203344900f, - -0.747100605980180130f, - 0.662415777590171780f, -0.749136394523459260f, 0.660114342067420480f, - -0.751165131909686370f, - 0.657806693297078640f, -0.753186799043612410f, 0.655492852999615460f, - -0.755201376896536550f, - 0.653172842953776760f, -0.757208846506484460f, 0.650846684996380990f, - -0.759209188978387960f, - 0.648514401022112550f, -0.761202385484261780f, 0.646176012983316390f, - -0.763188417263381270f, - 0.643831542889791500f, -0.765167265622458960f, 0.641481012808583160f, - -0.767138911935820400f, - 0.639124444863775730f, -0.769103337645579590f, 0.636761861236284200f, - -0.771060524261813710f, - 0.634393284163645490f, -0.773010453362736990f, 0.632018735939809060f, - -0.774953106594873820f, - 0.629638238914927100f, -0.776888465673232440f, 0.627251815495144190f, - -0.778816512381475870f, - 0.624859488142386450f, -0.780737228572094380f, 0.622461279374150080f, - -0.782650596166575730f, - 0.620057211763289210f, -0.784556597155575240f, 0.617647307937803980f, - -0.786455213599085770f, - 0.615231590580626820f, -0.788346427626606230f, 0.612810082429409710f, - -0.790230221437310030f, - 0.610382806276309480f, -0.792106577300212390f, 0.607949784967773740f, - -0.793975477554337170f, - 0.605511041404325550f, -0.795836904608883460f, 0.603066598540348280f, - -0.797690840943391040f, - 0.600616479383868970f, -0.799537269107905010f, 0.598160706996342380f, - -0.801376171723140130f, - 0.595699304492433470f, -0.803207531480644830f, 0.593232295039799800f, - -0.805031331142963660f, - 0.590759701858874280f, -0.806847553543799220f, 0.588281548222645330f, - -0.808656181588174980f, - 0.585797857456438860f, -0.810457198252594770f, 0.583308652937698290f, - -0.812250586585203880f, - 0.580813958095764530f, -0.814036329705948300f, 0.578313796411655590f, - -0.815814410806733780f, - 0.575808191417845340f, -0.817584813151583710f, 0.573297166698042320f, - -0.819347520076796900f, - 0.570780745886967370f, -0.821102514991104650f, 0.568258952670131490f, - -0.822849781375826320f, - 0.565731810783613230f, -0.824589302785025290f, 0.563199344013834090f, - -0.826321062845663420f, - 0.560661576197336030f, -0.828045045257755800f, 0.558118531220556100f, - -0.829761233794523050f, - 0.555570233019602290f, -0.831469612302545240f, 0.553016705580027580f, - -0.833170164701913190f, - 0.550457972936604810f, -0.834862874986380010f, 0.547894059173100190f, - -0.836547727223511890f, - 0.545324988422046460f, -0.838224705554837970f, 0.542750784864516000f, - -0.839893794195999410f, - 0.540171472729892970f, -0.841554977436898330f, 0.537587076295645510f, - -0.843208239641845440f, - 0.534997619887097260f, -0.844853565249707010f, 0.532403127877198010f, - -0.846490938774052020f, - 0.529803624686294830f, -0.848120344803297120f, 0.527199134781901390f, - -0.849741768000852440f, - 0.524589682678468840f, -0.851355193105265200f, 0.521975292937154390f, - -0.852960604930363630f, - 0.519355990165589530f, -0.854557988365400530f, 0.516731799017649980f, - -0.856147328375194470f, - 0.514102744193221660f, -0.857728610000272120f, 0.511468850437970520f, - -0.859301818357008360f, - 0.508830142543106990f, -0.860866938637767310f, 0.506186645345155450f, - -0.862423956111040500f, - 0.503538383725717580f, -0.863972856121586700f, 0.500885382611240940f, - -0.865513624090568980f, - 0.498227666972781870f, -0.867046245515692650f, 0.495565261825772490f, - -0.868570705971340900f, - 0.492898192229784090f, -0.870086991108711350f, 0.490226483288291100f, - -0.871595086655951090f, - 0.487550160148436050f, -0.873094978418290090f, 0.484869248000791120f, - -0.874586652278176110f, - 0.482183772079122830f, -0.876070094195406600f, 0.479493757660153010f, - -0.877545290207261240f, - 0.476799230063322250f, -0.879012226428633410f, 0.474100214650550020f, - -0.880470889052160750f, - 0.471396736825997810f, -0.881921264348354940f, 0.468688822035827960f, - -0.883363338665731580f, - 0.465976495767966130f, -0.884797098430937790f, 0.463259783551860260f, - -0.886222530148880640f, - 0.460538710958240010f, -0.887639620402853930f, 0.457813303598877290f, - -0.889048355854664570f, - 0.455083587126343840f, -0.890448723244757880f, 0.452349587233771000f, - -0.891840709392342720f, - 0.449611329654606600f, -0.893224301195515320f, 0.446868840162374330f, - -0.894599485631382580f, - 0.444122144570429260f, -0.895966249756185110f, 0.441371268731716620f, - -0.897324580705418320f, - 0.438616238538527710f, -0.898674465693953820f, 0.435857079922255470f, - -0.900015892016160280f, - 0.433093818853152010f, -0.901348847046022030f, 0.430326481340082610f, - -0.902673318237258830f, - 0.427555093430282200f, -0.903989293123443340f, 0.424779681209108810f, - -0.905296759318118820f, - 0.422000270799799790f, -0.906595704514915330f, 0.419216888363223960f, - -0.907886116487666150f, - 0.416429560097637320f, -0.909167983090522270f, 0.413638312238434560f, - -0.910441292258067140f, - 0.410843171057903910f, -0.911706032005429880f, 0.408044162864978740f, - -0.912962190428398100f, - 0.405241314004989860f, -0.914209755703530690f, 0.402434650859418540f, - -0.915448716088267830f, - 0.399624199845646790f, -0.916679059921042700f, 0.396809987416710420f, - -0.917900775621390390f, - 0.393992040061048100f, -0.919113851690057770f, 0.391170384302253980f, - -0.920318276709110480f, - 0.388345046698826300f, -0.921514039342041900f, 0.385516053843919020f, - -0.922701128333878520f, - 0.382683432365089840f, -0.923879532511286740f, 0.379847208924051110f, - -0.925049240782677580f, - 0.377007410216418310f, -0.926210242138311270f, 0.374164062971457990f, - -0.927362525650401110f, - 0.371317193951837600f, -0.928506080473215480f, 0.368466829953372320f, - -0.929640895843181330f, - 0.365612997804773960f, -0.930766961078983710f, 0.362755724367397230f, - -0.931884265581668150f, - 0.359895036534988280f, -0.932992798834738850f, 0.357030961233430030f, - -0.934092550404258870f, - 0.354163525420490510f, -0.935183509938947500f, 0.351292756085567150f, - -0.936265667170278260f, - 0.348418680249434510f, -0.937339011912574960f, 0.345541324963989150f, - -0.938403534063108060f, - 0.342660717311994380f, -0.939459223602189920f, 0.339776884406826960f, - -0.940506070593268300f, - 0.336889853392220050f, -0.941544065183020810f, 0.333999651442009490f, - -0.942573197601446870f, - 0.331106305759876430f, -0.943593458161960390f, 0.328209843579092660f, - -0.944604837261480260f, - 0.325310292162262980f, -0.945607325380521280f, 0.322407678801070020f, - -0.946600913083283530f, - 0.319502030816015750f, -0.947585591017741090f, 0.316593375556165850f, - -0.948561349915730270f, - 0.313681740398891570f, -0.949528180593036670f, 0.310767152749611470f, - -0.950486073949481700f, - 0.307849640041534980f, -0.951435020969008340f, 0.304929229735402430f, - -0.952375012719765880f, - 0.302005949319228200f, -0.953306040354193750f, 0.299079826308040480f, - -0.954228095109105670f, - 0.296150888243623960f, -0.955141168305770670f, 0.293219162694258680f, - -0.956045251349996410f, - 0.290284677254462330f, -0.956940335732208940f, 0.287347459544729570f, - -0.957826413027532910f, - 0.284407537211271820f, -0.958703474895871600f, 0.281464937925758050f, - -0.959571513081984520f, - 0.278519689385053060f, -0.960430519415565790f, 0.275571819310958250f, - -0.961280485811320640f, - 0.272621355449948980f, -0.962121404269041580f, 0.269668325572915200f, - -0.962953266873683880f, - 0.266712757474898420f, -0.963776065795439840f, 0.263754678974831510f, - -0.964589793289812650f, - 0.260794117915275570f, -0.965394441697689400f, 0.257831102162158930f, - -0.966190003445412620f, - 0.254865659604514630f, -0.966976471044852070f, 0.251897818154216910f, - -0.967753837093475510f, - 0.248927605745720260f, -0.968522094274417270f, 0.245955050335794590f, - -0.969281235356548530f, - 0.242980179903263980f, -0.970031253194543970f, 0.240003022448741500f, - -0.970772140728950350f, - 0.237023605994367340f, -0.971503890986251780f, 0.234041958583543460f, - -0.972226497078936270f, - 0.231058108280671280f, -0.972939952205560070f, 0.228072083170885790f, - -0.973644249650811870f, - 0.225083911359792780f, -0.974339382785575860f, 0.222093620973203590f, - -0.975025345066994120f, - 0.219101240156869770f, -0.975702130038528570f, 0.216106797076219600f, - -0.976369731330021140f, - 0.213110319916091360f, -0.977028142657754390f, 0.210111836880469720f, - -0.977677357824509930f, - 0.207111376192218560f, -0.978317370719627650f, 0.204108966092817010f, - -0.978948175319062200f, - 0.201104634842091960f, -0.979569765685440520f, 0.198098410717953730f, - -0.980182135968117320f, - 0.195090322016128330f, -0.980785280403230430f, 0.192080397049892380f, - -0.981379193313754560f, - 0.189068664149806280f, -0.981963869109555240f, 0.186055151663446630f, - -0.982539302287441240f, - 0.183039887955141060f, -0.983105487431216290f, 0.180022901405699510f, - -0.983662419211730250f, - 0.177004220412148860f, -0.984210092386929030f, 0.173983873387463850f, - -0.984748501801904210f, - 0.170961888760301360f, -0.985277642388941220f, 0.167938294974731230f, - -0.985797509167567370f, - 0.164913120489970090f, -0.986308097244598670f, 0.161886393780111910f, - -0.986809401814185420f, - 0.158858143333861390f, -0.987301418157858430f, 0.155828397654265320f, - -0.987784141644572180f, - 0.152797185258443410f, -0.988257567730749460f, 0.149764534677321620f, - -0.988721691960323780f, - 0.146730474455361750f, -0.989176509964781010f, 0.143695033150294580f, - -0.989622017463200780f, - 0.140658239332849240f, -0.990058210262297120f, 0.137620121586486180f, - -0.990485084256456980f, - 0.134580708507126220f, -0.990902635427780010f, 0.131540028702883280f, - -0.991310859846115440f, - 0.128498110793793220f, -0.991709753669099530f, 0.125454983411546210f, - -0.992099313142191800f, - 0.122410675199216280f, -0.992479534598709970f, 0.119365214810991350f, - -0.992850414459865100f, - 0.116318630911904880f, -0.993211949234794500f, 0.113270952177564360f, - -0.993564135520595300f, - 0.110222207293883180f, -0.993906970002356060f, 0.107172424956808870f, - -0.994240449453187900f, - 0.104121633872054730f, -0.994564570734255420f, 0.101069862754827880f, - -0.994879330794805620f, - 0.098017140329560770f, -0.995184726672196820f, 0.094963495329639061f, - -0.995480755491926940f, - 0.091908956497132696f, -0.995767414467659820f, 0.088853552582524684f, - -0.996044700901251970f, - 0.085797312344439880f, -0.996312612182778000f, 0.082740264549375803f, - -0.996571145790554840f, - 0.079682437971430126f, -0.996820299291165670f, 0.076623861392031617f, - -0.997060070339482960f, - 0.073564563599667454f, -0.997290456678690210f, 0.070504573389614009f, - -0.997511456140303450f, - 0.067443919563664106f, -0.997723066644191640f, 0.064382630929857410f, - -0.997925286198596000f, - 0.061320736302208648f, -0.998118112900149180f, 0.058258264500435732f, - -0.998301544933892890f, - 0.055195244349690031f, -0.998475580573294770f, 0.052131704680283317f, - -0.998640218180265270f, - 0.049067674327418126f, -0.998795456205172410f, 0.046003182130914644f, - -0.998941293186856870f, - 0.042938256934940959f, -0.999077727752645360f, 0.039872927587739845f, - -0.999204758618363890f, - 0.036807222941358991f, -0.999322384588349540f, 0.033741171851377642f, - -0.999430604555461730f, - 0.030674803176636581f, -0.999529417501093140f, 0.027608145778965820f, - -0.999618822495178640f, - 0.024541228522912264f, -0.999698818696204250f, 0.021474080275469605f, - -0.999769405351215280f, - 0.018406729905804820f, -0.999830581795823400f, 0.015339206284988220f, - -0.999882347454212560f, - 0.012271538285719944f, -0.999924701839144500f, 0.009203754782059960f, - -0.999957644551963900f, - 0.006135884649154515f, -0.999981175282601110f, 0.003067956762966138f, - -0.999995293809576190f -}; - -static const float32_t Weights_2048[4096] = { - 1.000000000000000000f, 0.000000000000000000f, 0.999999705862882230f, - -0.000766990318742704f, - 0.999998823451701880f, -0.001533980186284766f, 0.999997352766978210f, - -0.002300969151425805f, - 0.999995293809576190f, -0.003067956762965976f, 0.999992646580707190f, - -0.003834942569706228f, - 0.999989411081928400f, -0.004601926120448571f, 0.999985587315143200f, - -0.005368906963996343f, - 0.999981175282601110f, -0.006135884649154475f, 0.999976174986897610f, - -0.006902858724729756f, - 0.999970586430974140f, -0.007669828739531097f, 0.999964409618118280f, - -0.008436794242369799f, - 0.999957644551963900f, -0.009203754782059819f, 0.999950291236490480f, - -0.009970709907418031f, - 0.999942349676023910f, -0.010737659167264491f, 0.999933819875236000f, - -0.011504602110422714f, - 0.999924701839144500f, -0.012271538285719925f, 0.999914995573113470f, - -0.013038467241987334f, - 0.999904701082852900f, -0.013805388528060391f, 0.999893818374418490f, - -0.014572301692779064f, - 0.999882347454212560f, -0.015339206284988100f, 0.999870288328982950f, - -0.016106101853537287f, - 0.999857641005823860f, -0.016872987947281710f, 0.999844405492175240f, - -0.017639864115082053f, - 0.999830581795823400f, -0.018406729905804820f, 0.999816169924900410f, - -0.019173584868322623f, - 0.999801169887884260f, -0.019940428551514441f, 0.999785581693599210f, - -0.020707260504265895f, - 0.999769405351215280f, -0.021474080275469508f, 0.999752640870248840f, - -0.022240887414024961f, - 0.999735288260561680f, -0.023007681468839369f, 0.999717347532362190f, - -0.023774461988827555f, - 0.999698818696204250f, -0.024541228522912288f, 0.999679701762987930f, - -0.025307980620024571f, - 0.999659996743959220f, -0.026074717829103901f, 0.999639703650710200f, - -0.026841439699098531f, - 0.999618822495178640f, -0.027608145778965740f, 0.999597353289648380f, - -0.028374835617672099f, - 0.999575296046749220f, -0.029141508764193722f, 0.999552650779456990f, - -0.029908164767516555f, - 0.999529417501093140f, -0.030674803176636626f, 0.999505596225325310f, - -0.031441423540560301f, - 0.999481186966166950f, -0.032208025408304586f, 0.999456189737977340f, - -0.032974608328897335f, - 0.999430604555461730f, -0.033741171851377580f, 0.999404431433671300f, - -0.034507715524795750f, - 0.999377670388002850f, -0.035274238898213947f, 0.999350321434199440f, - -0.036040741520706229f, - 0.999322384588349540f, -0.036807222941358832f, 0.999293859866887790f, - -0.037573682709270494f, - 0.999264747286594420f, -0.038340120373552694f, 0.999235046864595850f, - -0.039106535483329888f, - 0.999204758618363890f, -0.039872927587739811f, 0.999173882565716380f, - -0.040639296235933736f, - 0.999142418724816910f, -0.041405640977076739f, 0.999110367114174890f, - -0.042171961360347947f, - 0.999077727752645360f, -0.042938256934940820f, 0.999044500659429290f, - -0.043704527250063421f, - 0.999010685854073380f, -0.044470771854938668f, 0.998976283356469820f, - -0.045236990298804590f, - 0.998941293186856870f, -0.046003182130914623f, 0.998905715365818290f, - -0.046769346900537863f, - 0.998869549914283560f, -0.047535484156959303f, 0.998832796853527990f, - -0.048301593449480144f, - 0.998795456205172410f, -0.049067674327418015f, 0.998757527991183340f, - -0.049833726340107277f, - 0.998719012233872940f, -0.050599749036899282f, 0.998679908955899090f, - -0.051365741967162593f, - 0.998640218180265270f, -0.052131704680283324f, 0.998599939930320370f, - -0.052897636725665324f, - 0.998559074229759310f, -0.053663537652730520f, 0.998517621102622210f, - -0.054429407010919133f, - 0.998475580573294770f, -0.055195244349689934f, 0.998432952666508440f, - -0.055961049218520569f, - 0.998389737407340160f, -0.056726821166907748f, 0.998345934821212370f, - -0.057492559744367566f, - 0.998301544933892890f, -0.058258264500435752f, 0.998256567771495180f, - -0.059023934984667931f, - 0.998211003360478190f, -0.059789570746639868f, 0.998164851727646240f, - -0.060555171335947788f, - 0.998118112900149180f, -0.061320736302208578f, 0.998070786905482340f, - -0.062086265195060088f, - 0.998022873771486240f, -0.062851757564161406f, 0.997974373526346990f, - -0.063617212959193106f, - 0.997925286198596000f, -0.064382630929857465f, 0.997875611817110150f, - -0.065148011025878833f, - 0.997825350411111640f, -0.065913352797003805f, 0.997774502010167820f, - -0.066678655793001557f, - 0.997723066644191640f, -0.067443919563664051f, 0.997671044343441000f, - -0.068209143658806329f, - 0.997618435138519550f, -0.068974327628266746f, 0.997565239060375750f, - -0.069739471021907307f, - 0.997511456140303450f, -0.070504573389613856f, 0.997457086409941910f, - -0.071269634281296401f, - 0.997402129901275300f, -0.072034653246889332f, 0.997346586646633230f, - -0.072799629836351673f, - 0.997290456678690210f, -0.073564563599667426f, 0.997233740030466280f, - -0.074329454086845756f, - 0.997176436735326190f, -0.075094300847921305f, 0.997118546826979980f, - -0.075859103432954447f, - 0.997060070339482960f, -0.076623861392031492f, 0.997001007307235290f, - -0.077388574275265049f, - 0.996941357764982160f, -0.078153241632794232f, 0.996881121747813850f, - -0.078917863014784942f, - 0.996820299291165670f, -0.079682437971430126f, 0.996758890430818000f, - -0.080446966052950014f, - 0.996696895202896060f, -0.081211446809592441f, 0.996634313643869900f, - -0.081975879791633066f, - 0.996571145790554840f, -0.082740264549375692f, 0.996507391680110820f, - -0.083504600633152432f, - 0.996443051350042630f, -0.084268887593324071f, 0.996378124838200210f, - -0.085033124980280275f, - 0.996312612182778000f, -0.085797312344439894f, 0.996246513422315520f, - -0.086561449236251170f, - 0.996179828595696980f, -0.087325535206192059f, 0.996112557742151130f, - -0.088089569804770507f, - 0.996044700901251970f, -0.088853552582524600f, 0.995976258112917790f, - -0.089617483090022959f, - 0.995907229417411720f, -0.090381360877864983f, 0.995837614855341610f, - -0.091145185496681005f, - 0.995767414467659820f, -0.091908956497132724f, 0.995696628295663520f, - -0.092672673429913310f, - 0.995625256380994310f, -0.093436335845747787f, 0.995553298765638470f, - -0.094199943295393204f, - 0.995480755491926940f, -0.094963495329638992f, 0.995407626602534900f, - -0.095726991499307162f, - 0.995333912140482280f, -0.096490431355252593f, 0.995259612149133390f, - -0.097253814448363271f, - 0.995184726672196930f, -0.098017140329560604f, 0.995109255753726110f, - -0.098780408549799623f, - 0.995033199438118630f, -0.099543618660069319f, 0.994956557770116380f, - -0.100306770211392860f, - 0.994879330794805620f, -0.101069862754827820f, 0.994801518557617110f, - -0.101832895841466530f, - 0.994723121104325700f, -0.102595869022436280f, 0.994644138481050710f, - -0.103358781848899610f, - 0.994564570734255420f, -0.104121633872054590f, 0.994484417910747600f, - -0.104884424643134970f, - 0.994403680057679100f, -0.105647153713410620f, 0.994322357222545810f, - -0.106409820634187680f, - 0.994240449453187900f, -0.107172424956808840f, 0.994157956797789730f, - -0.107934966232653650f, - 0.994074879304879370f, -0.108697444013138720f, 0.993991217023329380f, - -0.109459857849717980f, - 0.993906970002356060f, -0.110222207293883060f, 0.993822138291519660f, - -0.110984491897163390f, - 0.993736721940724600f, -0.111746711211126590f, 0.993650721000219120f, - -0.112508864787378690f, - 0.993564135520595300f, -0.113270952177564350f, 0.993476965552789190f, - -0.114032972933367200f, - 0.993389211148080650f, -0.114794926606510080f, 0.993300872358093280f, - -0.115556812748755260f, - 0.993211949234794500f, -0.116318630911904750f, 0.993122441830495580f, - -0.117080380647800590f, - 0.993032350197851410f, -0.117842061508324980f, 0.992941674389860470f, - -0.118603673045400720f, - 0.992850414459865100f, -0.119365214810991350f, 0.992758570461551140f, - -0.120126686357101500f, - 0.992666142448948020f, -0.120888087235777080f, 0.992573130476428810f, - -0.121649416999105530f, - 0.992479534598709970f, -0.122410675199216200f, 0.992385354870851670f, - -0.123171861388280480f, - 0.992290591348257370f, -0.123932975118512160f, 0.992195244086673920f, - -0.124694015942167640f, - 0.992099313142191800f, -0.125454983411546230f, 0.992002798571244520f, - -0.126215877078990350f, - 0.991905700430609330f, -0.126976696496885870f, 0.991808018777406430f, - -0.127737441217662310f, - 0.991709753669099530f, -0.128498110793793170f, 0.991610905163495370f, - -0.129258704777796140f, - 0.991511473318743900f, -0.130019222722233350f, 0.991411458193338540f, - -0.130779664179711710f, - 0.991310859846115440f, -0.131540028702883120f, 0.991209678336254060f, - -0.132300315844444650f, - 0.991107913723276890f, -0.133060525157139060f, 0.991005566067049370f, - -0.133820656193754720f, - 0.990902635427780010f, -0.134580708507126170f, 0.990799121866020370f, - -0.135340681650134210f, - 0.990695025442664630f, -0.136100575175706200f, 0.990590346218950150f, - -0.136860388636816380f, - 0.990485084256457090f, -0.137620121586486040f, 0.990379239617108160f, - -0.138379773577783890f, - 0.990272812363169110f, -0.139139344163826200f, 0.990165802557248400f, - -0.139898832897777210f, - 0.990058210262297120f, -0.140658239332849210f, 0.989950035541608990f, - -0.141417563022303020f, - 0.989841278458820530f, -0.142176803519448030f, 0.989731939077910570f, - -0.142935960377642670f, - 0.989622017463200890f, -0.143695033150294470f, 0.989511513679355190f, - -0.144454021390860470f, - 0.989400427791380380f, -0.145212924652847460f, 0.989288759864625170f, - -0.145971742489812210f, - 0.989176509964781010f, -0.146730474455361750f, 0.989063678157881540f, - -0.147489120103153570f, - 0.988950264510302990f, -0.148247678986896030f, 0.988836269088763540f, - -0.149006150660348450f, - 0.988721691960323780f, -0.149764534677321510f, 0.988606533192386450f, - -0.150522830591677400f, - 0.988490792852696590f, -0.151281037957330220f, 0.988374471009341280f, - -0.152039156328246050f, - 0.988257567730749460f, -0.152797185258443440f, 0.988140083085692570f, - -0.153555124301993450f, - 0.988022017143283530f, -0.154312973013020100f, 0.987903369972977790f, - -0.155070730945700510f, - 0.987784141644572180f, -0.155828397654265230f, 0.987664332228205710f, - -0.156585972692998430f, - 0.987543941794359230f, -0.157343455616238250f, 0.987422970413855410f, - -0.158100845978376980f, - 0.987301418157858430f, -0.158858143333861450f, 0.987179285097874340f, - -0.159615347237193060f, - 0.987056571305750970f, -0.160372457242928280f, 0.986933276853677710f, - -0.161129472905678810f, - 0.986809401814185530f, -0.161886393780111830f, 0.986684946260146690f, - -0.162643219420950310f, - 0.986559910264775410f, -0.163399949382973230f, 0.986434293901627180f, - -0.164156583221015810f, - 0.986308097244598670f, -0.164913120489969890f, 0.986181320367928270f, - -0.165669560744784120f, - 0.986053963346195440f, -0.166425903540464100f, 0.985926026254321130f, - -0.167182148432072940f, - 0.985797509167567480f, -0.167938294974731170f, 0.985668412161537550f, - -0.168694342723617330f, - 0.985538735312176060f, -0.169450291233967960f, 0.985408478695768420f, - -0.170206140061078070f, - 0.985277642388941220f, -0.170961888760301220f, 0.985146226468662230f, - -0.171717536887049970f, - 0.985014231012239840f, -0.172473083996795950f, 0.984881656097323700f, - -0.173228529645070320f, - 0.984748501801904210f, -0.173983873387463820f, 0.984614768204312600f, - -0.174739114779627200f, - 0.984480455383220930f, -0.175494253377271430f, 0.984345563417641900f, - -0.176249288736167880f, - 0.984210092386929030f, -0.177004220412148750f, 0.984074042370776450f, - -0.177759047961107170f, - 0.983937413449218920f, -0.178513770938997510f, 0.983800205702631600f, - -0.179268388901835750f, - 0.983662419211730250f, -0.180022901405699510f, 0.983524054057571260f, - -0.180777308006728590f, - 0.983385110321551180f, -0.181531608261124970f, 0.983245588085407070f, - -0.182285801725153300f, - 0.983105487431216290f, -0.183039887955140950f, 0.982964808441396440f, - -0.183793866507478450f, - 0.982823551198705240f, -0.184547736938619620f, 0.982681715786240860f, - -0.185301498805081900f, - 0.982539302287441240f, -0.186055151663446630f, 0.982396310786084690f, - -0.186808695070359270f, - 0.982252741366289370f, -0.187562128582529600f, 0.982108594112513610f, - -0.188315451756732120f, - 0.981963869109555240f, -0.189068664149806190f, 0.981818566442552500f, - -0.189821765318656410f, - 0.981672686196983110f, -0.190574754820252740f, 0.981526228458664770f, - -0.191327632211630900f, - 0.981379193313754560f, -0.192080397049892440f, 0.981231580848749730f, - -0.192833048892205230f, - 0.981083391150486710f, -0.193585587295803610f, 0.980934624306141640f, - -0.194338011817988600f, - 0.980785280403230430f, -0.195090322016128250f, 0.980635359529608120f, - -0.195842517447657850f, - 0.980484861773469380f, -0.196594597670080220f, 0.980333787223347960f, - -0.197346562240965920f, - 0.980182135968117430f, -0.198098410717953560f, 0.980029908096990090f, - -0.198850142658750090f, - 0.979877103699517640f, -0.199601757621130970f, 0.979723722865591170f, - -0.200353255162940450f, - 0.979569765685440520f, -0.201104634842091900f, 0.979415232249634780f, - -0.201855896216568050f, - 0.979260122649082020f, -0.202607038844421130f, 0.979104436975029250f, - -0.203358062283773320f, - 0.978948175319062200f, -0.204108966092816870f, 0.978791337773105670f, - -0.204859749829814420f, - 0.978633924429423210f, -0.205610413053099240f, 0.978475935380616830f, - -0.206360955321075510f, - 0.978317370719627650f, -0.207111376192218560f, 0.978158230539735050f, - -0.207861675225075070f, - 0.977998514934557140f, -0.208611851978263490f, 0.977838223998050430f, - -0.209361906010474160f, - 0.977677357824509930f, -0.210111836880469610f, 0.977515916508569280f, - -0.210861644147084860f, - 0.977353900145199960f, -0.211611327369227550f, 0.977191308829712280f, - -0.212360886105878420f, - 0.977028142657754390f, -0.213110319916091360f, 0.976864401725312640f, - -0.213859628358993750f, - 0.976700086128711840f, -0.214608810993786760f, 0.976535195964614470f, - -0.215357867379745550f, - 0.976369731330021140f, -0.216106797076219520f, 0.976203692322270560f, - -0.216855599642632620f, - 0.976037079039039020f, -0.217604274638483640f, 0.975869891578341030f, - -0.218352821623346320f, - 0.975702130038528570f, -0.219101240156869800f, 0.975533794518291360f, - -0.219849529798778700f, - 0.975364885116656980f, -0.220597690108873510f, 0.975195401932990370f, - -0.221345720647030810f, - 0.975025345066994120f, -0.222093620973203510f, 0.974854714618708430f, - -0.222841390647421120f, - 0.974683510688510670f, -0.223589029229789990f, 0.974511733377115720f, - -0.224336536280493600f, - 0.974339382785575860f, -0.225083911359792830f, 0.974166459015280320f, - -0.225831154028026170f, - 0.973992962167955830f, -0.226578263845610000f, 0.973818892345666100f, - -0.227325240373038860f, - 0.973644249650811980f, -0.228072083170885730f, 0.973469034186131070f, - -0.228818791799802220f, - 0.973293246054698250f, -0.229565365820518870f, 0.973116885359925130f, - -0.230311804793845440f, - 0.972939952205560180f, -0.231058108280671110f, 0.972762446695688570f, - -0.231804275841964780f, - 0.972584368934732210f, -0.232550307038775240f, 0.972405719027449770f, - -0.233296201432231590f, - 0.972226497078936270f, -0.234041958583543430f, 0.972046703194623500f, - -0.234787578054000970f, - 0.971866337480279400f, -0.235533059404975490f, 0.971685400042008540f, - -0.236278402197919570f, - 0.971503890986251780f, -0.237023605994367200f, 0.971321810419786160f, - -0.237768670355934190f, - 0.971139158449725090f, -0.238513594844318420f, 0.970955935183517970f, - -0.239258379021299980f, - 0.970772140728950350f, -0.240003022448741500f, 0.970587775194143630f, - -0.240747524688588430f, - 0.970402838687555500f, -0.241491885302869330f, 0.970217331317979160f, - -0.242236103853696010f, - 0.970031253194543970f, -0.242980179903263870f, 0.969844604426714830f, - -0.243724113013852160f, - 0.969657385124292450f, -0.244467902747824150f, 0.969469595397413060f, - -0.245211548667627540f, - 0.969281235356548530f, -0.245955050335794590f, 0.969092305112506210f, - -0.246698407314942410f, - 0.968902804776428870f, -0.247441619167773270f, 0.968712734459794780f, - -0.248184685457074780f, - 0.968522094274417380f, -0.248927605745720150f, 0.968330884332445190f, - -0.249670379596668570f, - 0.968139104746362440f, -0.250413006572965220f, 0.967946755628987800f, - -0.251155486237741920f, - 0.967753837093475510f, -0.251897818154216970f, 0.967560349253314360f, - -0.252640001885695520f, - 0.967366292222328510f, -0.253382036995570160f, 0.967171666114676640f, - -0.254123923047320620f, - 0.966976471044852070f, -0.254865659604514570f, 0.966780707127683270f, - -0.255607246230807380f, - 0.966584374478333120f, -0.256348682489942910f, 0.966387473212298900f, - -0.257089967945753120f, - 0.966190003445412500f, -0.257831102162158990f, 0.965991965293840570f, - -0.258572084703170340f, - 0.965793358874083680f, -0.259312915132886230f, 0.965594184302976830f, - -0.260053593015495190f, - 0.965394441697689400f, -0.260794117915275510f, 0.965194131175724720f, - -0.261534489396595520f, - 0.964993252854920320f, -0.262274707023913590f, 0.964791806853447900f, - -0.263014770361779000f, - 0.964589793289812760f, -0.263754678974831350f, 0.964387212282854290f, - -0.264494432427801630f, - 0.964184063951745830f, -0.265234030285511790f, 0.963980348415994110f, - -0.265973472112875590f, - 0.963776065795439840f, -0.266712757474898370f, 0.963571216210257320f, - -0.267451885936677620f, - 0.963365799780954050f, -0.268190857063403180f, 0.963159816628371360f, - -0.268929670420357260f, - 0.962953266873683880f, -0.269668325572915090f, 0.962746150638399410f, - -0.270406822086544820f, - 0.962538468044359160f, -0.271145159526808010f, 0.962330219213737400f, - -0.271883337459359720f, - 0.962121404269041580f, -0.272621355449948980f, 0.961912023333112210f, - -0.273359213064418680f, - 0.961702076529122540f, -0.274096909868706380f, 0.961491563980579000f, - -0.274834445428843940f, - 0.961280485811320640f, -0.275571819310958140f, 0.961068842145519350f, - -0.276309031081271080f, - 0.960856633107679660f, -0.277046080306099900f, 0.960643858822638590f, - -0.277782966551857690f, - 0.960430519415565790f, -0.278519689385053060f, 0.960216615011963430f, - -0.279256248372291180f, - 0.960002145737665960f, -0.279992643080273220f, 0.959787111718839900f, - -0.280728873075797190f, - 0.959571513081984520f, -0.281464937925757940f, 0.959355349953930790f, - -0.282200837197147560f, - 0.959138622461841890f, -0.282936570457055390f, 0.958921330733213170f, - -0.283672137272668430f, - 0.958703474895871600f, -0.284407537211271880f, 0.958485055077976100f, - -0.285142769840248670f, - 0.958266071408017670f, -0.285877834727080620f, 0.958046524014818600f, - -0.286612731439347790f, - 0.957826413027532910f, -0.287347459544729510f, 0.957605738575646350f, - -0.288082018611004130f, - 0.957384500788975860f, -0.288816408206049480f, 0.957162699797670210f, - -0.289550627897843030f, - 0.956940335732208820f, -0.290284677254462330f, 0.956717408723403050f, - -0.291018555844085090f, - 0.956493918902395100f, -0.291752263234989260f, 0.956269866400658030f, - -0.292485798995553880f, - 0.956045251349996410f, -0.293219162694258630f, 0.955820073882545420f, - -0.293952353899684660f, - 0.955594334130771110f, -0.294685372180514330f, 0.955368032227470350f, - -0.295418217105532010f, - 0.955141168305770780f, -0.296150888243623790f, 0.954913742499130520f, - -0.296883385163778270f, - 0.954685754941338340f, -0.297615707435086200f, 0.954457205766513490f, - -0.298347854626741400f, - 0.954228095109105670f, -0.299079826308040480f, 0.953998423103894490f, - -0.299811622048383350f, - 0.953768189885990330f, -0.300543241417273450f, 0.953537395590833280f, - -0.301274683984317950f, - 0.953306040354193860f, -0.302005949319228080f, 0.953074124312172200f, - -0.302737036991819140f, - 0.952841647601198720f, -0.303467946572011320f, 0.952608610358033350f, - -0.304198677629829110f, - 0.952375012719765880f, -0.304929229735402370f, 0.952140854823815830f, - -0.305659602458966120f, - 0.951906136807932350f, -0.306389795370860920f, 0.951670858810193860f, - -0.307119808041533100f, - 0.951435020969008340f, -0.307849640041534870f, 0.951198623423113230f, - -0.308579290941525090f, - 0.950961666311575080f, -0.309308760312268730f, 0.950724149773789610f, - -0.310038047724637890f, - 0.950486073949481700f, -0.310767152749611470f, 0.950247438978705230f, - -0.311496074958275910f, - 0.950008245001843000f, -0.312224813921824880f, 0.949768492159606680f, - -0.312953369211560200f, - 0.949528180593036670f, -0.313681740398891520f, 0.949287310443502120f, - -0.314409927055336660f, - 0.949045881852700560f, -0.315137928752522440f, 0.948803894962658490f, - -0.315865745062183960f, - 0.948561349915730270f, -0.316593375556165850f, 0.948318246854599090f, - -0.317320819806421740f, - 0.948074585922276230f, -0.318048077385014950f, 0.947830367262101010f, - -0.318775147864118480f, - 0.947585591017741090f, -0.319502030816015690f, 0.947340257333192050f, - -0.320228725813099860f, - 0.947094366352777220f, -0.320955232427875210f, 0.946847918221148000f, - -0.321681550232956580f, - 0.946600913083283530f, -0.322407678801069850f, 0.946353351084490590f, - -0.323133617705052330f, - 0.946105232370403450f, -0.323859366517852850f, 0.945856557086983910f, - -0.324584924812532150f, - 0.945607325380521280f, -0.325310292162262930f, 0.945357537397632290f, - -0.326035468140330240f, - 0.945107193285260610f, -0.326760452320131730f, 0.944856293190677210f, - -0.327485244275178000f, - 0.944604837261480260f, -0.328209843579092500f, 0.944352825645594750f, - -0.328934249805612200f, - 0.944100258491272660f, -0.329658462528587490f, 0.943847135947092690f, - -0.330382481321982780f, - 0.943593458161960390f, -0.331106305759876430f, 0.943339225285107720f, - -0.331829935416461110f, - 0.943084437466093490f, -0.332553369866044220f, 0.942829094854802710f, - -0.333276608683047930f, - 0.942573197601446870f, -0.333999651442009380f, 0.942316745856563780f, - -0.334722497717581220f, - 0.942059739771017310f, -0.335445147084531600f, 0.941802179495997650f, - -0.336167599117744520f, - 0.941544065183020810f, -0.336889853392220050f, 0.941285396983928660f, - -0.337611909483074620f, - 0.941026175050889260f, -0.338333766965541130f, 0.940766399536396070f, - -0.339055425414969640f, - 0.940506070593268300f, -0.339776884406826850f, 0.940245188374650880f, - -0.340498143516697160f, - 0.939983753034014050f, -0.341219202320282360f, 0.939721764725153340f, - -0.341940060393402190f, - 0.939459223602189920f, -0.342660717311994380f, 0.939196129819569900f, - -0.343381172652115040f, - 0.938932483532064600f, -0.344101425989938810f, 0.938668284894770170f, - -0.344821476901759290f, - 0.938403534063108060f, -0.345541324963989090f, 0.938138231192824360f, - -0.346260969753160010f, - 0.937872376439989890f, -0.346980410845923680f, 0.937605969960999990f, - -0.347699647819051380f, - 0.937339011912574960f, -0.348418680249434560f, 0.937071502451759190f, - -0.349137507714084970f, - 0.936803441735921560f, -0.349856129790134920f, 0.936534829922755500f, - -0.350574546054837510f, - 0.936265667170278260f, -0.351292756085567090f, 0.935995953636831410f, - -0.352010759459819080f, - 0.935725689481080370f, -0.352728555755210730f, 0.935454874862014620f, - -0.353446144549480810f, - 0.935183509938947610f, -0.354163525420490340f, 0.934911594871516090f, - -0.354880697946222790f, - 0.934639129819680780f, -0.355597661704783850f, 0.934366114943725790f, - -0.356314416274402410f, - 0.934092550404258980f, -0.357030961233429980f, 0.933818436362210960f, - -0.357747296160341900f, - 0.933543772978836170f, -0.358463420633736540f, 0.933268560415712050f, - -0.359179334232336500f, - 0.932992798834738960f, -0.359895036534988110f, 0.932716488398140250f, - -0.360610527120662270f, - 0.932439629268462360f, -0.361325805568454280f, 0.932162221608574430f, - -0.362040871457584180f, - 0.931884265581668150f, -0.362755724367397230f, 0.931605761351257830f, - -0.363470363877363760f, - 0.931326709081180430f, -0.364184789567079890f, 0.931047108935595280f, - -0.364899001016267320f, - 0.930766961078983710f, -0.365612997804773850f, 0.930486265676149780f, - -0.366326779512573590f, - 0.930205022892219070f, -0.367040345719767180f, 0.929923232892639670f, - -0.367753696006581980f, - 0.929640895843181330f, -0.368466829953372320f, 0.929358011909935500f, - -0.369179747140620020f, - 0.929074581259315860f, -0.369892447148934100f, 0.928790604058057020f, - -0.370604929559051670f, - 0.928506080473215590f, -0.371317193951837540f, 0.928221010672169440f, - -0.372029239908285010f, - 0.927935394822617890f, -0.372741067009515760f, 0.927649233092581180f, - -0.373452674836780300f, - 0.927362525650401110f, -0.374164062971457930f, 0.927075272664740100f, - -0.374875230995057540f, - 0.926787474304581750f, -0.375586178489217220f, 0.926499130739230510f, - -0.376296905035704790f, - 0.926210242138311380f, -0.377007410216418260f, 0.925920808671770070f, - -0.377717693613385640f, - 0.925630830509872720f, -0.378427754808765560f, 0.925340307823206310f, - -0.379137593384847320f, - 0.925049240782677580f, -0.379847208924051160f, 0.924757629559513910f, - -0.380556601008928520f, - 0.924465474325262600f, -0.381265769222162380f, 0.924172775251791200f, - -0.381974713146567220f, - 0.923879532511286740f, -0.382683432365089780f, 0.923585746276256670f, - -0.383391926460808660f, - 0.923291416719527640f, -0.384100195016935040f, 0.922996544014246250f, - -0.384808237616812880f, - 0.922701128333878630f, -0.385516053843918850f, 0.922405169852209880f, - -0.386223643281862980f, - 0.922108668743345180f, -0.386931005514388580f, 0.921811625181708120f, - -0.387638140125372730f, - 0.921514039342042010f, -0.388345046698826250f, 0.921215911399408730f, - -0.389051724818894380f, - 0.920917241529189520f, -0.389758174069856410f, 0.920618029907083970f, - -0.390464394036126590f, - 0.920318276709110590f, -0.391170384302253870f, 0.920017982111606570f, - -0.391876144452922350f, - 0.919717146291227360f, -0.392581674072951470f, 0.919415769424947070f, - -0.393286972747296400f, - 0.919113851690057770f, -0.393992040061048100f, 0.918811393264170050f, - -0.394696875599433560f, - 0.918508394325212250f, -0.395401478947816350f, 0.918204855051430900f, - -0.396105849691696270f, - 0.917900775621390500f, -0.396809987416710310f, 0.917596156213972950f, - -0.397513891708632330f, - 0.917290997008377910f, -0.398217562153373560f, 0.916985298184123000f, - -0.398920998336982910f, - 0.916679059921042700f, -0.399624199845646790f, 0.916372282399289140f, - -0.400327166265690090f, - 0.916064965799331720f, -0.401029897183575620f, 0.915757110301956720f, - -0.401732392185905010f, - 0.915448716088267830f, -0.402434650859418430f, 0.915139783339685260f, - -0.403136672790995300f, - 0.914830312237946200f, -0.403838457567654070f, 0.914520302965104450f, - -0.404540004776553000f, - 0.914209755703530690f, -0.405241314004989860f, 0.913898670635911680f, - -0.405942384840402510f, - 0.913587047945250810f, -0.406643216870369030f, 0.913274887814867760f, - -0.407343809682607970f, - 0.912962190428398210f, -0.408044162864978690f, 0.912648955969793900f, - -0.408744276005481360f, - 0.912335184623322750f, -0.409444148692257590f, 0.912020876573568340f, - -0.410143780513590240f, - 0.911706032005429880f, -0.410843171057903910f, 0.911390651104122430f, - -0.411542319913765220f, - 0.911074734055176360f, -0.412241226669882890f, 0.910758281044437570f, - -0.412939890915108080f, - 0.910441292258067250f, -0.413638312238434500f, 0.910123767882541680f, - -0.414336490228999100f, - 0.909805708104652220f, -0.415034424476081630f, 0.909487113111505430f, - -0.415732114569105360f, - 0.909167983090522380f, -0.416429560097637150f, 0.908848318229439120f, - -0.417126760651387870f, - 0.908528118716306120f, -0.417823715820212270f, 0.908207384739488700f, - -0.418520425194109700f, - 0.907886116487666260f, -0.419216888363223910f, 0.907564314149832630f, - -0.419913104917843620f, - 0.907241977915295820f, -0.420609074448402510f, 0.906919107973678140f, - -0.421304796545479640f, - 0.906595704514915330f, -0.422000270799799680f, 0.906271767729257660f, - -0.422695496802232950f, - 0.905947297807268460f, -0.423390474143796050f, 0.905622294939825270f, - -0.424085202415651560f, - 0.905296759318118820f, -0.424779681209108810f, 0.904970691133653250f, - -0.425473910115623800f, - 0.904644090578246240f, -0.426167888726799620f, 0.904316957844028320f, - -0.426861616634386430f, - 0.903989293123443340f, -0.427555093430282080f, 0.903661096609247980f, - -0.428248318706531960f, - 0.903332368494511820f, -0.428941292055329490f, 0.903003108972617150f, - -0.429634013069016380f, - 0.902673318237258830f, -0.430326481340082610f, 0.902342996482444200f, - -0.431018696461167030f, - 0.902012143902493180f, -0.431710658025057260f, 0.901680760692037730f, - -0.432402365624690140f, - 0.901348847046022030f, -0.433093818853151960f, 0.901016403159702330f, - -0.433785017303678520f, - 0.900683429228646970f, -0.434475960569655650f, 0.900349925448735600f, - -0.435166648244619260f, - 0.900015892016160280f, -0.435857079922255470f, 0.899681329127423930f, - -0.436547255196401200f, - 0.899346236979341570f, -0.437237173661044090f, 0.899010615769039070f, - -0.437926834910322860f, - 0.898674465693953820f, -0.438616238538527660f, 0.898337786951834310f, - -0.439305384140099950f, - 0.898000579740739880f, -0.439994271309633260f, 0.897662844259040860f, - -0.440682899641872900f, - 0.897324580705418320f, -0.441371268731716670f, 0.896985789278863970f, - -0.442059378174214700f, - 0.896646470178680150f, -0.442747227564570020f, 0.896306623604479550f, - -0.443434816498138480f, - 0.895966249756185220f, -0.444122144570429200f, 0.895625348834030110f, - -0.444809211377104880f, - 0.895283921038557580f, -0.445496016513981740f, 0.894941966570620750f, - -0.446182559577030070f, - 0.894599485631382700f, -0.446868840162374160f, 0.894256478422316040f, - -0.447554857866293010f, - 0.893912945145203250f, -0.448240612285219890f, 0.893568886002135910f, - -0.448926103015743260f, - 0.893224301195515320f, -0.449611329654606540f, 0.892879190928051680f, - -0.450296291798708610f, - 0.892533555402764580f, -0.450980989045103860f, 0.892187394822982480f, - -0.451665420991002490f, - 0.891840709392342720f, -0.452349587233770890f, 0.891493499314791380f, - -0.453033487370931580f, - 0.891145764794583180f, -0.453717121000163870f, 0.890797506036281490f, - -0.454400487719303580f, - 0.890448723244757880f, -0.455083587126343840f, 0.890099416625192320f, - -0.455766418819434640f, - 0.889749586383072780f, -0.456448982396883920f, 0.889399232724195520f, - -0.457131277457156980f, - 0.889048355854664570f, -0.457813303598877170f, 0.888696955980891600f, - -0.458495060420826270f, - 0.888345033309596350f, -0.459176547521944090f, 0.887992588047805560f, - -0.459857764501329540f, - 0.887639620402853930f, -0.460538710958240010f, 0.887286130582383150f, - -0.461219386492092380f, - 0.886932118794342190f, -0.461899790702462730f, 0.886577585246987040f, - -0.462579923189086810f, - 0.886222530148880640f, -0.463259783551860150f, 0.885866953708892790f, - -0.463939371390838520f, - 0.885510856136199950f, -0.464618686306237820f, 0.885154237640285110f, - -0.465297727898434600f, - 0.884797098430937790f, -0.465976495767966180f, 0.884439438718253810f, - -0.466654989515530920f, - 0.884081258712634990f, -0.467333208741988420f, 0.883722558624789660f, - -0.468011153048359830f, - 0.883363338665731580f, -0.468688822035827900f, 0.883003599046780830f, - -0.469366215305737520f, - 0.882643339979562790f, -0.470043332459595620f, 0.882282561676008710f, - -0.470720173099071600f, - 0.881921264348355050f, -0.471396736825997640f, 0.881559448209143780f, - -0.472073023242368660f, - 0.881197113471222090f, -0.472749031950342790f, 0.880834260347742040f, - -0.473424762552241530f, - 0.880470889052160750f, -0.474100214650549970f, 0.880106999798240360f, - -0.474775387847917120f, - 0.879742592800047410f, -0.475450281747155870f, 0.879377668271953290f, - -0.476124895951243580f, - 0.879012226428633530f, -0.476799230063322090f, 0.878646267485068130f, - -0.477473283686698060f, - 0.878279791656541580f, -0.478147056424843010f, 0.877912799158641840f, - -0.478820547881393890f, - 0.877545290207261350f, -0.479493757660153010f, 0.877177265018595940f, - -0.480166685365088390f, - 0.876808723809145650f, -0.480839330600333960f, 0.876439666795713610f, - -0.481511692970189860f, - 0.876070094195406600f, -0.482183772079122720f, 0.875700006225634600f, - -0.482855567531765670f, - 0.875329403104110890f, -0.483527078932918740f, 0.874958285048851650f, - -0.484198305887549030f, - 0.874586652278176110f, -0.484869248000791060f, 0.874214505010706300f, - -0.485539904877946960f, - 0.873841843465366860f, -0.486210276124486420f, 0.873468667861384880f, - -0.486880361346047340f, - 0.873094978418290090f, -0.487550160148436000f, 0.872720775355914300f, - -0.488219672137626790f, - 0.872346058894391540f, -0.488888896919763170f, 0.871970829254157810f, - -0.489557834101157440f, - 0.871595086655950980f, -0.490226483288291160f, 0.871218831320811020f, - -0.490894844087815090f, - 0.870842063470078980f, -0.491562916106549900f, 0.870464783325397670f, - -0.492230698951486020f, - 0.870086991108711460f, -0.492898192229784040f, 0.869708687042265670f, - -0.493565395548774770f, - 0.869329871348606840f, -0.494232308515959670f, 0.868950544250582380f, - -0.494898930739011260f, - 0.868570705971340900f, -0.495565261825772540f, 0.868190356734331310f, - -0.496231301384258250f, - 0.867809496763303320f, -0.496897049022654470f, 0.867428126282306920f, - -0.497562504349319150f, - 0.867046245515692650f, -0.498227666972781870f, 0.866663854688111130f, - -0.498892536501744590f, - 0.866280954024512990f, -0.499557112545081840f, 0.865897543750148820f, - -0.500221394711840680f, - 0.865513624090569090f, -0.500885382611240710f, 0.865129195271623800f, - -0.501549075852675390f, - 0.864744257519462380f, -0.502212474045710790f, 0.864358811060534030f, - -0.502875576800086990f, - 0.863972856121586810f, -0.503538383725717580f, 0.863586392929668100f, - -0.504200894432690340f, - 0.863199421712124160f, -0.504863108531267590f, 0.862811942696600330f, - -0.505525025631885390f, - 0.862423956111040610f, -0.506186645345155230f, 0.862035462183687210f, - -0.506847967281863210f, - 0.861646461143081300f, -0.507508991052970870f, 0.861256953218062170f, - -0.508169716269614600f, - 0.860866938637767310f, -0.508830142543106990f, 0.860476417631632070f, - -0.509490269484936360f, - 0.860085390429390140f, -0.510150096706766810f, 0.859693857261072610f, - -0.510809623820439040f, - 0.859301818357008470f, -0.511468850437970300f, 0.858909273947823900f, - -0.512127776171554690f, - 0.858516224264442740f, -0.512786400633562960f, 0.858122669538086140f, - -0.513444723436543460f, - 0.857728610000272120f, -0.514102744193221660f, 0.857334045882815590f, - -0.514760462516501200f, - 0.856938977417828760f, -0.515417878019462930f, 0.856543404837719960f, - -0.516074990315366630f, - 0.856147328375194470f, -0.516731799017649870f, 0.855750748263253920f, - -0.517388303739929060f, - 0.855353664735196030f, -0.518044504095999340f, 0.854956078024614930f, - -0.518700399699834950f, - 0.854557988365400530f, -0.519355990165589640f, 0.854159395991738850f, - -0.520011275107596040f, - 0.853760301138111410f, -0.520666254140367160f, 0.853360704039295430f, - -0.521320926878595660f, - 0.852960604930363630f, -0.521975292937154390f, 0.852560004046684080f, - -0.522629351931096610f, - 0.852158901623919830f, -0.523283103475656430f, 0.851757297898029120f, - -0.523936547186248600f, - 0.851355193105265200f, -0.524589682678468950f, 0.850952587482175730f, - -0.525242509568094710f, - 0.850549481265603480f, -0.525895027471084630f, 0.850145874692685210f, - -0.526547236003579440f, - 0.849741768000852550f, -0.527199134781901280f, 0.849337161427830780f, - -0.527850723422555230f, - 0.848932055211639610f, -0.528502001542228480f, 0.848526449590592650f, - -0.529152968757790610f, - 0.848120344803297230f, -0.529803624686294610f, 0.847713741088654380f, - -0.530453968944976320f, - 0.847306638685858320f, -0.531104001151255000f, 0.846899037834397240f, - -0.531753720922733320f, - 0.846490938774052130f, -0.532403127877197900f, 0.846082341744897050f, - -0.533052221632619450f, - 0.845673246987299070f, -0.533701001807152960f, 0.845263654741918220f, - -0.534349468019137520f, - 0.844853565249707120f, -0.534997619887097150f, 0.844442978751910660f, - -0.535645457029741090f, - 0.844031895490066410f, -0.536292979065963180f, 0.843620315706004150f, - -0.536940185614842910f, - 0.843208239641845440f, -0.537587076295645390f, 0.842795667540004120f, - -0.538233650727821700f, - 0.842382599643185850f, -0.538879908531008420f, 0.841969036194387680f, - -0.539525849325028890f, - 0.841554977436898440f, -0.540171472729892850f, 0.841140423614298080f, - -0.540816778365796670f, - 0.840725374970458070f, -0.541461765853123440f, 0.840309831749540770f, - -0.542106434812443920f, - 0.839893794195999520f, -0.542750784864515890f, 0.839477262554578550f, - -0.543394815630284800f, - 0.839060237070312740f, -0.544038526730883820f, 0.838642717988527300f, - -0.544681917787634530f, - 0.838224705554838080f, -0.545324988422046460f, 0.837806200015150940f, - -0.545967738255817570f, - 0.837387201615661940f, -0.546610166910834860f, 0.836967710602857020f, - -0.547252274009174090f, - 0.836547727223512010f, -0.547894059173100190f, 0.836127251724692270f, - -0.548535522025067390f, - 0.835706284353752600f, -0.549176662187719660f, 0.835284825358337370f, - -0.549817479283890910f, - 0.834862874986380010f, -0.550457972936604810f, 0.834440433486103190f, - -0.551098142769075430f, - 0.834017501106018130f, -0.551737988404707340f, 0.833594078094925140f, - -0.552377509467096070f, - 0.833170164701913190f, -0.553016705580027470f, 0.832745761176359460f, - -0.553655576367479310f, - 0.832320867767929680f, -0.554294121453620000f, 0.831895484726577590f, - -0.554932340462810370f, - 0.831469612302545240f, -0.555570233019602180f, 0.831043250746362320f, - -0.556207798748739930f, - 0.830616400308846310f, -0.556845037275160100f, 0.830189061241102370f, - -0.557481948223991550f, - 0.829761233794523050f, -0.558118531220556100f, 0.829332918220788250f, - -0.558754785890368310f, - 0.828904114771864870f, -0.559390711859136140f, 0.828474823700007130f, - -0.560026308752760380f, - 0.828045045257755800f, -0.560661576197336030f, 0.827614779697938400f, - -0.561296513819151470f, - 0.827184027273669130f, -0.561931121244689470f, 0.826752788238348520f, - -0.562565398100626560f, - 0.826321062845663530f, -0.563199344013834090f, 0.825888851349586780f, - -0.563832958611378170f, - 0.825456154004377550f, -0.564466241520519500f, 0.825022971064580220f, - -0.565099192368713980f, - 0.824589302785025290f, -0.565731810783613120f, 0.824155149420828570f, - -0.566364096393063840f, - 0.823720511227391430f, -0.566996048825108680f, 0.823285388460400110f, - -0.567627667707986230f, - 0.822849781375826430f, -0.568258952670131490f, 0.822413690229926390f, - -0.568889903340175860f, - 0.821977115279241550f, -0.569520519346947140f, 0.821540056780597610f, - -0.570150800319470300f, - 0.821102514991104650f, -0.570780745886967260f, 0.820664490168157460f, - -0.571410355678857230f, - 0.820225982569434690f, -0.572039629324757050f, 0.819786992452898990f, - -0.572668566454481160f, - 0.819347520076796900f, -0.573297166698042200f, 0.818907565699658950f, - -0.573925429685650750f, - 0.818467129580298660f, -0.574553355047715760f, 0.818026211977813440f, - -0.575180942414845080f, - 0.817584813151583710f, -0.575808191417845340f, 0.817142933361272970f, - -0.576435101687721830f, - 0.816700572866827850f, -0.577061672855679440f, 0.816257731928477390f, - -0.577687904553122800f, - 0.815814410806733780f, -0.578313796411655590f, 0.815370609762391290f, - -0.578939348063081780f, - 0.814926329056526620f, -0.579564559139405630f, 0.814481568950498610f, - -0.580189429272831680f, - 0.814036329705948410f, -0.580813958095764530f, 0.813590611584798510f, - -0.581438145240810170f, - 0.813144414849253590f, -0.582061990340775440f, 0.812697739761799490f, - -0.582685493028668460f, - 0.812250586585203880f, -0.583308652937698290f, 0.811802955582515470f, - -0.583931469701276180f, - 0.811354847017063730f, -0.584553942953015330f, 0.810906261152459670f, - -0.585176072326730410f, - 0.810457198252594770f, -0.585797857456438860f, 0.810007658581641140f, - -0.586419297976360500f, - 0.809557642404051260f, -0.587040393520917970f, 0.809107149984558240f, - -0.587661143724736660f, - 0.808656181588174980f, -0.588281548222645220f, 0.808204737480194720f, - -0.588901606649675720f, - 0.807752817926190360f, -0.589521318641063940f, 0.807300423192014450f, - -0.590140683832248820f, - 0.806847553543799330f, -0.590759701858874160f, 0.806394209247956240f, - -0.591378372356787580f, - 0.805940390571176280f, -0.591996694962040990f, 0.805486097780429230f, - -0.592614669310891130f, - 0.805031331142963660f, -0.593232295039799800f, 0.804576090926307110f, - -0.593849571785433630f, - 0.804120377398265810f, -0.594466499184664430f, 0.803664190826924090f, - -0.595083076874569960f, - 0.803207531480644940f, -0.595699304492433360f, 0.802750399628069160f, - -0.596315181675743710f, - 0.802292795538115720f, -0.596930708062196500f, 0.801834719479981310f, - -0.597545883289693160f, - 0.801376171723140240f, -0.598160706996342270f, 0.800917152537344300f, - -0.598775178820458720f, - 0.800457662192622820f, -0.599389298400564540f, 0.799997700959281910f, - -0.600003065375388940f, - 0.799537269107905010f, -0.600616479383868970f, 0.799076366909352350f, - -0.601229540065148500f, - 0.798614994634760820f, -0.601842247058580030f, 0.798153152555543750f, - -0.602454600003723750f, - 0.797690840943391160f, -0.603066598540348160f, 0.797228060070268810f, - -0.603678242308430370f, - 0.796764810208418830f, -0.604289530948155960f, 0.796301091630359110f, - -0.604900464099919820f, - 0.795836904608883570f, -0.605511041404325550f, 0.795372249417061310f, - -0.606121262502186120f, - 0.794907126328237010f, -0.606731127034524480f, 0.794441535616030590f, - -0.607340634642572930f, - 0.793975477554337170f, -0.607949784967773630f, 0.793508952417326660f, - -0.608558577651779450f, - 0.793041960479443640f, -0.609167012336453210f, 0.792574502015407690f, - -0.609775088663868430f, - 0.792106577300212390f, -0.610382806276309480f, 0.791638186609125880f, - -0.610990164816271660f, - 0.791169330217690200f, -0.611597163926461910f, 0.790700008401721610f, - -0.612203803249797950f, - 0.790230221437310030f, -0.612810082429409710f, 0.789759969600819070f, - -0.613416001108638590f, - 0.789289253168885650f, -0.614021558931038380f, 0.788818072418420280f, - -0.614626755540375050f, - 0.788346427626606340f, -0.615231590580626820f, 0.787874319070900220f, - -0.615836063695985090f, - 0.787401747029031430f, -0.616440174530853650f, 0.786928711779001810f, - -0.617043922729849760f, - 0.786455213599085770f, -0.617647307937803870f, 0.785981252767830150f, - -0.618250329799760250f, - 0.785506829564053930f, -0.618852987960976320f, 0.785031944266848080f, - -0.619455282066924020f, - 0.784556597155575240f, -0.620057211763289100f, 0.784080788509869950f, - -0.620658776695972140f, - 0.783604518609638200f, -0.621259976511087550f, 0.783127787735057310f, - -0.621860810854965360f, - 0.782650596166575730f, -0.622461279374149970f, 0.782172944184913010f, - -0.623061381715401260f, - 0.781694832071059390f, -0.623661117525694530f, 0.781216260106276090f, - -0.624260486452220650f, - 0.780737228572094490f, -0.624859488142386340f, 0.780257737750316590f, - -0.625458122243814360f, - 0.779777787923014550f, -0.626056388404343520f, 0.779297379372530300f, - -0.626654286272029350f, - 0.778816512381475980f, -0.627251815495144080f, 0.778335187232733210f, - -0.627848975722176460f, - 0.777853404209453150f, -0.628445766601832710f, 0.777371163595056310f, - -0.629042187783036000f, - 0.776888465673232440f, -0.629638238914926980f, 0.776405310727940390f, - -0.630233919646864370f, - 0.775921699043407690f, -0.630829229628424470f, 0.775437630904130540f, - -0.631424168509401860f, - 0.774953106594873930f, -0.632018735939809060f, 0.774468126400670860f, - -0.632612931569877410f, - 0.773982690606822900f, -0.633206755050057190f, 0.773496799498899050f, - -0.633800206031017280f, - 0.773010453362736990f, -0.634393284163645490f, 0.772523652484441330f, - -0.634985989099049460f, - 0.772036397150384520f, -0.635578320488556110f, 0.771548687647206300f, - -0.636170277983712170f, - 0.771060524261813820f, -0.636761861236284200f, 0.770571907281380810f, - -0.637353069898259130f, - 0.770082836993347900f, -0.637943903621844060f, 0.769593313685422940f, - -0.638534362059466790f, - 0.769103337645579700f, -0.639124444863775730f, 0.768612909162058380f, - -0.639714151687640450f, - 0.768122028523365420f, -0.640303482184151670f, 0.767630696018273380f, - -0.640892436006621380f, - 0.767138911935820400f, -0.641481012808583160f, 0.766646676565310380f, - -0.642069212243792540f, - 0.766153990196312920f, -0.642657033966226860f, 0.765660853118662500f, - -0.643244477630085850f, - 0.765167265622458960f, -0.643831542889791390f, 0.764673227998067140f, - -0.644418229399988380f, - 0.764178740536116670f, -0.645004536815543930f, 0.763683803527501870f, - -0.645590464791548690f, - 0.763188417263381270f, -0.646176012983316280f, 0.762692582035177980f, - -0.646761181046383920f, - 0.762196298134578900f, -0.647345968636512060f, 0.761699565853535380f, - -0.647930375409685340f, - 0.761202385484261780f, -0.648514401022112440f, 0.760704757319236920f, - -0.649098045130225950f, - 0.760206681651202420f, -0.649681307390683190f, 0.759708158773163440f, - -0.650264187460365850f, - 0.759209188978388070f, -0.650846684996380880f, 0.758709772560407390f, - -0.651428799656059820f, - 0.758209909813015280f, -0.652010531096959500f, 0.757709601030268080f, - -0.652591878976862440f, - 0.757208846506484570f, -0.653172842953776760f, 0.756707646536245670f, - -0.653753422685936060f, - 0.756206001414394540f, -0.654333617831800440f, 0.755703911436035880f, - -0.654913428050056030f, - 0.755201376896536550f, -0.655492852999615350f, 0.754698398091524500f, - -0.656071892339617600f, - 0.754194975316889170f, -0.656650545729428940f, 0.753691108868781210f, - -0.657228812828642540f, - 0.753186799043612520f, -0.657806693297078640f, 0.752682046138055340f, - -0.658384186794785050f, - 0.752176850449042810f, -0.658961292982037320f, 0.751671212273768430f, - -0.659538011519338660f, - 0.751165131909686480f, -0.660114342067420480f, 0.750658609654510700f, - -0.660690284287242300f, - 0.750151645806215070f, -0.661265837839992270f, 0.749644240663033480f, - -0.661841002387086870f, - 0.749136394523459370f, -0.662415777590171780f, 0.748628107686245440f, - -0.662990163111121470f, - 0.748119380450403600f, -0.663564158612039770f, 0.747610213115205150f, - -0.664137763755260010f, - 0.747100605980180130f, -0.664710978203344790f, 0.746590559345117310f, - -0.665283801619087180f, - 0.746080073510063780f, -0.665856233665509720f, 0.745569148775325430f, - -0.666428274005865240f, - 0.745057785441466060f, -0.666999922303637470f, 0.744545983809307370f, - -0.667571178222540310f, - 0.744033744179929290f, -0.668142041426518450f, 0.743521066854669120f, - -0.668712511579747980f, - 0.743007952135121720f, -0.669282588346636010f, 0.742494400323139180f, - -0.669852271391821020f, - 0.741980411720831070f, -0.670421560380173090f, 0.741465986630563290f, - -0.670990454976794220f, - 0.740951125354959110f, -0.671558954847018330f, 0.740435828196898020f, - -0.672127059656411730f, - 0.739920095459516200f, -0.672694769070772860f, 0.739403927446205760f, - -0.673262082756132970f, - 0.738887324460615110f, -0.673829000378756040f, 0.738370286806648620f, - -0.674395521605139050f, - 0.737852814788465980f, -0.674961646102011930f, 0.737334908710482910f, - -0.675527373536338520f, - 0.736816568877369900f, -0.676092703575315920f, 0.736297795594053170f, - -0.676657635886374950f, - 0.735778589165713590f, -0.677222170137180330f, 0.735258949897786840f, - -0.677786305995631500f, - 0.734738878095963500f, -0.678350043129861470f, 0.734218374066188280f, - -0.678913381208238410f, - 0.733697438114660370f, -0.679476319899364970f, 0.733176070547832740f, - -0.680038858872078930f, - 0.732654271672412820f, -0.680600997795453020f, 0.732132041795361290f, - -0.681162736338795430f, - 0.731609381223892630f, -0.681724074171649710f, 0.731086290265474340f, - -0.682285010963795570f, - 0.730562769227827590f, -0.682845546385248080f, 0.730038818418926260f, - -0.683405680106258680f, - 0.729514438146997010f, -0.683965411797315400f, 0.728989628720519420f, - -0.684524741129142300f, - 0.728464390448225200f, -0.685083667772700360f, 0.727938723639098620f, - -0.685642191399187470f, - 0.727412628602375770f, -0.686200311680038590f, 0.726886105647544970f, - -0.686758028286925890f, - 0.726359155084346010f, -0.687315340891759050f, 0.725831777222770370f, - -0.687872249166685550f, - 0.725303972373060770f, -0.688428752784090440f, 0.724775740845711280f, - -0.688984851416597040f, - 0.724247082951467000f, -0.689540544737066830f, 0.723717999001323500f, - -0.690095832418599950f, - 0.723188489306527460f, -0.690650714134534600f, 0.722658554178575610f, - -0.691205189558448450f, - 0.722128193929215350f, -0.691759258364157750f, 0.721597408870443770f, - -0.692312920225718220f, - 0.721066199314508110f, -0.692866174817424630f, 0.720534565573905270f, - -0.693419021813811760f, - 0.720002507961381650f, -0.693971460889654000f, 0.719470026789932990f, - -0.694523491719965520f, - 0.718937122372804490f, -0.695075113980000880f, 0.718403795023489830f, - -0.695626327345254870f, - 0.717870045055731710f, -0.696177131491462990f, 0.717335872783521730f, - -0.696727526094601200f, - 0.716801278521099540f, -0.697277510830886520f, 0.716266262582953120f, - -0.697827085376777290f, - 0.715730825283818590f, -0.698376249408972920f, 0.715194966938680120f, - -0.698925002604414150f, - 0.714658687862769090f, -0.699473344640283770f, 0.714121988371564820f, - -0.700021275194006250f, - 0.713584868780793640f, -0.700568793943248340f, 0.713047329406429340f, - -0.701115900565918660f, - 0.712509370564692320f, -0.701662594740168450f, 0.711970992572050100f, - -0.702208876144391870f, - 0.711432195745216430f, -0.702754744457225300f, 0.710892980401151680f, - -0.703300199357548730f, - 0.710353346857062420f, -0.703845240524484940f, 0.709813295430400840f, - -0.704389867637400410f, - 0.709272826438865690f, -0.704934080375904880f, 0.708731940200400650f, - -0.705477878419852100f, - 0.708190637033195400f, -0.706021261449339740f, 0.707648917255684350f, - -0.706564229144709510f, - 0.707106781186547570f, -0.707106781186547460f, 0.706564229144709620f, - -0.707648917255684350f, - 0.706021261449339740f, -0.708190637033195290f, 0.705477878419852210f, - -0.708731940200400650f, - 0.704934080375904990f, -0.709272826438865580f, 0.704389867637400410f, - -0.709813295430400840f, - 0.703845240524484940f, -0.710353346857062310f, 0.703300199357548730f, - -0.710892980401151680f, - 0.702754744457225300f, -0.711432195745216430f, 0.702208876144391870f, - -0.711970992572049990f, - 0.701662594740168570f, -0.712509370564692320f, 0.701115900565918660f, - -0.713047329406429230f, - 0.700568793943248450f, -0.713584868780793520f, 0.700021275194006360f, - -0.714121988371564710f, - 0.699473344640283770f, -0.714658687862768980f, 0.698925002604414150f, - -0.715194966938680010f, - 0.698376249408972920f, -0.715730825283818590f, 0.697827085376777290f, - -0.716266262582953120f, - 0.697277510830886630f, -0.716801278521099540f, 0.696727526094601200f, - -0.717335872783521730f, - 0.696177131491462990f, -0.717870045055731710f, 0.695626327345254870f, - -0.718403795023489720f, - 0.695075113980000880f, -0.718937122372804380f, 0.694523491719965520f, - -0.719470026789932990f, - 0.693971460889654000f, -0.720002507961381650f, 0.693419021813811880f, - -0.720534565573905270f, - 0.692866174817424740f, -0.721066199314508110f, 0.692312920225718220f, - -0.721597408870443660f, - 0.691759258364157750f, -0.722128193929215350f, 0.691205189558448450f, - -0.722658554178575610f, - 0.690650714134534720f, -0.723188489306527350f, 0.690095832418599950f, - -0.723717999001323390f, - 0.689540544737066940f, -0.724247082951466890f, 0.688984851416597150f, - -0.724775740845711280f, - 0.688428752784090550f, -0.725303972373060660f, 0.687872249166685550f, - -0.725831777222770370f, - 0.687315340891759160f, -0.726359155084346010f, 0.686758028286925890f, - -0.726886105647544970f, - 0.686200311680038700f, -0.727412628602375770f, 0.685642191399187470f, - -0.727938723639098620f, - 0.685083667772700360f, -0.728464390448225200f, 0.684524741129142300f, - -0.728989628720519310f, - 0.683965411797315510f, -0.729514438146996900f, 0.683405680106258790f, - -0.730038818418926150f, - 0.682845546385248080f, -0.730562769227827590f, 0.682285010963795570f, - -0.731086290265474230f, - 0.681724074171649820f, -0.731609381223892520f, 0.681162736338795430f, - -0.732132041795361290f, - 0.680600997795453130f, -0.732654271672412820f, 0.680038858872079040f, - -0.733176070547832740f, - 0.679476319899365080f, -0.733697438114660260f, 0.678913381208238410f, - -0.734218374066188170f, - 0.678350043129861580f, -0.734738878095963390f, 0.677786305995631500f, - -0.735258949897786730f, - 0.677222170137180450f, -0.735778589165713480f, 0.676657635886374950f, - -0.736297795594053060f, - 0.676092703575316030f, -0.736816568877369790f, 0.675527373536338630f, - -0.737334908710482790f, - 0.674961646102012040f, -0.737852814788465980f, 0.674395521605139050f, - -0.738370286806648510f, - 0.673829000378756150f, -0.738887324460615110f, 0.673262082756132970f, - -0.739403927446205760f, - 0.672694769070772970f, -0.739920095459516090f, 0.672127059656411840f, - -0.740435828196898020f, - 0.671558954847018330f, -0.740951125354959110f, 0.670990454976794220f, - -0.741465986630563290f, - 0.670421560380173090f, -0.741980411720830960f, 0.669852271391821130f, - -0.742494400323139180f, - 0.669282588346636010f, -0.743007952135121720f, 0.668712511579748090f, - -0.743521066854669120f, - 0.668142041426518560f, -0.744033744179929180f, 0.667571178222540310f, - -0.744545983809307250f, - 0.666999922303637470f, -0.745057785441465950f, 0.666428274005865350f, - -0.745569148775325430f, - 0.665856233665509720f, -0.746080073510063780f, 0.665283801619087180f, - -0.746590559345117310f, - 0.664710978203344900f, -0.747100605980180130f, 0.664137763755260010f, - -0.747610213115205150f, - 0.663564158612039880f, -0.748119380450403490f, 0.662990163111121470f, - -0.748628107686245330f, - 0.662415777590171780f, -0.749136394523459260f, 0.661841002387086870f, - -0.749644240663033480f, - 0.661265837839992270f, -0.750151645806214960f, 0.660690284287242300f, - -0.750658609654510590f, - 0.660114342067420480f, -0.751165131909686370f, 0.659538011519338770f, - -0.751671212273768430f, - 0.658961292982037320f, -0.752176850449042700f, 0.658384186794785050f, - -0.752682046138055230f, - 0.657806693297078640f, -0.753186799043612410f, 0.657228812828642650f, - -0.753691108868781210f, - 0.656650545729429050f, -0.754194975316889170f, 0.656071892339617710f, - -0.754698398091524390f, - 0.655492852999615460f, -0.755201376896536550f, 0.654913428050056150f, - -0.755703911436035880f, - 0.654333617831800550f, -0.756206001414394540f, 0.653753422685936170f, - -0.756707646536245670f, - 0.653172842953776760f, -0.757208846506484460f, 0.652591878976862550f, - -0.757709601030268080f, - 0.652010531096959500f, -0.758209909813015280f, 0.651428799656059820f, - -0.758709772560407390f, - 0.650846684996380990f, -0.759209188978387960f, 0.650264187460365960f, - -0.759708158773163440f, - 0.649681307390683190f, -0.760206681651202420f, 0.649098045130226060f, - -0.760704757319236920f, - 0.648514401022112550f, -0.761202385484261780f, 0.647930375409685460f, - -0.761699565853535270f, - 0.647345968636512060f, -0.762196298134578900f, 0.646761181046383920f, - -0.762692582035177870f, - 0.646176012983316390f, -0.763188417263381270f, 0.645590464791548800f, - -0.763683803527501870f, - 0.645004536815544040f, -0.764178740536116670f, 0.644418229399988380f, - -0.764673227998067140f, - 0.643831542889791500f, -0.765167265622458960f, 0.643244477630085850f, - -0.765660853118662390f, - 0.642657033966226860f, -0.766153990196312810f, 0.642069212243792540f, - -0.766646676565310380f, - 0.641481012808583160f, -0.767138911935820400f, 0.640892436006621380f, - -0.767630696018273270f, - 0.640303482184151670f, -0.768122028523365310f, 0.639714151687640450f, - -0.768612909162058270f, - 0.639124444863775730f, -0.769103337645579590f, 0.638534362059466790f, - -0.769593313685422940f, - 0.637943903621844170f, -0.770082836993347900f, 0.637353069898259130f, - -0.770571907281380700f, - 0.636761861236284200f, -0.771060524261813710f, 0.636170277983712170f, - -0.771548687647206300f, - 0.635578320488556230f, -0.772036397150384410f, 0.634985989099049460f, - -0.772523652484441330f, - 0.634393284163645490f, -0.773010453362736990f, 0.633800206031017280f, - -0.773496799498899050f, - 0.633206755050057190f, -0.773982690606822790f, 0.632612931569877520f, - -0.774468126400670860f, - 0.632018735939809060f, -0.774953106594873820f, 0.631424168509401860f, - -0.775437630904130430f, - 0.630829229628424470f, -0.775921699043407580f, 0.630233919646864480f, - -0.776405310727940390f, - 0.629638238914927100f, -0.776888465673232440f, 0.629042187783036000f, - -0.777371163595056200f, - 0.628445766601832710f, -0.777853404209453040f, 0.627848975722176570f, - -0.778335187232733090f, - 0.627251815495144190f, -0.778816512381475870f, 0.626654286272029460f, - -0.779297379372530300f, - 0.626056388404343520f, -0.779777787923014440f, 0.625458122243814360f, - -0.780257737750316590f, - 0.624859488142386450f, -0.780737228572094380f, 0.624260486452220650f, - -0.781216260106276090f, - 0.623661117525694640f, -0.781694832071059390f, 0.623061381715401370f, - -0.782172944184912900f, - 0.622461279374150080f, -0.782650596166575730f, 0.621860810854965360f, - -0.783127787735057310f, - 0.621259976511087660f, -0.783604518609638200f, 0.620658776695972140f, - -0.784080788509869950f, - 0.620057211763289210f, -0.784556597155575240f, 0.619455282066924020f, - -0.785031944266848080f, - 0.618852987960976320f, -0.785506829564053930f, 0.618250329799760250f, - -0.785981252767830150f, - 0.617647307937803980f, -0.786455213599085770f, 0.617043922729849760f, - -0.786928711779001700f, - 0.616440174530853650f, -0.787401747029031320f, 0.615836063695985090f, - -0.787874319070900110f, - 0.615231590580626820f, -0.788346427626606230f, 0.614626755540375050f, - -0.788818072418420170f, - 0.614021558931038490f, -0.789289253168885650f, 0.613416001108638590f, - -0.789759969600819070f, - 0.612810082429409710f, -0.790230221437310030f, 0.612203803249798060f, - -0.790700008401721610f, - 0.611597163926462020f, -0.791169330217690090f, 0.610990164816271770f, - -0.791638186609125770f, - 0.610382806276309480f, -0.792106577300212390f, 0.609775088663868430f, - -0.792574502015407580f, - 0.609167012336453210f, -0.793041960479443640f, 0.608558577651779450f, - -0.793508952417326660f, - 0.607949784967773740f, -0.793975477554337170f, 0.607340634642572930f, - -0.794441535616030590f, - 0.606731127034524480f, -0.794907126328237010f, 0.606121262502186230f, - -0.795372249417061190f, - 0.605511041404325550f, -0.795836904608883460f, 0.604900464099919930f, - -0.796301091630359110f, - 0.604289530948156070f, -0.796764810208418720f, 0.603678242308430370f, - -0.797228060070268700f, - 0.603066598540348280f, -0.797690840943391040f, 0.602454600003723860f, - -0.798153152555543750f, - 0.601842247058580030f, -0.798614994634760820f, 0.601229540065148620f, - -0.799076366909352350f, - 0.600616479383868970f, -0.799537269107905010f, 0.600003065375389060f, - -0.799997700959281910f, - 0.599389298400564540f, -0.800457662192622710f, 0.598775178820458720f, - -0.800917152537344300f, - 0.598160706996342380f, -0.801376171723140130f, 0.597545883289693270f, - -0.801834719479981310f, - 0.596930708062196500f, -0.802292795538115720f, 0.596315181675743820f, - -0.802750399628069160f, - 0.595699304492433470f, -0.803207531480644830f, 0.595083076874569960f, - -0.803664190826924090f, - 0.594466499184664540f, -0.804120377398265700f, 0.593849571785433630f, - -0.804576090926307000f, - 0.593232295039799800f, -0.805031331142963660f, 0.592614669310891130f, - -0.805486097780429120f, - 0.591996694962040990f, -0.805940390571176280f, 0.591378372356787580f, - -0.806394209247956240f, - 0.590759701858874280f, -0.806847553543799220f, 0.590140683832248940f, - -0.807300423192014450f, - 0.589521318641063940f, -0.807752817926190360f, 0.588901606649675840f, - -0.808204737480194720f, - 0.588281548222645330f, -0.808656181588174980f, 0.587661143724736770f, - -0.809107149984558130f, - 0.587040393520918080f, -0.809557642404051260f, 0.586419297976360500f, - -0.810007658581641140f, - 0.585797857456438860f, -0.810457198252594770f, 0.585176072326730410f, - -0.810906261152459670f, - 0.584553942953015330f, -0.811354847017063730f, 0.583931469701276300f, - -0.811802955582515360f, - 0.583308652937698290f, -0.812250586585203880f, 0.582685493028668460f, - -0.812697739761799490f, - 0.582061990340775550f, -0.813144414849253590f, 0.581438145240810280f, - -0.813590611584798510f, - 0.580813958095764530f, -0.814036329705948300f, 0.580189429272831680f, - -0.814481568950498610f, - 0.579564559139405740f, -0.814926329056526620f, 0.578939348063081890f, - -0.815370609762391290f, - 0.578313796411655590f, -0.815814410806733780f, 0.577687904553122800f, - -0.816257731928477390f, - 0.577061672855679550f, -0.816700572866827850f, 0.576435101687721830f, - -0.817142933361272970f, - 0.575808191417845340f, -0.817584813151583710f, 0.575180942414845190f, - -0.818026211977813440f, - 0.574553355047715760f, -0.818467129580298660f, 0.573925429685650750f, - -0.818907565699658950f, - 0.573297166698042320f, -0.819347520076796900f, 0.572668566454481160f, - -0.819786992452898990f, - 0.572039629324757050f, -0.820225982569434690f, 0.571410355678857340f, - -0.820664490168157460f, - 0.570780745886967370f, -0.821102514991104650f, 0.570150800319470300f, - -0.821540056780597610f, - 0.569520519346947250f, -0.821977115279241550f, 0.568889903340175970f, - -0.822413690229926390f, - 0.568258952670131490f, -0.822849781375826320f, 0.567627667707986230f, - -0.823285388460400110f, - 0.566996048825108680f, -0.823720511227391320f, 0.566364096393063950f, - -0.824155149420828570f, - 0.565731810783613230f, -0.824589302785025290f, 0.565099192368714090f, - -0.825022971064580220f, - 0.564466241520519500f, -0.825456154004377440f, 0.563832958611378170f, - -0.825888851349586780f, - 0.563199344013834090f, -0.826321062845663420f, 0.562565398100626560f, - -0.826752788238348520f, - 0.561931121244689470f, -0.827184027273669020f, 0.561296513819151470f, - -0.827614779697938400f, - 0.560661576197336030f, -0.828045045257755800f, 0.560026308752760380f, - -0.828474823700007130f, - 0.559390711859136140f, -0.828904114771864870f, 0.558754785890368310f, - -0.829332918220788250f, - 0.558118531220556100f, -0.829761233794523050f, 0.557481948223991660f, - -0.830189061241102370f, - 0.556845037275160100f, -0.830616400308846200f, 0.556207798748739930f, - -0.831043250746362320f, - 0.555570233019602290f, -0.831469612302545240f, 0.554932340462810370f, - -0.831895484726577590f, - 0.554294121453620110f, -0.832320867767929680f, 0.553655576367479310f, - -0.832745761176359460f, - 0.553016705580027580f, -0.833170164701913190f, 0.552377509467096070f, - -0.833594078094925140f, - 0.551737988404707450f, -0.834017501106018130f, 0.551098142769075430f, - -0.834440433486103190f, - 0.550457972936604810f, -0.834862874986380010f, 0.549817479283891020f, - -0.835284825358337370f, - 0.549176662187719770f, -0.835706284353752600f, 0.548535522025067390f, - -0.836127251724692160f, - 0.547894059173100190f, -0.836547727223511890f, 0.547252274009174090f, - -0.836967710602857020f, - 0.546610166910834860f, -0.837387201615661940f, 0.545967738255817680f, - -0.837806200015150940f, - 0.545324988422046460f, -0.838224705554837970f, 0.544681917787634530f, - -0.838642717988527300f, - 0.544038526730883930f, -0.839060237070312630f, 0.543394815630284800f, - -0.839477262554578550f, - 0.542750784864516000f, -0.839893794195999410f, 0.542106434812444030f, - -0.840309831749540770f, - 0.541461765853123560f, -0.840725374970458070f, 0.540816778365796670f, - -0.841140423614298080f, - 0.540171472729892970f, -0.841554977436898330f, 0.539525849325029010f, - -0.841969036194387680f, - 0.538879908531008420f, -0.842382599643185960f, 0.538233650727821700f, - -0.842795667540004120f, - 0.537587076295645510f, -0.843208239641845440f, 0.536940185614843020f, - -0.843620315706004040f, - 0.536292979065963180f, -0.844031895490066410f, 0.535645457029741090f, - -0.844442978751910660f, - 0.534997619887097260f, -0.844853565249707010f, 0.534349468019137520f, - -0.845263654741918220f, - 0.533701001807152960f, -0.845673246987299070f, 0.533052221632619670f, - -0.846082341744896940f, - 0.532403127877198010f, -0.846490938774052020f, 0.531753720922733320f, - -0.846899037834397350f, - 0.531104001151255000f, -0.847306638685858320f, 0.530453968944976320f, - -0.847713741088654270f, - 0.529803624686294830f, -0.848120344803297120f, 0.529152968757790720f, - -0.848526449590592650f, - 0.528502001542228480f, -0.848932055211639610f, 0.527850723422555460f, - -0.849337161427830670f, - 0.527199134781901390f, -0.849741768000852440f, 0.526547236003579330f, - -0.850145874692685210f, - 0.525895027471084740f, -0.850549481265603370f, 0.525242509568094710f, - -0.850952587482175730f, - 0.524589682678468840f, -0.851355193105265200f, 0.523936547186248600f, - -0.851757297898029120f, - 0.523283103475656430f, -0.852158901623919830f, 0.522629351931096720f, - -0.852560004046683970f, - 0.521975292937154390f, -0.852960604930363630f, 0.521320926878595550f, - -0.853360704039295430f, - 0.520666254140367270f, -0.853760301138111300f, 0.520011275107596040f, - -0.854159395991738730f, - 0.519355990165589530f, -0.854557988365400530f, 0.518700399699835170f, - -0.854956078024614820f, - 0.518044504095999340f, -0.855353664735196030f, 0.517388303739929060f, - -0.855750748263253920f, - 0.516731799017649980f, -0.856147328375194470f, 0.516074990315366630f, - -0.856543404837719960f, - 0.515417878019463150f, -0.856938977417828650f, 0.514760462516501200f, - -0.857334045882815590f, - 0.514102744193221660f, -0.857728610000272120f, 0.513444723436543570f, - -0.858122669538086020f, - 0.512786400633563070f, -0.858516224264442740f, 0.512127776171554690f, - -0.858909273947823900f, - 0.511468850437970520f, -0.859301818357008360f, 0.510809623820439040f, - -0.859693857261072610f, - 0.510150096706766700f, -0.860085390429390140f, 0.509490269484936360f, - -0.860476417631632070f, - 0.508830142543106990f, -0.860866938637767310f, 0.508169716269614710f, - -0.861256953218062060f, - 0.507508991052970870f, -0.861646461143081300f, 0.506847967281863320f, - -0.862035462183687210f, - 0.506186645345155450f, -0.862423956111040500f, 0.505525025631885510f, - -0.862811942696600330f, - 0.504863108531267480f, -0.863199421712124160f, 0.504200894432690560f, - -0.863586392929667990f, - 0.503538383725717580f, -0.863972856121586700f, 0.502875576800086880f, - -0.864358811060534030f, - 0.502212474045710900f, -0.864744257519462380f, 0.501549075852675390f, - -0.865129195271623690f, - 0.500885382611240940f, -0.865513624090568980f, 0.500221394711840680f, - -0.865897543750148820f, - 0.499557112545081890f, -0.866280954024512990f, 0.498892536501744750f, - -0.866663854688111020f, - 0.498227666972781870f, -0.867046245515692650f, 0.497562504349319090f, - -0.867428126282306920f, - 0.496897049022654640f, -0.867809496763303210f, 0.496231301384258310f, - -0.868190356734331310f, - 0.495565261825772490f, -0.868570705971340900f, 0.494898930739011310f, - -0.868950544250582380f, - 0.494232308515959730f, -0.869329871348606730f, 0.493565395548774880f, - -0.869708687042265560f, - 0.492898192229784090f, -0.870086991108711350f, 0.492230698951486080f, - -0.870464783325397670f, - 0.491562916106550060f, -0.870842063470078860f, 0.490894844087815140f, - -0.871218831320810900f, - 0.490226483288291100f, -0.871595086655951090f, 0.489557834101157550f, - -0.871970829254157700f, - 0.488888896919763230f, -0.872346058894391540f, 0.488219672137626740f, - -0.872720775355914300f, - 0.487550160148436050f, -0.873094978418290090f, 0.486880361346047400f, - -0.873468667861384880f, - 0.486210276124486530f, -0.873841843465366750f, 0.485539904877947020f, - -0.874214505010706300f, - 0.484869248000791120f, -0.874586652278176110f, 0.484198305887549140f, - -0.874958285048851540f, - 0.483527078932918740f, -0.875329403104110780f, 0.482855567531765670f, - -0.875700006225634600f, - 0.482183772079122830f, -0.876070094195406600f, 0.481511692970189920f, - -0.876439666795713610f, - 0.480839330600333900f, -0.876808723809145760f, 0.480166685365088440f, - -0.877177265018595940f, - 0.479493757660153010f, -0.877545290207261240f, 0.478820547881394050f, - -0.877912799158641730f, - 0.478147056424843120f, -0.878279791656541460f, 0.477473283686698060f, - -0.878646267485068130f, - 0.476799230063322250f, -0.879012226428633410f, 0.476124895951243630f, - -0.879377668271953180f, - 0.475450281747155870f, -0.879742592800047410f, 0.474775387847917230f, - -0.880106999798240360f, - 0.474100214650550020f, -0.880470889052160750f, 0.473424762552241530f, - -0.880834260347742040f, - 0.472749031950342900f, -0.881197113471221980f, 0.472073023242368660f, - -0.881559448209143780f, - 0.471396736825997810f, -0.881921264348354940f, 0.470720173099071710f, - -0.882282561676008600f, - 0.470043332459595620f, -0.882643339979562790f, 0.469366215305737630f, - -0.883003599046780720f, - 0.468688822035827960f, -0.883363338665731580f, 0.468011153048359830f, - -0.883722558624789660f, - 0.467333208741988530f, -0.884081258712634990f, 0.466654989515530970f, - -0.884439438718253700f, - 0.465976495767966130f, -0.884797098430937790f, 0.465297727898434650f, - -0.885154237640285110f, - 0.464618686306237820f, -0.885510856136199950f, 0.463939371390838460f, - -0.885866953708892790f, - 0.463259783551860260f, -0.886222530148880640f, 0.462579923189086810f, - -0.886577585246987040f, - 0.461899790702462840f, -0.886932118794342080f, 0.461219386492092430f, - -0.887286130582383150f, - 0.460538710958240010f, -0.887639620402853930f, 0.459857764501329650f, - -0.887992588047805560f, - 0.459176547521944150f, -0.888345033309596240f, 0.458495060420826220f, - -0.888696955980891710f, - 0.457813303598877290f, -0.889048355854664570f, 0.457131277457156980f, - -0.889399232724195520f, - 0.456448982396883860f, -0.889749586383072890f, 0.455766418819434750f, - -0.890099416625192210f, - 0.455083587126343840f, -0.890448723244757880f, 0.454400487719303750f, - -0.890797506036281490f, - 0.453717121000163930f, -0.891145764794583180f, 0.453033487370931580f, - -0.891493499314791380f, - 0.452349587233771000f, -0.891840709392342720f, 0.451665420991002540f, - -0.892187394822982480f, - 0.450980989045103810f, -0.892533555402764690f, 0.450296291798708730f, - -0.892879190928051680f, - 0.449611329654606600f, -0.893224301195515320f, 0.448926103015743260f, - -0.893568886002136020f, - 0.448240612285220000f, -0.893912945145203250f, 0.447554857866293010f, - -0.894256478422316040f, - 0.446868840162374330f, -0.894599485631382580f, 0.446182559577030120f, - -0.894941966570620750f, - 0.445496016513981740f, -0.895283921038557580f, 0.444809211377105000f, - -0.895625348834030000f, - 0.444122144570429260f, -0.895966249756185110f, 0.443434816498138430f, - -0.896306623604479660f, - 0.442747227564570130f, -0.896646470178680150f, 0.442059378174214760f, - -0.896985789278863970f, - 0.441371268731716620f, -0.897324580705418320f, 0.440682899641873020f, - -0.897662844259040750f, - 0.439994271309633260f, -0.898000579740739880f, 0.439305384140100060f, - -0.898337786951834190f, - 0.438616238538527710f, -0.898674465693953820f, 0.437926834910322860f, - -0.899010615769039070f, - 0.437237173661044200f, -0.899346236979341460f, 0.436547255196401250f, - -0.899681329127423930f, - 0.435857079922255470f, -0.900015892016160280f, 0.435166648244619370f, - -0.900349925448735600f, - 0.434475960569655710f, -0.900683429228646860f, 0.433785017303678520f, - -0.901016403159702330f, - 0.433093818853152010f, -0.901348847046022030f, 0.432402365624690140f, - -0.901680760692037730f, - 0.431710658025057370f, -0.902012143902493070f, 0.431018696461167080f, - -0.902342996482444200f, - 0.430326481340082610f, -0.902673318237258830f, 0.429634013069016500f, - -0.903003108972617040f, - 0.428941292055329550f, -0.903332368494511820f, 0.428248318706531910f, - -0.903661096609247980f, - 0.427555093430282200f, -0.903989293123443340f, 0.426861616634386490f, - -0.904316957844028320f, - 0.426167888726799620f, -0.904644090578246240f, 0.425473910115623910f, - -0.904970691133653250f, - 0.424779681209108810f, -0.905296759318118820f, 0.424085202415651670f, - -0.905622294939825160f, - 0.423390474143796100f, -0.905947297807268460f, 0.422695496802232950f, - -0.906271767729257660f, - 0.422000270799799790f, -0.906595704514915330f, 0.421304796545479700f, - -0.906919107973678030f, - 0.420609074448402510f, -0.907241977915295930f, 0.419913104917843730f, - -0.907564314149832520f, - 0.419216888363223960f, -0.907886116487666150f, 0.418520425194109700f, - -0.908207384739488700f, - 0.417823715820212380f, -0.908528118716306120f, 0.417126760651387870f, - -0.908848318229439120f, - 0.416429560097637320f, -0.909167983090522270f, 0.415732114569105420f, - -0.909487113111505430f, - 0.415034424476081630f, -0.909805708104652220f, 0.414336490228999210f, - -0.910123767882541570f, - 0.413638312238434560f, -0.910441292258067140f, 0.412939890915108020f, - -0.910758281044437570f, - 0.412241226669883000f, -0.911074734055176250f, 0.411542319913765280f, - -0.911390651104122320f, - 0.410843171057903910f, -0.911706032005429880f, 0.410143780513590350f, - -0.912020876573568230f, - 0.409444148692257590f, -0.912335184623322750f, 0.408744276005481520f, - -0.912648955969793900f, - 0.408044162864978740f, -0.912962190428398100f, 0.407343809682607970f, - -0.913274887814867760f, - 0.406643216870369140f, -0.913587047945250810f, 0.405942384840402570f, - -0.913898670635911680f, - 0.405241314004989860f, -0.914209755703530690f, 0.404540004776553110f, - -0.914520302965104450f, - 0.403838457567654130f, -0.914830312237946090f, 0.403136672790995240f, - -0.915139783339685260f, - 0.402434650859418540f, -0.915448716088267830f, 0.401732392185905010f, - -0.915757110301956720f, - 0.401029897183575790f, -0.916064965799331610f, 0.400327166265690150f, - -0.916372282399289140f, - 0.399624199845646790f, -0.916679059921042700f, 0.398920998336983020f, - -0.916985298184122890f, - 0.398217562153373620f, -0.917290997008377910f, 0.397513891708632330f, - -0.917596156213972950f, - 0.396809987416710420f, -0.917900775621390390f, 0.396105849691696320f, - -0.918204855051430900f, - 0.395401478947816300f, -0.918508394325212250f, 0.394696875599433670f, - -0.918811393264169940f, - 0.393992040061048100f, -0.919113851690057770f, 0.393286972747296570f, - -0.919415769424946960f, - 0.392581674072951530f, -0.919717146291227360f, 0.391876144452922350f, - -0.920017982111606570f, - 0.391170384302253980f, -0.920318276709110480f, 0.390464394036126650f, - -0.920618029907083860f, - 0.389758174069856410f, -0.920917241529189520f, 0.389051724818894500f, - -0.921215911399408730f, - 0.388345046698826300f, -0.921514039342041900f, 0.387638140125372680f, - -0.921811625181708120f, - 0.386931005514388690f, -0.922108668743345070f, 0.386223643281862980f, - -0.922405169852209880f, - 0.385516053843919020f, -0.922701128333878520f, 0.384808237616812930f, - -0.922996544014246250f, - 0.384100195016935040f, -0.923291416719527640f, 0.383391926460808770f, - -0.923585746276256560f, - 0.382683432365089840f, -0.923879532511286740f, 0.381974713146567220f, - -0.924172775251791200f, - 0.381265769222162490f, -0.924465474325262600f, 0.380556601008928570f, - -0.924757629559513910f, - 0.379847208924051110f, -0.925049240782677580f, 0.379137593384847430f, - -0.925340307823206200f, - 0.378427754808765620f, -0.925630830509872720f, 0.377717693613385810f, - -0.925920808671769960f, - 0.377007410216418310f, -0.926210242138311270f, 0.376296905035704790f, - -0.926499130739230510f, - 0.375586178489217330f, -0.926787474304581750f, 0.374875230995057600f, - -0.927075272664740100f, - 0.374164062971457990f, -0.927362525650401110f, 0.373452674836780410f, - -0.927649233092581180f, - 0.372741067009515810f, -0.927935394822617890f, 0.372029239908284960f, - -0.928221010672169440f, - 0.371317193951837600f, -0.928506080473215480f, 0.370604929559051670f, - -0.928790604058057020f, - 0.369892447148934270f, -0.929074581259315750f, 0.369179747140620070f, - -0.929358011909935500f, - 0.368466829953372320f, -0.929640895843181330f, 0.367753696006582090f, - -0.929923232892639560f, - 0.367040345719767240f, -0.930205022892219070f, 0.366326779512573590f, - -0.930486265676149780f, - 0.365612997804773960f, -0.930766961078983710f, 0.364899001016267380f, - -0.931047108935595170f, - 0.364184789567079840f, -0.931326709081180430f, 0.363470363877363870f, - -0.931605761351257830f, - 0.362755724367397230f, -0.931884265581668150f, 0.362040871457584350f, - -0.932162221608574320f, - 0.361325805568454340f, -0.932439629268462360f, 0.360610527120662270f, - -0.932716488398140250f, - 0.359895036534988280f, -0.932992798834738850f, 0.359179334232336560f, - -0.933268560415712050f, - 0.358463420633736540f, -0.933543772978836170f, 0.357747296160342010f, - -0.933818436362210960f, - 0.357030961233430030f, -0.934092550404258870f, 0.356314416274402360f, - -0.934366114943725900f, - 0.355597661704783960f, -0.934639129819680780f, 0.354880697946222790f, - -0.934911594871516090f, - 0.354163525420490510f, -0.935183509938947500f, 0.353446144549480870f, - -0.935454874862014620f, - 0.352728555755210730f, -0.935725689481080370f, 0.352010759459819240f, - -0.935995953636831300f, - 0.351292756085567150f, -0.936265667170278260f, 0.350574546054837570f, - -0.936534829922755500f, - 0.349856129790135030f, -0.936803441735921560f, 0.349137507714085030f, - -0.937071502451759190f, - 0.348418680249434510f, -0.937339011912574960f, 0.347699647819051490f, - -0.937605969960999990f, - 0.346980410845923680f, -0.937872376439989890f, 0.346260969753160170f, - -0.938138231192824360f, - 0.345541324963989150f, -0.938403534063108060f, 0.344821476901759290f, - -0.938668284894770170f, - 0.344101425989938980f, -0.938932483532064490f, 0.343381172652115100f, - -0.939196129819569900f, - 0.342660717311994380f, -0.939459223602189920f, 0.341940060393402300f, - -0.939721764725153340f, - 0.341219202320282410f, -0.939983753034013940f, 0.340498143516697100f, - -0.940245188374650880f, - 0.339776884406826960f, -0.940506070593268300f, 0.339055425414969640f, - -0.940766399536396070f, - 0.338333766965541290f, -0.941026175050889260f, 0.337611909483074680f, - -0.941285396983928660f, - 0.336889853392220050f, -0.941544065183020810f, 0.336167599117744690f, - -0.941802179495997650f, - 0.335445147084531660f, -0.942059739771017310f, 0.334722497717581220f, - -0.942316745856563780f, - 0.333999651442009490f, -0.942573197601446870f, 0.333276608683047980f, - -0.942829094854802710f, - 0.332553369866044220f, -0.943084437466093490f, 0.331829935416461220f, - -0.943339225285107720f, - 0.331106305759876430f, -0.943593458161960390f, 0.330382481321982950f, - -0.943847135947092690f, - 0.329658462528587550f, -0.944100258491272660f, 0.328934249805612200f, - -0.944352825645594750f, - 0.328209843579092660f, -0.944604837261480260f, 0.327485244275178060f, - -0.944856293190677210f, - 0.326760452320131790f, -0.945107193285260610f, 0.326035468140330350f, - -0.945357537397632290f, - 0.325310292162262980f, -0.945607325380521280f, 0.324584924812532150f, - -0.945856557086983910f, - 0.323859366517852960f, -0.946105232370403340f, 0.323133617705052330f, - -0.946353351084490590f, - 0.322407678801070020f, -0.946600913083283530f, 0.321681550232956640f, - -0.946847918221148000f, - 0.320955232427875210f, -0.947094366352777220f, 0.320228725813100020f, - -0.947340257333191940f, - 0.319502030816015750f, -0.947585591017741090f, 0.318775147864118480f, - -0.947830367262101010f, - 0.318048077385015060f, -0.948074585922276230f, 0.317320819806421790f, - -0.948318246854599090f, - 0.316593375556165850f, -0.948561349915730270f, 0.315865745062184070f, - -0.948803894962658380f, - 0.315137928752522440f, -0.949045881852700560f, 0.314409927055336820f, - -0.949287310443502010f, - 0.313681740398891570f, -0.949528180593036670f, 0.312953369211560200f, - -0.949768492159606680f, - 0.312224813921825050f, -0.950008245001843000f, 0.311496074958275970f, - -0.950247438978705230f, - 0.310767152749611470f, -0.950486073949481700f, 0.310038047724638000f, - -0.950724149773789610f, - 0.309308760312268780f, -0.950961666311575080f, 0.308579290941525030f, - -0.951198623423113230f, - 0.307849640041534980f, -0.951435020969008340f, 0.307119808041533100f, - -0.951670858810193860f, - 0.306389795370861080f, -0.951906136807932230f, 0.305659602458966230f, - -0.952140854823815830f, - 0.304929229735402430f, -0.952375012719765880f, 0.304198677629829270f, - -0.952608610358033240f, - 0.303467946572011370f, -0.952841647601198720f, 0.302737036991819140f, - -0.953074124312172200f, - 0.302005949319228200f, -0.953306040354193750f, 0.301274683984318000f, - -0.953537395590833280f, - 0.300543241417273400f, -0.953768189885990330f, 0.299811622048383460f, - -0.953998423103894490f, - 0.299079826308040480f, -0.954228095109105670f, 0.298347854626741570f, - -0.954457205766513490f, - 0.297615707435086310f, -0.954685754941338340f, 0.296883385163778270f, - -0.954913742499130520f, - 0.296150888243623960f, -0.955141168305770670f, 0.295418217105532070f, - -0.955368032227470240f, - 0.294685372180514330f, -0.955594334130771110f, 0.293952353899684770f, - -0.955820073882545420f, - 0.293219162694258680f, -0.956045251349996410f, 0.292485798995553830f, - -0.956269866400658140f, - 0.291752263234989370f, -0.956493918902394990f, 0.291018555844085090f, - -0.956717408723403050f, - 0.290284677254462330f, -0.956940335732208940f, 0.289550627897843140f, - -0.957162699797670100f, - 0.288816408206049480f, -0.957384500788975860f, 0.288082018611004300f, - -0.957605738575646240f, - 0.287347459544729570f, -0.957826413027532910f, 0.286612731439347790f, - -0.958046524014818600f, - 0.285877834727080730f, -0.958266071408017670f, 0.285142769840248720f, - -0.958485055077976100f, - 0.284407537211271820f, -0.958703474895871600f, 0.283672137272668550f, - -0.958921330733213060f, - 0.282936570457055390f, -0.959138622461841890f, 0.282200837197147500f, - -0.959355349953930790f, - 0.281464937925758050f, -0.959571513081984520f, 0.280728873075797190f, - -0.959787111718839900f, - 0.279992643080273380f, -0.960002145737665850f, 0.279256248372291240f, - -0.960216615011963430f, - 0.278519689385053060f, -0.960430519415565790f, 0.277782966551857800f, - -0.960643858822638470f, - 0.277046080306099950f, -0.960856633107679660f, 0.276309031081271030f, - -0.961068842145519350f, - 0.275571819310958250f, -0.961280485811320640f, 0.274834445428843940f, - -0.961491563980579000f, - 0.274096909868706330f, -0.961702076529122540f, 0.273359213064418790f, - -0.961912023333112100f, - 0.272621355449948980f, -0.962121404269041580f, 0.271883337459359890f, - -0.962330219213737400f, - 0.271145159526808070f, -0.962538468044359160f, 0.270406822086544820f, - -0.962746150638399410f, - 0.269668325572915200f, -0.962953266873683880f, 0.268929670420357310f, - -0.963159816628371360f, - 0.268190857063403180f, -0.963365799780954050f, 0.267451885936677740f, - -0.963571216210257210f, - 0.266712757474898420f, -0.963776065795439840f, 0.265973472112875530f, - -0.963980348415994110f, - 0.265234030285511900f, -0.964184063951745720f, 0.264494432427801630f, - -0.964387212282854290f, - 0.263754678974831510f, -0.964589793289812650f, 0.263014770361779060f, - -0.964791806853447900f, - 0.262274707023913590f, -0.964993252854920320f, 0.261534489396595630f, - -0.965194131175724720f, - 0.260794117915275570f, -0.965394441697689400f, 0.260053593015495130f, - -0.965594184302976830f, - 0.259312915132886350f, -0.965793358874083570f, 0.258572084703170390f, - -0.965991965293840570f, - 0.257831102162158930f, -0.966190003445412620f, 0.257089967945753230f, - -0.966387473212298790f, - 0.256348682489942910f, -0.966584374478333120f, 0.255607246230807550f, - -0.966780707127683270f, - 0.254865659604514630f, -0.966976471044852070f, 0.254123923047320620f, - -0.967171666114676640f, - 0.253382036995570270f, -0.967366292222328510f, 0.252640001885695580f, - -0.967560349253314360f, - 0.251897818154216910f, -0.967753837093475510f, 0.251155486237742030f, - -0.967946755628987800f, - 0.250413006572965280f, -0.968139104746362330f, 0.249670379596668520f, - -0.968330884332445300f, - 0.248927605745720260f, -0.968522094274417270f, 0.248184685457074780f, - -0.968712734459794780f, - 0.247441619167773440f, -0.968902804776428870f, 0.246698407314942500f, - -0.969092305112506100f, - 0.245955050335794590f, -0.969281235356548530f, 0.245211548667627680f, - -0.969469595397412950f, - 0.244467902747824210f, -0.969657385124292450f, 0.243724113013852130f, - -0.969844604426714830f, - 0.242980179903263980f, -0.970031253194543970f, 0.242236103853696070f, - -0.970217331317979160f, - 0.241491885302869300f, -0.970402838687555500f, 0.240747524688588540f, - -0.970587775194143630f, - 0.240003022448741500f, -0.970772140728950350f, 0.239258379021300120f, - -0.970955935183517970f, - 0.238513594844318500f, -0.971139158449725090f, 0.237768670355934210f, - -0.971321810419786160f, - 0.237023605994367340f, -0.971503890986251780f, 0.236278402197919620f, - -0.971685400042008540f, - 0.235533059404975460f, -0.971866337480279400f, 0.234787578054001080f, - -0.972046703194623500f, - 0.234041958583543460f, -0.972226497078936270f, 0.233296201432231560f, - -0.972405719027449770f, - 0.232550307038775330f, -0.972584368934732210f, 0.231804275841964780f, - -0.972762446695688570f, - 0.231058108280671280f, -0.972939952205560070f, 0.230311804793845530f, - -0.973116885359925130f, - 0.229565365820518870f, -0.973293246054698250f, 0.228818791799802360f, - -0.973469034186130950f, - 0.228072083170885790f, -0.973644249650811870f, 0.227325240373038830f, - -0.973818892345666100f, - 0.226578263845610110f, -0.973992962167955830f, 0.225831154028026200f, - -0.974166459015280320f, - 0.225083911359792780f, -0.974339382785575860f, 0.224336536280493690f, - -0.974511733377115720f, - 0.223589029229790020f, -0.974683510688510670f, 0.222841390647421280f, - -0.974854714618708430f, - 0.222093620973203590f, -0.975025345066994120f, 0.221345720647030810f, - -0.975195401932990370f, - 0.220597690108873650f, -0.975364885116656870f, 0.219849529798778750f, - -0.975533794518291360f, - 0.219101240156869770f, -0.975702130038528570f, 0.218352821623346430f, - -0.975869891578341030f, - 0.217604274638483670f, -0.976037079039039020f, 0.216855599642632570f, - -0.976203692322270560f, - 0.216106797076219600f, -0.976369731330021140f, 0.215357867379745550f, - -0.976535195964614470f, - 0.214608810993786920f, -0.976700086128711840f, 0.213859628358993830f, - -0.976864401725312640f, - 0.213110319916091360f, -0.977028142657754390f, 0.212360886105878580f, - -0.977191308829712280f, - 0.211611327369227610f, -0.977353900145199960f, 0.210861644147084830f, - -0.977515916508569280f, - 0.210111836880469720f, -0.977677357824509930f, 0.209361906010474190f, - -0.977838223998050430f, - 0.208611851978263460f, -0.977998514934557140f, 0.207861675225075150f, - -0.978158230539735050f, - 0.207111376192218560f, -0.978317370719627650f, 0.206360955321075680f, - -0.978475935380616830f, - 0.205610413053099320f, -0.978633924429423100f, 0.204859749829814420f, - -0.978791337773105670f, - 0.204108966092817010f, -0.978948175319062200f, 0.203358062283773370f, - -0.979104436975029250f, - 0.202607038844421110f, -0.979260122649082020f, 0.201855896216568160f, - -0.979415232249634780f, - 0.201104634842091960f, -0.979569765685440520f, 0.200353255162940420f, - -0.979723722865591170f, - 0.199601757621131050f, -0.979877103699517640f, 0.198850142658750120f, - -0.980029908096989980f, - 0.198098410717953730f, -0.980182135968117320f, 0.197346562240966000f, - -0.980333787223347960f, - 0.196594597670080220f, -0.980484861773469380f, 0.195842517447657990f, - -0.980635359529608120f, - 0.195090322016128330f, -0.980785280403230430f, 0.194338011817988600f, - -0.980934624306141640f, - 0.193585587295803750f, -0.981083391150486590f, 0.192833048892205290f, - -0.981231580848749730f, - 0.192080397049892380f, -0.981379193313754560f, 0.191327632211630990f, - -0.981526228458664660f, - 0.190574754820252800f, -0.981672686196983110f, 0.189821765318656580f, - -0.981818566442552500f, - 0.189068664149806280f, -0.981963869109555240f, 0.188315451756732120f, - -0.982108594112513610f, - 0.187562128582529740f, -0.982252741366289370f, 0.186808695070359330f, - -0.982396310786084690f, - 0.186055151663446630f, -0.982539302287441240f, 0.185301498805082040f, - -0.982681715786240860f, - 0.184547736938619640f, -0.982823551198705240f, 0.183793866507478390f, - -0.982964808441396440f, - 0.183039887955141060f, -0.983105487431216290f, 0.182285801725153320f, - -0.983245588085407070f, - 0.181531608261125130f, -0.983385110321551180f, 0.180777308006728670f, - -0.983524054057571260f, - 0.180022901405699510f, -0.983662419211730250f, 0.179268388901835880f, - -0.983800205702631490f, - 0.178513770938997590f, -0.983937413449218920f, 0.177759047961107140f, - -0.984074042370776450f, - 0.177004220412148860f, -0.984210092386929030f, 0.176249288736167940f, - -0.984345563417641900f, - 0.175494253377271400f, -0.984480455383220930f, 0.174739114779627310f, - -0.984614768204312600f, - 0.173983873387463850f, -0.984748501801904210f, 0.173228529645070490f, - -0.984881656097323700f, - 0.172473083996796030f, -0.985014231012239840f, 0.171717536887049970f, - -0.985146226468662230f, - 0.170961888760301360f, -0.985277642388941220f, 0.170206140061078120f, - -0.985408478695768420f, - 0.169450291233967930f, -0.985538735312176060f, 0.168694342723617440f, - -0.985668412161537550f, - 0.167938294974731230f, -0.985797509167567370f, 0.167182148432072880f, - -0.985926026254321130f, - 0.166425903540464220f, -0.986053963346195440f, 0.165669560744784140f, - -0.986181320367928270f, - 0.164913120489970090f, -0.986308097244598670f, 0.164156583221015890f, - -0.986434293901627070f, - 0.163399949382973230f, -0.986559910264775410f, 0.162643219420950450f, - -0.986684946260146690f, - 0.161886393780111910f, -0.986809401814185420f, 0.161129472905678780f, - -0.986933276853677710f, - 0.160372457242928400f, -0.987056571305750970f, 0.159615347237193090f, - -0.987179285097874340f, - 0.158858143333861390f, -0.987301418157858430f, 0.158100845978377090f, - -0.987422970413855410f, - 0.157343455616238280f, -0.987543941794359230f, 0.156585972692998590f, - -0.987664332228205710f, - 0.155828397654265320f, -0.987784141644572180f, 0.155070730945700510f, - -0.987903369972977790f, - 0.154312973013020240f, -0.988022017143283530f, 0.153555124301993500f, - -0.988140083085692570f, - 0.152797185258443410f, -0.988257567730749460f, 0.152039156328246160f, - -0.988374471009341280f, - 0.151281037957330250f, -0.988490792852696590f, 0.150522830591677370f, - -0.988606533192386450f, - 0.149764534677321620f, -0.988721691960323780f, 0.149006150660348470f, - -0.988836269088763540f, - 0.148247678986896200f, -0.988950264510302990f, 0.147489120103153680f, - -0.989063678157881540f, - 0.146730474455361750f, -0.989176509964781010f, 0.145971742489812370f, - -0.989288759864625170f, - 0.145212924652847520f, -0.989400427791380380f, 0.144454021390860440f, - -0.989511513679355190f, - 0.143695033150294580f, -0.989622017463200780f, 0.142935960377642700f, - -0.989731939077910570f, - 0.142176803519448000f, -0.989841278458820530f, 0.141417563022303130f, - -0.989950035541608990f, - 0.140658239332849240f, -0.990058210262297120f, 0.139898832897777380f, - -0.990165802557248400f, - 0.139139344163826280f, -0.990272812363169110f, 0.138379773577783890f, - -0.990379239617108160f, - 0.137620121586486180f, -0.990485084256456980f, 0.136860388636816430f, - -0.990590346218950150f, - 0.136100575175706200f, -0.990695025442664630f, 0.135340681650134330f, - -0.990799121866020370f, - 0.134580708507126220f, -0.990902635427780010f, 0.133820656193754690f, - -0.991005566067049370f, - 0.133060525157139180f, -0.991107913723276780f, 0.132300315844444680f, - -0.991209678336254060f, - 0.131540028702883280f, -0.991310859846115440f, 0.130779664179711790f, - -0.991411458193338540f, - 0.130019222722233350f, -0.991511473318743900f, 0.129258704777796270f, - -0.991610905163495370f, - 0.128498110793793220f, -0.991709753669099530f, 0.127737441217662280f, - -0.991808018777406430f, - 0.126976696496885980f, -0.991905700430609330f, 0.126215877078990400f, - -0.992002798571244520f, - 0.125454983411546210f, -0.992099313142191800f, 0.124694015942167770f, - -0.992195244086673920f, - 0.123932975118512200f, -0.992290591348257370f, 0.123171861388280650f, - -0.992385354870851670f, - 0.122410675199216280f, -0.992479534598709970f, 0.121649416999105540f, - -0.992573130476428810f, - 0.120888087235777220f, -0.992666142448948020f, 0.120126686357101580f, - -0.992758570461551140f, - 0.119365214810991350f, -0.992850414459865100f, 0.118603673045400840f, - -0.992941674389860470f, - 0.117842061508325020f, -0.993032350197851410f, 0.117080380647800550f, - -0.993122441830495580f, - 0.116318630911904880f, -0.993211949234794500f, 0.115556812748755290f, - -0.993300872358093280f, - 0.114794926606510250f, -0.993389211148080650f, 0.114032972933367300f, - -0.993476965552789190f, - 0.113270952177564360f, -0.993564135520595300f, 0.112508864787378830f, - -0.993650721000219120f, - 0.111746711211126660f, -0.993736721940724600f, 0.110984491897163380f, - -0.993822138291519660f, - 0.110222207293883180f, -0.993906970002356060f, 0.109459857849718030f, - -0.993991217023329380f, - 0.108697444013138670f, -0.994074879304879370f, 0.107934966232653760f, - -0.994157956797789730f, - 0.107172424956808870f, -0.994240449453187900f, 0.106409820634187840f, - -0.994322357222545810f, - 0.105647153713410700f, -0.994403680057679100f, 0.104884424643134970f, - -0.994484417910747600f, - 0.104121633872054730f, -0.994564570734255420f, 0.103358781848899700f, - -0.994644138481050710f, - 0.102595869022436280f, -0.994723121104325700f, 0.101832895841466670f, - -0.994801518557617110f, - 0.101069862754827880f, -0.994879330794805620f, 0.100306770211392820f, - -0.994956557770116380f, - 0.099543618660069444f, -0.995033199438118630f, 0.098780408549799664f, - -0.995109255753726110f, - 0.098017140329560770f, -0.995184726672196820f, 0.097253814448363354f, - -0.995259612149133390f, - 0.096490431355252607f, -0.995333912140482280f, 0.095726991499307315f, - -0.995407626602534900f, - 0.094963495329639061f, -0.995480755491926940f, 0.094199943295393190f, - -0.995553298765638470f, - 0.093436335845747912f, -0.995625256380994310f, 0.092672673429913366f, - -0.995696628295663520f, - 0.091908956497132696f, -0.995767414467659820f, 0.091145185496681130f, - -0.995837614855341610f, - 0.090381360877865011f, -0.995907229417411720f, 0.089617483090022917f, - -0.995976258112917790f, - 0.088853552582524684f, -0.996044700901251970f, 0.088089569804770507f, - -0.996112557742151130f, - 0.087325535206192226f, -0.996179828595696870f, 0.086561449236251239f, - -0.996246513422315520f, - 0.085797312344439880f, -0.996312612182778000f, 0.085033124980280414f, - -0.996378124838200210f, - 0.084268887593324127f, -0.996443051350042630f, 0.083504600633152404f, - -0.996507391680110820f, - 0.082740264549375803f, -0.996571145790554840f, 0.081975879791633108f, - -0.996634313643869900f, - 0.081211446809592386f, -0.996696895202896060f, 0.080446966052950097f, - -0.996758890430818000f, - 0.079682437971430126f, -0.996820299291165670f, 0.078917863014785095f, - -0.996881121747813850f, - 0.078153241632794315f, -0.996941357764982160f, 0.077388574275265049f, - -0.997001007307235290f, - 0.076623861392031617f, -0.997060070339482960f, 0.075859103432954503f, - -0.997118546826979980f, - 0.075094300847921291f, -0.997176436735326190f, 0.074329454086845867f, - -0.997233740030466160f, - 0.073564563599667454f, -0.997290456678690210f, 0.072799629836351618f, - -0.997346586646633230f, - 0.072034653246889416f, -0.997402129901275300f, 0.071269634281296415f, - -0.997457086409941910f, - 0.070504573389614009f, -0.997511456140303450f, 0.069739471021907376f, - -0.997565239060375750f, - 0.068974327628266732f, -0.997618435138519550f, 0.068209143658806454f, - -0.997671044343441000f, - 0.067443919563664106f, -0.997723066644191640f, 0.066678655793001543f, - -0.997774502010167820f, - 0.065913352797003930f, -0.997825350411111640f, 0.065148011025878860f, - -0.997875611817110150f, - 0.064382630929857410f, -0.997925286198596000f, 0.063617212959193190f, - -0.997974373526346990f, - 0.062851757564161420f, -0.998022873771486240f, 0.062086265195060247f, - -0.998070786905482340f, - 0.061320736302208648f, -0.998118112900149180f, 0.060555171335947781f, - -0.998164851727646240f, - 0.059789570746640007f, -0.998211003360478190f, 0.059023934984667986f, - -0.998256567771495180f, - 0.058258264500435732f, -0.998301544933892890f, 0.057492559744367684f, - -0.998345934821212370f, - 0.056726821166907783f, -0.998389737407340160f, 0.055961049218520520f, - -0.998432952666508440f, - 0.055195244349690031f, -0.998475580573294770f, 0.054429407010919147f, - -0.998517621102622210f, - 0.053663537652730679f, -0.998559074229759310f, 0.052897636725665401f, - -0.998599939930320370f, - 0.052131704680283317f, -0.998640218180265270f, 0.051365741967162731f, - -0.998679908955899090f, - 0.050599749036899337f, -0.998719012233872940f, 0.049833726340107257f, - -0.998757527991183340f, - 0.049067674327418126f, -0.998795456205172410f, 0.048301593449480172f, - -0.998832796853527990f, - 0.047535484156959261f, -0.998869549914283560f, 0.046769346900537960f, - -0.998905715365818290f, - 0.046003182130914644f, -0.998941293186856870f, 0.045236990298804750f, - -0.998976283356469820f, - 0.044470771854938744f, -0.999010685854073380f, 0.043704527250063421f, - -0.999044500659429290f, - 0.042938256934940959f, -0.999077727752645360f, 0.042171961360348002f, - -0.999110367114174890f, - 0.041405640977076712f, -0.999142418724816910f, 0.040639296235933854f, - -0.999173882565716380f, - 0.039872927587739845f, -0.999204758618363890f, 0.039106535483329839f, - -0.999235046864595850f, - 0.038340120373552791f, -0.999264747286594420f, 0.037573682709270514f, - -0.999293859866887790f, - 0.036807222941358991f, -0.999322384588349540f, 0.036040741520706299f, - -0.999350321434199440f, - 0.035274238898213947f, -0.999377670388002850f, 0.034507715524795889f, - -0.999404431433671300f, - 0.033741171851377642f, -0.999430604555461730f, 0.032974608328897315f, - -0.999456189737977340f, - 0.032208025408304704f, -0.999481186966166950f, 0.031441423540560343f, - -0.999505596225325310f, - 0.030674803176636581f, -0.999529417501093140f, 0.029908164767516655f, - -0.999552650779456990f, - 0.029141508764193740f, -0.999575296046749220f, 0.028374835617672258f, - -0.999597353289648380f, - 0.027608145778965820f, -0.999618822495178640f, 0.026841439699098527f, - -0.999639703650710200f, - 0.026074717829104040f, -0.999659996743959220f, 0.025307980620024630f, - -0.999679701762987930f, - 0.024541228522912264f, -0.999698818696204250f, 0.023774461988827676f, - -0.999717347532362190f, - 0.023007681468839410f, -0.999735288260561680f, 0.022240887414024919f, - -0.999752640870248840f, - 0.021474080275469605f, -0.999769405351215280f, 0.020707260504265912f, - -0.999785581693599210f, - 0.019940428551514598f, -0.999801169887884260f, 0.019173584868322699f, - -0.999816169924900410f, - 0.018406729905804820f, -0.999830581795823400f, 0.017639864115082195f, - -0.999844405492175240f, - 0.016872987947281773f, -0.999857641005823860f, 0.016106101853537263f, - -0.999870288328982950f, - 0.015339206284988220f, -0.999882347454212560f, 0.014572301692779104f, - -0.999893818374418490f, - 0.013805388528060349f, -0.999904701082852900f, 0.013038467241987433f, - -0.999914995573113470f, - 0.012271538285719944f, -0.999924701839144500f, 0.011504602110422875f, - -0.999933819875236000f, - 0.010737659167264572f, -0.999942349676023910f, 0.009970709907418029f, - -0.999950291236490480f, - 0.009203754782059960f, -0.999957644551963900f, 0.008436794242369860f, - -0.999964409618118280f, - 0.007669828739531077f, -0.999970586430974140f, 0.006902858724729877f, - -0.999976174986897610f, - 0.006135884649154515f, -0.999981175282601110f, 0.005368906963996303f, - -0.999985587315143200f, - 0.004601926120448672f, -0.999989411081928400f, 0.003834942569706248f, - -0.999992646580707190f, - 0.003067956762966138f, -0.999995293809576190f, 0.002300969151425887f, - -0.999997352766978210f, - 0.001533980186284766f, -0.999998823451701880f, 0.000766990318742846f, - -0.999999705862882230f -}; - -static const float32_t Weights_8192[16384] = { - 1.000000000000000000, -0.000000000000000000, 0.999999981616429330, - -0.000191747597310703, - 0.999999926465717890, -0.000383495187571396, 0.999999834547867670, - -0.000575242763732066, - 0.999999705862882230, -0.000766990318742704, 0.999999540410766110, - -0.000958737845553301, - 0.999999338191525530, -0.001150485337113849, 0.999999099205167830, - -0.001342232786374338, - 0.999998823451701880, -0.001533980186284766, 0.999998510931137790, - -0.001725727529795126, - 0.999998161643486980, -0.001917474809855419, 0.999997775588762350, - -0.002109222019415644, - 0.999997352766978210, -0.002300969151425805, 0.999996893178149880, - -0.002492716198835908, - 0.999996396822294350, -0.002684463154595962, 0.999995863699429940, - -0.002876210011655979, - 0.999995293809576190, -0.003067956762965976, 0.999994687152754080, - -0.003259703401475973, - 0.999994043728985820, -0.003451449920135994, 0.999993363538295150, - -0.003643196311896068, - 0.999992646580707190, -0.003834942569706228, 0.999991892856248010, - -0.004026688686516512, - 0.999991102364945590, -0.004218434655276963, 0.999990275106828920, - -0.004410180468937631, - 0.999989411081928400, -0.004601926120448571, 0.999988510290275690, - -0.004793671602759841, - 0.999987572731904080, -0.004985416908821511, 0.999986598406848000, - -0.005177162031583651, - 0.999985587315143200, -0.005368906963996343, 0.999984539456826970, - -0.005560651699009674, - 0.999983454831937730, -0.005752396229573736, 0.999982333440515350, - -0.005944140548638633, - 0.999981175282601110, -0.006135884649154475, 0.999979980358237650, - -0.006327628524071378, - 0.999978748667468830, -0.006519372166339468, 0.999977480210339940, - -0.006711115568908879, - 0.999976174986897610, -0.006902858724729756, 0.999974832997189810, - -0.007094601626752250, - 0.999973454241265940, -0.007286344267926521, 0.999972038719176730, - -0.007478086641202744, - 0.999970586430974140, -0.007669828739531097, 0.999969097376711580, - -0.007861570555861772, - 0.999967571556443780, -0.008053312083144972, 0.999966008970226920, - -0.008245053314330906, - 0.999964409618118280, -0.008436794242369799, 0.999962773500176930, - -0.008628534860211886, - 0.999961100616462820, -0.008820275160807412, 0.999959390967037450, - -0.009012015137106633, - 0.999957644551963900, -0.009203754782059819, 0.999955861371306100, - -0.009395494088617252, - 0.999954041425129780, -0.009587233049729225, 0.999952184713501780, - -0.009778971658346044, - 0.999950291236490480, -0.009970709907418031, 0.999948360994165400, - -0.010162447789895513, - 0.999946393986597460, -0.010354185298728842, 0.999944390213859060, - -0.010545922426868378, - 0.999942349676023910, -0.010737659167264491, 0.999940272373166960, - -0.010929395512867571, - 0.999938158305364590, -0.011121131456628021, 0.999936007472694620, - -0.011312866991496258, - 0.999933819875236000, -0.011504602110422714, 0.999931595513069200, - -0.011696336806357838, - 0.999929334386276070, -0.011888071072252092, 0.999927036494939640, - -0.012079804901055957, - 0.999924701839144500, -0.012271538285719925, 0.999922330418976490, - -0.012463271219194511, - 0.999919922234522750, -0.012655003694430242, 0.999917477285871770, - -0.012846735704377662, - 0.999914995573113470, -0.013038467241987334, 0.999912477096339240, - -0.013230198300209835, - 0.999909921855641540, -0.013421928871995765, 0.999907329851114300, - -0.013613658950295740, - 0.999904701082852900, -0.013805388528060391, 0.999902035550953920, - -0.013997117598240367, - 0.999899333255515390, -0.014188846153786345, 0.999896594196636680, - -0.014380574187649006, - 0.999893818374418490, -0.014572301692779064, 0.999891005788962950, - -0.014764028662127246, - 0.999888156440373320, -0.014955755088644296, 0.999885270328754520, - -0.015147480965280987, - 0.999882347454212560, -0.015339206284988100, 0.999879387816854930, - -0.015530931040716447, - 0.999876391416790410, -0.015722655225416857, 0.999873358254129260, - -0.015914378832040183, - 0.999870288328982950, -0.016106101853537287, 0.999867181641464380, - -0.016297824282859065, - 0.999864038191687680, -0.016489546112956437, 0.999860857979768540, - -0.016681267336780332, - 0.999857641005823860, -0.016872987947281710, 0.999854387269971890, - -0.017064707937411563, - 0.999851096772332190, -0.017256427300120877, 0.999847769513025900, - -0.017448146028360693, - 0.999844405492175240, -0.017639864115082053, 0.999841004709904000, - -0.017831581553236039, - 0.999837567166337090, -0.018023298335773746, 0.999834092861600960, - -0.018215014455646290, - 0.999830581795823400, -0.018406729905804820, 0.999827033969133420, - -0.018598444679200511, - 0.999823449381661570, -0.018790158768784555, 0.999819828033539420, - -0.018981872167508178, - 0.999816169924900410, -0.019173584868322623, 0.999812475055878780, - -0.019365296864179156, - 0.999808743426610520, -0.019557008148029083, 0.999804975037232870, - -0.019748718712823729, - 0.999801169887884260, -0.019940428551514441, 0.999797327978704690, - -0.020132137657052594, - 0.999793449309835270, -0.020323846022389593, 0.999789533881418780, - -0.020515553640476875, - 0.999785581693599210, -0.020707260504265895, 0.999781592746521670, - -0.020898966606708137, - 0.999777567040332940, -0.021090671940755121, 0.999773504575180990, - -0.021282376499358387, - 0.999769405351215280, -0.021474080275469508, 0.999765269368586450, - -0.021665783262040078, - 0.999761096627446610, -0.021857485452021735, 0.999756887127949080, - -0.022049186838366135, - 0.999752640870248840, -0.022240887414024961, 0.999748357854501780, - -0.022432587171949934, - 0.999744038080865430, -0.022624286105092803, 0.999739681549498660, - -0.022815984206405345, - 0.999735288260561680, -0.023007681468839369, 0.999730858214216030, - -0.023199377885346720, - 0.999726391410624470, -0.023391073448879258, 0.999721887849951310, - -0.023582768152388894, - 0.999717347532362190, -0.023774461988827555, 0.999712770458023870, - -0.023966154951147210, - 0.999708156627104880, -0.024157847032299864, 0.999703506039774650, - -0.024349538225237534, - 0.999698818696204250, -0.024541228522912288, 0.999694094596566000, - -0.024732917918276223, - 0.999689333741033640, -0.024924606404281468, 0.999684536129782140, - -0.025116293973880186, - 0.999679701762987930, -0.025307980620024571, 0.999674830640828740, - -0.025499666335666853, - 0.999669922763483760, -0.025691351113759295, 0.999664978131133310, - -0.025883034947254198, - 0.999659996743959220, -0.026074717829103901, 0.999654978602144690, - -0.026266399752260760, - 0.999649923705874240, -0.026458080709677187, 0.999644832055333610, - -0.026649760694305618, - 0.999639703650710200, -0.026841439699098531, 0.999634538492192300, - -0.027033117717008431, - 0.999629336579970110, -0.027224794740987875, 0.999624097914234570, - -0.027416470763989436, - 0.999618822495178640, -0.027608145778965740, 0.999613510322995950, - -0.027799819778869445, - 0.999608161397882110, -0.027991492756653243, 0.999602775720033530, - -0.028183164705269874, - 0.999597353289648380, -0.028374835617672099, 0.999591894106925950, - -0.028566505486812728, - 0.999586398172067070, -0.028758174305644615, 0.999580865485273700, - -0.028949842067120635, - 0.999575296046749220, -0.029141508764193722, 0.999569689856698580, - -0.029333174389816835, - 0.999564046915327740, -0.029524838936942976, 0.999558367222844300, - -0.029716502398525191, - 0.999552650779456990, -0.029908164767516555, 0.999546897585375960, - -0.030099826036870198, - 0.999541107640812940, -0.030291486199539284, 0.999535280945980540, - -0.030483145248477009, - 0.999529417501093140, -0.030674803176636626, 0.999523517306366350, - -0.030866459976971412, - 0.999517580362016990, -0.031058115642434700, 0.999511606668263440, - -0.031249770165979861, - 0.999505596225325310, -0.031441423540560301, 0.999499549033423640, - -0.031633075759129478, - 0.999493465092780590, -0.031824726814640887, 0.999487344403620080, - -0.032016376700048060, - 0.999481186966166950, -0.032208025408304586, 0.999474992780647780, - -0.032399672932364086, - 0.999468761847290050, -0.032591319265180226, 0.999462494166323160, - -0.032782964399706724, - 0.999456189737977340, -0.032974608328897335, 0.999449848562484530, - -0.033166251045705857, - 0.999443470640077770, -0.033357892543086139, 0.999437055970991530, - -0.033549532813992068, - 0.999430604555461730, -0.033741171851377580, 0.999424116393725640, - -0.033932809648196664, - 0.999417591486021720, -0.034124446197403326, 0.999411029832589780, - -0.034316081491951651, - 0.999404431433671300, -0.034507715524795750, 0.999397796289508640, - -0.034699348288889799, - 0.999391124400346050, -0.034890979777188004, 0.999384415766428560, - -0.035082609982644619, - 0.999377670388002850, -0.035274238898213947, 0.999370888265317170, - -0.035465866516850353, - 0.999364069398620550, -0.035657492831508222, 0.999357213788164000, - -0.035849117835142018, - 0.999350321434199440, -0.036040741520706229, 0.999343392336980220, - -0.036232363881155395, - 0.999336426496761240, -0.036423984909444110, 0.999329423913798420, - -0.036615604598527030, - 0.999322384588349540, -0.036807222941358832, 0.999315308520673070, - -0.036998839930894263, - 0.999308195711029470, -0.037190455560088119, 0.999301046159680070, - -0.037382069821895229, - 0.999293859866887790, -0.037573682709270494, 0.999286636832916740, - -0.037765294215168860, - 0.999279377058032710, -0.037956904332545310, 0.999272080542502610, - -0.038148513054354891, - 0.999264747286594420, -0.038340120373552694, 0.999257377290578060, - -0.038531726283093870, - 0.999249970554724420, -0.038723330775933623, 0.999242527079305830, - -0.038914933845027193, - 0.999235046864595850, -0.039106535483329888, 0.999227529910869610, - -0.039298135683797059, - 0.999219976218403530, -0.039489734439384118, 0.999212385787475290, - -0.039681331743046527, - 0.999204758618363890, -0.039872927587739811, 0.999197094711349880, - -0.040064521966419520, - 0.999189394066714920, -0.040256114872041282, 0.999181656684742350, - -0.040447706297560782, - 0.999173882565716380, -0.040639296235933736, 0.999166071709923000, - -0.040830884680115948, - 0.999158224117649430, -0.041022471623063238, 0.999150339789184110, - -0.041214057057731519, - 0.999142418724816910, -0.041405640977076739, 0.999134460924839150, - -0.041597223374054894, - 0.999126466389543390, -0.041788804241622061, 0.999118435119223490, - -0.041980383572734356, - 0.999110367114174890, -0.042171961360347947, 0.999102262374694130, - -0.042363537597419072, - 0.999094120901079070, -0.042555112276904020, 0.999085942693629270, - -0.042746685391759132, - 0.999077727752645360, -0.042938256934940820, 0.999069476078429330, - -0.043129826899405546, - 0.999061187671284600, -0.043321395278109825, 0.999052862531515930, - -0.043512962064010237, - 0.999044500659429290, -0.043704527250063421, 0.999036102055332330, - -0.043896090829226068, - 0.999027666719533690, -0.044087652794454944, 0.999019194652343460, - -0.044279213138706849, - 0.999010685854073380, -0.044470771854938668, 0.999002140325035980, - -0.044662328936107325, - 0.998993558065545680, -0.044853884375169815, 0.998984939075918010, - -0.045045438165083197, - 0.998976283356469820, -0.045236990298804590, 0.998967590907519300, - -0.045428540769291155, - 0.998958861729386080, -0.045620089569500144, 0.998950095822391250, - -0.045811636692388844, - 0.998941293186856870, -0.046003182130914623, 0.998932453823106690, - -0.046194725878034908, - 0.998923577731465780, -0.046386267926707157, 0.998914664912260440, - -0.046577808269888943, - 0.998905715365818290, -0.046769346900537863, 0.998896729092468410, - -0.046960883811611592, - 0.998887706092541290, -0.047152418996067869, 0.998878646366368690, - -0.047343952446864478, - 0.998869549914283560, -0.047535484156959303, 0.998860416736620520, - -0.047727014119310254, - 0.998851246833715180, -0.047918542326875327, 0.998842040205904840, - -0.048110068772612591, - 0.998832796853527990, -0.048301593449480144, 0.998823516776924490, - -0.048493116350436176, - 0.998814199976435390, -0.048684637468438943, 0.998804846452403420, - -0.048876156796446760, - 0.998795456205172410, -0.049067674327418015, 0.998786029235087640, - -0.049259190054311140, - 0.998776565542495610, -0.049450703970084664, 0.998767065127744380, - -0.049642216067697156, - 0.998757527991183340, -0.049833726340107277, 0.998747954133162860, - -0.050025234780273729, - 0.998738343554035230, -0.050216741381155311, 0.998728696254153720, - -0.050408246135710856, - 0.998719012233872940, -0.050599749036899282, 0.998709291493549030, - -0.050791250077679581, - 0.998699534033539280, -0.050982749251010803, 0.998689739854202620, - -0.051174246549852080, - 0.998679908955899090, -0.051365741967162593, 0.998670041338990070, - -0.051557235495901611, - 0.998660137003838490, -0.051748727129028456, 0.998650195950808280, - -0.051940216859502536, - 0.998640218180265270, -0.052131704680283324, 0.998630203692576050, - -0.052323190584330347, - 0.998620152488108870, -0.052514674564603223, 0.998610064567233340, - -0.052706156614061632, - 0.998599939930320370, -0.052897636725665324, 0.998589778577742230, - -0.053089114892374133, - 0.998579580509872500, -0.053280591107147945, 0.998569345727086110, - -0.053472065362946727, - 0.998559074229759310, -0.053663537652730520, 0.998548766018269920, - -0.053855007969459440, - 0.998538421092996730, -0.054046476306093660, 0.998528039454320230, - -0.054237942655593452, - 0.998517621102622210, -0.054429407010919133, 0.998507166038285490, - -0.054620869365031105, - 0.998496674261694640, -0.054812329710889854, 0.998486145773235360, - -0.055003788041455920, - 0.998475580573294770, -0.055195244349689934, 0.998464978662261250, - -0.055386698628552597, - 0.998454340040524800, -0.055578150871004678, 0.998443664708476340, - -0.055769601070007030, - 0.998432952666508440, -0.055961049218520569, 0.998422203915015020, - -0.056152495309506292, - 0.998411418454391300, -0.056343939335925290, 0.998400596285033640, - -0.056535381290738700, - 0.998389737407340160, -0.056726821166907748, 0.998378841821709990, - -0.056918258957393740, - 0.998367909528543820, -0.057109694655158062, 0.998356940528243420, - -0.057301128253162158, - 0.998345934821212370, -0.057492559744367566, 0.998334892407855000, - -0.057683989121735904, - 0.998323813288577560, -0.057875416378228857, 0.998312697463787260, - -0.058066841506808194, - 0.998301544933892890, -0.058258264500435752, 0.998290355699304350, - -0.058449685352073476, - 0.998279129760433200, -0.058641104054683341, 0.998267867117692110, - -0.058832520601227435, - 0.998256567771495180, -0.059023934984667931, 0.998245231722257880, - -0.059215347197967061, - 0.998233858970396850, -0.059406757234087150, 0.998222449516330550, - -0.059598165085990591, - 0.998211003360478190, -0.059789570746639868, 0.998199520503260660, - -0.059980974208997548, - 0.998188000945100300, -0.060172375466026259, 0.998176444686420530, - -0.060363774510688743, - 0.998164851727646240, -0.060555171335947788, 0.998153222069203760, - -0.060746565934766288, - 0.998141555711520520, -0.060937958300107203, 0.998129852655025630, - -0.061129348424933588, - 0.998118112900149180, -0.061320736302208578, 0.998106336447323050, - -0.061512121924895378, - 0.998094523296980010, -0.061703505285957298, 0.998082673449554590, - -0.061894886378357716, - 0.998070786905482340, -0.062086265195060088, 0.998058863665200250, - -0.062277641729027972, - 0.998046903729146840, -0.062469015973224996, 0.998034907097761770, - -0.062660387920614874, - 0.998022873771486240, -0.062851757564161406, 0.998010803750762450, - -0.063043124896828492, - 0.997998697036034390, -0.063234489911580066, 0.997986553627747020, - -0.063425852601380228, - 0.997974373526346990, -0.063617212959193106, 0.997962156732281950, - -0.063808570977982898, - 0.997949903246001190, -0.063999926650713940, 0.997937613067955250, - -0.064191279970350637, - 0.997925286198596000, -0.064382630929857465, 0.997912922638376610, - -0.064573979522198982, - 0.997900522387751620, -0.064765325740339885, 0.997888085447177110, - -0.064956669577244872, - 0.997875611817110150, -0.065148011025878833, 0.997863101498009500, - -0.065339350079206632, - 0.997850554490335110, -0.065530686730193327, 0.997837970794548280, - -0.065722020971803990, - 0.997825350411111640, -0.065913352797003805, 0.997812693340489280, - -0.066104682198758077, - 0.997799999583146470, -0.066296009170032130, 0.997787269139549960, - -0.066487333703791451, - 0.997774502010167820, -0.066678655793001557, 0.997761698195469560, - -0.066869975430628115, - 0.997748857695925690, -0.067061292609636822, 0.997735980512008620, - -0.067252607322993499, - 0.997723066644191640, -0.067443919563664051, 0.997710116092949570, - -0.067635229324614479, - 0.997697128858758500, -0.067826536598810869, 0.997684104942096030, - -0.068017841379219388, - 0.997671044343441000, -0.068209143658806329, 0.997657947063273710, - -0.068400443430538013, - 0.997644813102075420, -0.068591740687380942, 0.997631642460329320, - -0.068783035422301630, - 0.997618435138519550, -0.068974327628266746, 0.997605191137131640, - -0.069165617298242985, - 0.997591910456652630, -0.069356904425197208, 0.997578593097570800, - -0.069548189002096306, - 0.997565239060375750, -0.069739471021907307, 0.997551848345558430, - -0.069930750477597309, - 0.997538420953611340, -0.070122027362133521, 0.997524956885027960, - -0.070313301668483250, - 0.997511456140303450, -0.070504573389613856, 0.997497918719934210, - -0.070695842518492855, - 0.997484344624417930, -0.070887109048087801, 0.997470733854253670, - -0.071078372971366405, - 0.997457086409941910, -0.071269634281296401, 0.997443402291984360, - -0.071460892970845680, - 0.997429681500884180, -0.071652149032982212, 0.997415924037145960, - -0.071843402460674027, - 0.997402129901275300, -0.072034653246889332, 0.997388299093779460, - -0.072225901384596322, - 0.997374431615167150, -0.072417146866763413, 0.997360527465947940, - -0.072608389686358993, - 0.997346586646633230, -0.072799629836351673, 0.997332609157735470, - -0.072990867309710036, - 0.997318594999768600, -0.073182102099402888, 0.997304544173247990, - -0.073373334198399032, - 0.997290456678690210, -0.073564563599667426, 0.997276332516613180, - -0.073755790296177098, - 0.997262171687536170, -0.073947014280897200, 0.997247974191979860, - -0.074138235546796979, - 0.997233740030466280, -0.074329454086845756, 0.997219469203518670, - -0.074520669894013000, - 0.997205161711661850, -0.074711882961268211, 0.997190817555421940, - -0.074903093281581082, - 0.997176436735326190, -0.075094300847921305, 0.997162019251903290, - -0.075285505653258769, - 0.997147565105683480, -0.075476707690563388, 0.997133074297198110, - -0.075667906952805231, - 0.997118546826979980, -0.075859103432954447, 0.997103982695563330, - -0.076050297123981259, - 0.997089381903483400, -0.076241488018856066, 0.997074744451277310, - -0.076432676110549283, - 0.997060070339482960, -0.076623861392031492, 0.997045359568640040, - -0.076815043856273343, - 0.997030612139289450, -0.077006223496245640, 0.997015828051973310, - -0.077197400304919200, - 0.997001007307235290, -0.077388574275265049, 0.996986149905620180, - -0.077579745400254224, - 0.996971255847674320, -0.077770913672857947, 0.996956325133945280, - -0.077962079086047492, - 0.996941357764982160, -0.078153241632794232, 0.996926353741335090, - -0.078344401306069705, - 0.996911313063555740, -0.078535558098845479, 0.996896235732197210, - -0.078726712004093299, - 0.996881121747813850, -0.078917863014784942, 0.996865971110961310, - -0.079109011123892375, - 0.996850783822196610, -0.079300156324387597, 0.996835559882078170, - -0.079491298609242769, - 0.996820299291165670, -0.079682437971430126, 0.996805002050020430, - -0.079873574403921996, - 0.996789668159204560, -0.080064707899690890, 0.996774297619282050, - -0.080255838451709319, - 0.996758890430818000, -0.080446966052950014, 0.996743446594378860, - -0.080638090696385709, - 0.996727966110532490, -0.080829212374989329, 0.996712448979848010, - -0.081020331081733857, - 0.996696895202896060, -0.081211446809592441, 0.996681304780248300, - -0.081402559551538245, - 0.996665677712478160, -0.081593669300544652, 0.996650014000160070, - -0.081784776049585076, - 0.996634313643869900, -0.081975879791633066, 0.996618576644185070, - -0.082166980519662314, - 0.996602803001684130, -0.082358078226646536, 0.996586992716946950, - -0.082549172905559673, - 0.996571145790554840, -0.082740264549375692, 0.996555262223090540, - -0.082931353151068699, - 0.996539342015137940, -0.083122438703612911, 0.996523385167282450, - -0.083313521199982685, - 0.996507391680110820, -0.083504600633152432, 0.996491361554210920, - -0.083695676996096716, - 0.996475294790172160, -0.083886750281790226, 0.996459191388585410, - -0.084077820483207694, - 0.996443051350042630, -0.084268887593324071, 0.996426874675137240, - -0.084459951605114325, - 0.996410661364464100, -0.084651012511553617, 0.996394411418619290, - -0.084842070305617134, - 0.996378124838200210, -0.085033124980280275, 0.996361801623805720, - -0.085224176528518478, - 0.996345441776035900, -0.085415224943307333, 0.996329045295492380, - -0.085606270217622529, - 0.996312612182778000, -0.085797312344439894, 0.996296142438496850, - -0.085988351316735337, - 0.996279636063254650, -0.086179387127484894, 0.996263093057658140, - -0.086370419769664752, - 0.996246513422315520, -0.086561449236251170, 0.996229897157836500, - -0.086752475520220543, - 0.996213244264832040, -0.086943498614549378, 0.996196554743914220, - -0.087134518512214307, - 0.996179828595696980, -0.087325535206192059, 0.996163065820794950, - -0.087516548689459531, - 0.996146266419824620, -0.087707558954993659, 0.996129430393403740, - -0.087898565995771588, - 0.996112557742151130, -0.088089569804770507, 0.996095648466687300, - -0.088280570374967740, - 0.996078702567633980, -0.088471567699340767, 0.996061720045614000, - -0.088662561770867149, - 0.996044700901251970, -0.088853552582524600, 0.996027645135173610, - -0.089044540127290892, - 0.996010552748005870, -0.089235524398144014, 0.995993423740377360, - -0.089426505388061961, - 0.995976258112917790, -0.089617483090022959, 0.995959055866258320, - -0.089808457497005278, - 0.995941817001031350, -0.089999428601987341, 0.995924541517870800, - -0.090190396397947695, - 0.995907229417411720, -0.090381360877864983, 0.995889880700290720, - -0.090572322034717989, - 0.995872495367145730, -0.090763279861485621, 0.995855073418615790, - -0.090954234351146926, - 0.995837614855341610, -0.091145185496681005, 0.995820119677964910, - -0.091336133291067184, - 0.995802587887129160, -0.091527077727284828, 0.995785019483478750, - -0.091718018798313455, - 0.995767414467659820, -0.091908956497132724, 0.995749772840319510, - -0.092099890816722388, - 0.995732094602106430, -0.092290821750062355, 0.995714379753670610, - -0.092481749290132600, - 0.995696628295663520, -0.092672673429913310, 0.995678840228737540, - -0.092863594162384724, - 0.995661015553546910, -0.093054511480527249, 0.995643154270746900, - -0.093245425377321375, - 0.995625256380994310, -0.093436335845747787, 0.995607321884947050, - -0.093627242878787195, - 0.995589350783264600, -0.093818146469420549, 0.995571343076607770, - -0.094009046610628838, - 0.995553298765638470, -0.094199943295393204, 0.995535217851020390, - -0.094390836516694943, - 0.995517100333418110, -0.094581726267515445, 0.995498946213497770, - -0.094772612540836243, - 0.995480755491926940, -0.094963495329638992, 0.995462528169374420, - -0.095154374626905486, - 0.995444264246510340, -0.095345250425617617, 0.995425963724006160, - -0.095536122718757471, - 0.995407626602534900, -0.095726991499307162, 0.995389252882770690, - -0.095917856760249040, - 0.995370842565388990, -0.096108718494565509, 0.995352395651066810, - -0.096299576695239128, - 0.995333912140482280, -0.096490431355252593, 0.995315392034315070, - -0.096681282467588725, - 0.995296835333246090, -0.096872130025230471, 0.995278242037957670, - -0.097062974021160917, - 0.995259612149133390, -0.097253814448363271, 0.995240945667458130, - -0.097444651299820870, - 0.995222242593618360, -0.097635484568517200, 0.995203502928301510, - -0.097826314247435861, - 0.995184726672196930, -0.098017140329560604, 0.995165913825994620, - -0.098207962807875276, - 0.995147064390386470, -0.098398781675363881, 0.995128178366065490, - -0.098589596925010584, - 0.995109255753726110, -0.098780408549799623, 0.995090296554064000, - -0.098971216542715429, - 0.995071300767776170, -0.099162020896742503, 0.995052268395561050, - -0.099352821604865540, - 0.995033199438118630, -0.099543618660069319, 0.995014093896149700, - -0.099734412055338825, - 0.994994951770357020, -0.099925201783659073, 0.994975773061444140, - -0.100115987838015310, - 0.994956557770116380, -0.100306770211392860, 0.994937305897080070, - -0.100497548896777200, - 0.994918017443043200, -0.100688323887153960, 0.994898692408714870, - -0.100879095175508860, - 0.994879330794805620, -0.101069862754827820, 0.994859932602027320, - -0.101260626618096830, - 0.994840497831093180, -0.101451386758302080, 0.994821026482717860, - -0.101642143168429830, - 0.994801518557617110, -0.101832895841466530, 0.994781974056508260, - -0.102023644770398740, - 0.994762392980109930, -0.102214389948213210, 0.994742775329142010, - -0.102405131367896720, - 0.994723121104325700, -0.102595869022436280, 0.994703430306383860, - -0.102786602904819040, - 0.994683702936040250, -0.102977333008032220, 0.994663938994020390, - -0.103168059325063230, - 0.994644138481050710, -0.103358781848899610, 0.994624301397859400, - -0.103549500572529070, - 0.994604427745175660, -0.103740215488939370, 0.994584517523730340, - -0.103930926591118510, - 0.994564570734255420, -0.104121633872054590, 0.994544587377484300, - -0.104312337324735800, - 0.994524567454151740, -0.104503036942150570, 0.994504510964993700, - -0.104693732717287390, - 0.994484417910747600, -0.104884424643134970, 0.994464288292152390, - -0.105075112712682040, - 0.994444122109948040, -0.105265796918917600, 0.994423919364875950, - -0.105456477254830710, - 0.994403680057679100, -0.105647153713410620, 0.994383404189101430, - -0.105837826287646670, - 0.994363091759888570, -0.106028494970528410, 0.994342742770787270, - -0.106219159755045480, - 0.994322357222545810, -0.106409820634187680, 0.994301935115913580, - -0.106600477600944960, - 0.994281476451641550, -0.106791130648307390, 0.994260981230481790, - -0.106981779769265230, - 0.994240449453187900, -0.107172424956808840, 0.994219881120514960, - -0.107363066203928760, - 0.994199276233218910, -0.107553703503615620, 0.994178634792057590, - -0.107744336848860280, - 0.994157956797789730, -0.107934966232653650, 0.994137242251175720, - -0.108125591647986870, - 0.994116491152977070, -0.108316213087851170, 0.994095703503956930, - -0.108506830545237920, - 0.994074879304879370, -0.108697444013138720, 0.994054018556510210, - -0.108888053484545190, - 0.994033121259616400, -0.109078658952449240, 0.994012187414966220, - -0.109269260409842780, - 0.993991217023329380, -0.109459857849717980, 0.993970210085476920, - -0.109650451265067100, - 0.993949166602181130, -0.109841040648882600, 0.993928086574215830, - -0.110031625994157000, - 0.993906970002356060, -0.110222207293883060, 0.993885816887378090, - -0.110412784541053630, - 0.993864627230059750, -0.110603357728661730, 0.993843401031180180, - -0.110793926849700560, - 0.993822138291519660, -0.110984491897163390, 0.993800839011860120, - -0.111175052864043720, - 0.993779503192984580, -0.111365609743335160, 0.993758130835677430, - -0.111556162528031480, - 0.993736721940724600, -0.111746711211126590, 0.993715276508913230, - -0.111937255785614570, - 0.993693794541031790, -0.112127796244489640, 0.993672276037870010, - -0.112318332580746170, - 0.993650721000219120, -0.112508864787378690, 0.993629129428871720, - -0.112699392857381860, - 0.993607501324621610, -0.112889916783750520, 0.993585836688263950, - -0.113080436559479620, - 0.993564135520595300, -0.113270952177564350, 0.993542397822413600, - -0.113461463630999950, - 0.993520623594518090, -0.113651970912781870, 0.993498812837709360, - -0.113842474015905710, - 0.993476965552789190, -0.114032972933367200, 0.993455081740560960, - -0.114223467658162260, - 0.993433161401829360, -0.114413958183286920, 0.993411204537400060, - -0.114604444501737420, - 0.993389211148080650, -0.114794926606510080, 0.993367181234679600, - -0.114985404490601460, - 0.993345114798006910, -0.115175878147008190, 0.993323011838873950, - -0.115366347568727140, - 0.993300872358093280, -0.115556812748755260, 0.993278696356479030, - -0.115747273680089720, - 0.993256483834846440, -0.115937730355727780, 0.993234234794012290, - -0.116128182768666930, - 0.993211949234794500, -0.116318630911904750, 0.993189627158012620, - -0.116509074778439040, - 0.993167268564487230, -0.116699514361267690, 0.993144873455040430, - -0.116889949653388780, - 0.993122441830495580, -0.117080380647800590, 0.993099973691677570, - -0.117270807337501460, - 0.993077469039412300, -0.117461229715489990, 0.993054927874527320, - -0.117651647774764860, - 0.993032350197851410, -0.117842061508324980, 0.993009736010214580, - -0.118032470909169340, - 0.992987085312448390, -0.118222875970297170, 0.992964398105385610, - -0.118413276684707790, - 0.992941674389860470, -0.118603673045400720, 0.992918914166708300, - -0.118794065045375640, - 0.992896117436765980, -0.118984452677632340, 0.992873284200871730, - -0.119174835935170880, - 0.992850414459865100, -0.119365214810991350, 0.992827508214586760, - -0.119555589298094110, - 0.992804565465879140, -0.119745959389479600, 0.992781586214585570, - -0.119936325078148470, - 0.992758570461551140, -0.120126686357101500, 0.992735518207621850, - -0.120317043219339680, - 0.992712429453645460, -0.120507395657864130, 0.992689304200470750, - -0.120697743665676110, - 0.992666142448948020, -0.120888087235777080, 0.992642944199928820, - -0.121078426361168640, - 0.992619709454266140, -0.121268761034852600, 0.992596438212814290, - -0.121459091249830840, - 0.992573130476428810, -0.121649416999105530, 0.992549786245966680, - -0.121839738275678890, - 0.992526405522286100, -0.122030055072553360, 0.992502988306246950, - -0.122220367382731540, - 0.992479534598709970, -0.122410675199216200, 0.992456044400537700, - -0.122600978515010240, - 0.992432517712593660, -0.122791277323116770, 0.992408954535742850, - -0.122981571616539050, - 0.992385354870851670, -0.123171861388280480, 0.992361718718787870, - -0.123362146631344680, - 0.992338046080420420, -0.123552427338735370, 0.992314336956619640, - -0.123742703503456510, - 0.992290591348257370, -0.123932975118512160, 0.992266809256206580, - -0.124123242176906600, - 0.992242990681341700, -0.124313504671644230, 0.992219135624538450, - -0.124503762595729660, - 0.992195244086673920, -0.124694015942167640, 0.992171316068626520, - -0.124884264703963130, - 0.992147351571276090, -0.125074508874121170, 0.992123350595503720, - -0.125264748445647060, - 0.992099313142191800, -0.125454983411546230, 0.992075239212224070, - -0.125645213764824290, - 0.992051128806485720, -0.125835439498487000, 0.992026981925863360, - -0.126025660605540320, - 0.992002798571244520, -0.126215877078990350, 0.991978578743518580, - -0.126406088911843380, - 0.991954322443575950, -0.126596296097105850, 0.991930029672308480, - -0.126786498627784410, - 0.991905700430609330, -0.126976696496885870, 0.991881334719373010, - -0.127166889697417160, - 0.991856932539495470, -0.127357078222385400, 0.991832493891873780, - -0.127547262064797970, - 0.991808018777406430, -0.127737441217662310, 0.991783507196993490, - -0.127927615673986080, - 0.991758959151536110, -0.128117785426777130, 0.991734374641936810, - -0.128307950469043420, - 0.991709753669099530, -0.128498110793793170, 0.991685096233929420, - -0.128688266394034690, - 0.991660402337333210, -0.128878417262776550, 0.991635671980218740, - -0.129068563393027410, - 0.991610905163495370, -0.129258704777796140, 0.991586101888073500, - -0.129448841410091780, - 0.991561262154865290, -0.129638973282923560, 0.991536385964783880, - -0.129829100389300930, - 0.991511473318743900, -0.130019222722233350, 0.991486524217661480, - -0.130209340274730630, - 0.991461538662453790, -0.130399453039802690, 0.991436516654039420, - -0.130589561010459650, - 0.991411458193338540, -0.130779664179711710, 0.991386363281272280, - -0.130969762540569380, - 0.991361231918763460, -0.131159856086043270, 0.991336064106736140, - -0.131349944809144190, - 0.991310859846115440, -0.131540028702883120, 0.991285619137828200, - -0.131730107760271160, - 0.991260341982802440, -0.131920181974319790, 0.991235028381967420, - -0.132110251338040360, - 0.991209678336254060, -0.132300315844444650, 0.991184291846594180, - -0.132490375486544550, - 0.991158868913921350, -0.132680430257352070, 0.991133409539170170, - -0.132870480149879430, - 0.991107913723276890, -0.133060525157139060, 0.991082381467178640, - -0.133250565272143570, - 0.991056812771814340, -0.133440600487905680, 0.991031207638124130, - -0.133630630797438340, - 0.991005566067049370, -0.133820656193754720, 0.990979888059532740, - -0.134010676669868130, - 0.990954173616518500, -0.134200692218792020, 0.990928422738951990, - -0.134390702833540070, - 0.990902635427780010, -0.134580708507126170, 0.990876811683950700, - -0.134770709232564350, - 0.990850951508413620, -0.134960705002868750, 0.990825054902119470, - -0.135150695811053850, - 0.990799121866020370, -0.135340681650134210, 0.990773152401069780, - -0.135530662513124590, - 0.990747146508222710, -0.135720638393039910, 0.990721104188435180, - -0.135910609282895330, - 0.990695025442664630, -0.136100575175706200, 0.990668910271870100, - -0.136290536064487960, - 0.990642758677011570, -0.136480491942256280, 0.990616570659050620, - -0.136670442802027090, - 0.990590346218950150, -0.136860388636816380, 0.990564085357674370, - -0.137050329439640410, - 0.990537788076188750, -0.137240265203515590, 0.990511454375460290, - -0.137430195921458550, - 0.990485084256457090, -0.137620121586486040, 0.990458677720148620, - -0.137810042191615080, - 0.990432234767505970, -0.137999957729862790, 0.990405755399501260, - -0.138189868194246560, - 0.990379239617108160, -0.138379773577783890, 0.990352687421301450, - -0.138569673873492500, - 0.990326098813057330, -0.138759569074390350, 0.990299473793353590, - -0.138949459173495490, - 0.990272812363169110, -0.139139344163826200, 0.990246114523483990, - -0.139329224038400980, - 0.990219380275280000, -0.139519098790238490, 0.990192609619540030, - -0.139708968412357550, - 0.990165802557248400, -0.139898832897777210, 0.990138959089390650, - -0.140088692239516670, - 0.990112079216953770, -0.140278546430595420, 0.990085162940925970, - -0.140468395464033000, - 0.990058210262297120, -0.140658239332849210, 0.990031221182058000, - -0.140848078030064080, - 0.990004195701200910, -0.141037911548697710, 0.989977133820719610, - -0.141227739881770510, - 0.989950035541608990, -0.141417563022303020, 0.989922900864865450, - -0.141607380963316020, - 0.989895729791486660, -0.141797193697830390, 0.989868522322471580, - -0.141987001218867290, - 0.989841278458820530, -0.142176803519448030, 0.989813998201535260, - -0.142366600592594180, - 0.989786681551618640, -0.142556392431327340, 0.989759328510075200, - -0.142746179028669460, - 0.989731939077910570, -0.142935960377642670, 0.989704513256131850, - -0.143125736471269190, - 0.989677051045747210, -0.143315507302571500, 0.989649552447766530, - -0.143505272864572290, - 0.989622017463200890, -0.143695033150294470, 0.989594446093062460, - -0.143884788152760980, - 0.989566838338365120, -0.144074537864995160, 0.989539194200123930, - -0.144264282280020440, - 0.989511513679355190, -0.144454021390860470, 0.989483796777076760, - -0.144643755190539040, - 0.989456043494307710, -0.144833483672080210, 0.989428253832068230, - -0.145023206828508220, - 0.989400427791380380, -0.145212924652847460, 0.989372565373267010, - -0.145402637138122570, - 0.989344666578752640, -0.145592344277358340, 0.989316731408863000, - -0.145782046063579860, - 0.989288759864625170, -0.145971742489812210, 0.989260751947067640, - -0.146161433549080900, - 0.989232707657220050, -0.146351119234411460, 0.989204626996113780, - -0.146540799538829760, - 0.989176509964781010, -0.146730474455361750, 0.989148356564255590, - -0.146920143977033620, - 0.989120166795572690, -0.147109808096871820, 0.989091940659768800, - -0.147299466807902850, - 0.989063678157881540, -0.147489120103153570, 0.989035379290950310, - -0.147678767975650970, - 0.989007044060015270, -0.147868410418422220, 0.988978672466118480, - -0.148058047424494720, - 0.988950264510302990, -0.148247678986896030, 0.988921820193613190, - -0.148437305098653970, - 0.988893339517095130, -0.148626925752796540, 0.988864822481795640, - -0.148816540942351920, - 0.988836269088763540, -0.149006150660348450, 0.988807679339048450, - -0.149195754899814820, - 0.988779053233701520, -0.149385353653779720, 0.988750390773775360, - -0.149574946915272230, - 0.988721691960323780, -0.149764534677321510, 0.988692956794401940, - -0.149954116932956960, - 0.988664185277066230, -0.150143693675208190, 0.988635377409374790, - -0.150333264897105000, - 0.988606533192386450, -0.150522830591677400, 0.988577652627162020, - -0.150712390751955610, - 0.988548735714763200, -0.150901945370970040, 0.988519782456253270, - -0.151091494441751300, - 0.988490792852696590, -0.151281037957330220, 0.988461766905159300, - -0.151470575910737810, - 0.988432704614708340, -0.151660108295005310, 0.988403605982412390, - -0.151849635103164180, - 0.988374471009341280, -0.152039156328246050, 0.988345299696566150, - -0.152228671963282740, - 0.988316092045159690, -0.152418182001306330, 0.988286848056195820, - -0.152607686435349050, - 0.988257567730749460, -0.152797185258443440, 0.988228251069897420, - -0.152986678463622040, - 0.988198898074717610, -0.153176166043917840, 0.988169508746289060, - -0.153365647992363880, - 0.988140083085692570, -0.153555124301993450, 0.988110621094009820, - -0.153744594965840030, - 0.988081122772324070, -0.153934059976937350, 0.988051588121720110, - -0.154123519328319360, - 0.988022017143283530, -0.154312973013020100, 0.987992409838101880, - -0.154502421024073940, - 0.987962766207263420, -0.154691863354515430, 0.987933086251858380, - -0.154881299997379320, - 0.987903369972977790, -0.155070730945700510, 0.987873617371714200, - -0.155260156192514240, - 0.987843828449161740, -0.155449575730855850, 0.987814003206415550, - -0.155638989553760900, - 0.987784141644572180, -0.155828397654265230, 0.987754243764729530, - -0.156017800025404800, - 0.987724309567986960, -0.156207196660215900, 0.987694339055445130, - -0.156396587551734880, - 0.987664332228205710, -0.156585972692998430, 0.987634289087372160, - -0.156775352077043350, - 0.987604209634049160, -0.156964725696906780, 0.987574093869342360, - -0.157154093545625900, - 0.987543941794359230, -0.157343455616238250, 0.987513753410208420, - -0.157532811901781530, - 0.987483528717999710, -0.157722162395293630, 0.987453267718844560, - -0.157911507089812660, - 0.987422970413855410, -0.158100845978376980, 0.987392636804146240, - -0.158290179054025180, - 0.987362266890832400, -0.158479506309795960, 0.987331860675030430, - -0.158668827738728310, - 0.987301418157858430, -0.158858143333861450, 0.987270939340435420, - -0.159047453088234760, - 0.987240424223882250, -0.159236756994887850, 0.987209872809320820, - -0.159426055046860580, - 0.987179285097874340, -0.159615347237193060, 0.987148661090667570, - -0.159804633558925440, - 0.987118000788826280, -0.159993914005098270, 0.987087304193477900, - -0.160183188568752220, - 0.987056571305750970, -0.160372457242928280, 0.987025802126775600, - -0.160561720020667490, - 0.986994996657682980, -0.160750976895011220, 0.986964154899605650, - -0.160940227859001080, - 0.986933276853677710, -0.161129472905678810, 0.986902362521034470, - -0.161318712028086400, - 0.986871411902812470, -0.161507945219266120, 0.986840425000149680, - -0.161697172472260400, - 0.986809401814185530, -0.161886393780111830, 0.986778342346060430, - -0.162075609135863330, - 0.986747246596916590, -0.162264818532558000, 0.986716114567897100, - -0.162454021963239190, - 0.986684946260146690, -0.162643219420950310, 0.986653741674811350, - -0.162832410898735210, - 0.986622500813038480, -0.163021596389637840, 0.986591223675976400, - -0.163210775886702380, - 0.986559910264775410, -0.163399949382973230, 0.986528560580586690, - -0.163589116871495020, - 0.986497174624562880, -0.163778278345312670, 0.986465752397857940, - -0.163967433797471170, - 0.986434293901627180, -0.164156583221015810, 0.986402799137027220, - -0.164345726608992190, - 0.986371268105216030, -0.164534863954446000, 0.986339700807353000, - -0.164723995250423170, - 0.986308097244598670, -0.164913120489969890, 0.986276457418115090, - -0.165102239666132660, - 0.986244781329065460, -0.165291352771958000, 0.986213068978614490, - -0.165480459800492780, - 0.986181320367928270, -0.165669560744784120, 0.986149535498173860, - -0.165858655597879300, - 0.986117714370520090, -0.166047744352825790, 0.986085856986136820, - -0.166236827002671420, - 0.986053963346195440, -0.166425903540464100, 0.986022033451868560, - -0.166614973959252090, - 0.985990067304330140, -0.166804038252083730, 0.985958064904755460, - -0.166993096412007710, - 0.985926026254321130, -0.167182148432072940, 0.985893951354205210, - -0.167371194305328430, - 0.985861840205586980, -0.167560234024823560, 0.985829692809647050, - -0.167749267583607890, - 0.985797509167567480, -0.167938294974731170, 0.985765289280531310, - -0.168127316191243410, - 0.985733033149723490, -0.168316331226194830, 0.985700740776329850, - -0.168505340072635900, - 0.985668412161537550, -0.168694342723617330, 0.985636047306535420, - -0.168883339172189980, - 0.985603646212513400, -0.169072329411405010, 0.985571208880662740, - -0.169261313434313830, - 0.985538735312176060, -0.169450291233967960, 0.985506225508247290, - -0.169639262803419290, - 0.985473679470071810, -0.169828228135719850, 0.985441097198846210, - -0.170017187223921950, - 0.985408478695768420, -0.170206140061078070, 0.985375823962037710, - -0.170395086640240940, - 0.985343132998854790, -0.170584026954463590, 0.985310405807421570, - -0.170772960996799230, - 0.985277642388941220, -0.170961888760301220, 0.985244842744618540, - -0.171150810238023280, - 0.985212006875659350, -0.171339725423019310, 0.985179134783271130, - -0.171528634308343420, - 0.985146226468662230, -0.171717536887049970, 0.985113281933042710, - -0.171906433152193530, - 0.985080301177623800, -0.172095323096829010, 0.985047284203618200, - -0.172284206714011370, - 0.985014231012239840, -0.172473083996795950, 0.984981141604703960, - -0.172661954938238270, - 0.984948015982227030, -0.172850819531394080, 0.984914854146027200, - -0.173039677769319360, - 0.984881656097323700, -0.173228529645070320, 0.984848421837337010, - -0.173417375151703470, - 0.984815151367289140, -0.173606214282275410, 0.984781844688403350, - -0.173795047029843160, - 0.984748501801904210, -0.173983873387463820, 0.984715122709017620, - -0.174172693348194820, - 0.984681707410970940, -0.174361506905093750, 0.984648255908992630, - -0.174550314051218510, - 0.984614768204312600, -0.174739114779627200, 0.984581244298162180, - -0.174927909083378160, - 0.984547684191773960, -0.175116696955529920, 0.984514087886381840, - -0.175305478389141320, - 0.984480455383220930, -0.175494253377271430, 0.984446786683527920, - -0.175683021912979490, - 0.984413081788540700, -0.175871783989325040, 0.984379340699498510, - -0.176060539599367820, - 0.984345563417641900, -0.176249288736167880, 0.984311749944212780, - -0.176438031392785410, - 0.984277900280454370, -0.176626767562280880, 0.984244014427611110, - -0.176815497237715000, - 0.984210092386929030, -0.177004220412148750, 0.984176134159655320, - -0.177192937078643280, - 0.984142139747038570, -0.177381647230260040, 0.984108109150328540, - -0.177570350860060710, - 0.984074042370776450, -0.177759047961107170, 0.984039939409634970, - -0.177947738526461560, - 0.984005800268157870, -0.178136422549186300, 0.983971624947600270, - -0.178325100022344000, - 0.983937413449218920, -0.178513770938997510, 0.983903165774271500, - -0.178702435292209970, - 0.983868881924017220, -0.178891093075044720, 0.983834561899716630, - -0.179079744280565390, - 0.983800205702631600, -0.179268388901835750, 0.983765813334025240, - -0.179457026931919890, - 0.983731384795162090, -0.179645658363882160, 0.983696920087308140, - -0.179834283190787090, - 0.983662419211730250, -0.180022901405699510, 0.983627882169697210, - -0.180211513001684450, - 0.983593308962478650, -0.180400117971807240, 0.983558699591345900, - -0.180588716309133340, - 0.983524054057571260, -0.180777308006728590, 0.983489372362428730, - -0.180965893057658980, - 0.983454654507193270, -0.181154471454990810, 0.983419900493141540, - -0.181343043191790540, - 0.983385110321551180, -0.181531608261124970, 0.983350283993701500, - -0.181720166656061110, - 0.983315421510872810, -0.181908718369666160, 0.983280522874346970, - -0.182097263395007650, - 0.983245588085407070, -0.182285801725153300, 0.983210617145337640, - -0.182474333353171120, - 0.983175610055424420, -0.182662858272129270, 0.983140566816954500, - -0.182851376475096330, - 0.983105487431216290, -0.183039887955140950, 0.983070371899499640, - -0.183228392705332140, - 0.983035220223095640, -0.183416890718739100, 0.983000032403296590, - -0.183605381988431270, - 0.982964808441396440, -0.183793866507478450, 0.982929548338690170, - -0.183982344268950520, - 0.982894252096474070, -0.184170815265917720, 0.982858919716046110, - -0.184359279491450510, - 0.982823551198705240, -0.184547736938619620, 0.982788146545751970, - -0.184736187600495950, - 0.982752705758487830, -0.184924631470150790, 0.982717228838215990, - -0.185113068540655540, - 0.982681715786240860, -0.185301498805081900, 0.982646166603868050, - -0.185489922256501880, - 0.982610581292404750, -0.185678338887987630, 0.982574959853159240, - -0.185866748692611660, - 0.982539302287441240, -0.186055151663446630, 0.982503608596561830, - -0.186243547793565560, - 0.982467878781833170, -0.186431937076041610, 0.982432112844569110, - -0.186620319503948280, - 0.982396310786084690, -0.186808695070359270, 0.982360472607696210, - -0.186997063768348540, - 0.982324598310721280, -0.187185425590990330, 0.982288687896478830, - -0.187373780531359110, - 0.982252741366289370, -0.187562128582529600, 0.982216758721474510, - -0.187750469737576780, - 0.982180739963357090, -0.187938803989575910, 0.982144685093261580, - -0.188127131331602420, - 0.982108594112513610, -0.188315451756732120, 0.982072467022440000, - -0.188503765258040940, - 0.982036303824369020, -0.188692071828605230, 0.982000104519630490, - -0.188880371461501380, - 0.981963869109555240, -0.189068664149806190, 0.981927597595475540, - -0.189256949886596750, - 0.981891289978725100, -0.189445228664950230, 0.981854946260638630, - -0.189633500477944190, - 0.981818566442552500, -0.189821765318656410, 0.981782150525804310, - -0.190010023180164990, - 0.981745698511732990, -0.190198274055548150, 0.981709210401678800, - -0.190386517937884470, - 0.981672686196983110, -0.190574754820252740, 0.981636125898989080, - -0.190762984695732110, - 0.981599529509040720, -0.190951207557401800, 0.981562897028483650, - -0.191139423398341450, - 0.981526228458664770, -0.191327632211630900, 0.981489523800932130, - -0.191515833990350210, - 0.981452783056635520, -0.191704028727579800, 0.981416006227125550, - -0.191892216416400220, - 0.981379193313754560, -0.192080397049892440, 0.981342344317876040, - -0.192268570621137500, - 0.981305459240844670, -0.192456737123216840, 0.981268538084016710, - -0.192644896549212100, - 0.981231580848749730, -0.192833048892205230, 0.981194587536402320, - -0.193021194145278380, - 0.981157558148334830, -0.193209332301513960, 0.981120492685908730, - -0.193397463353994740, - 0.981083391150486710, -0.193585587295803610, 0.981046253543432780, - -0.193773704120023820, - 0.981009079866112630, -0.193961813819738840, 0.980971870119892840, - -0.194149916388032450, - 0.980934624306141640, -0.194338011817988600, 0.980897342426228390, - -0.194526100102691610, - 0.980860024481523870, -0.194714181235225960, 0.980822670473400100, - -0.194902255208676520, - 0.980785280403230430, -0.195090322016128250, 0.980747854272389750, - -0.195278381650666550, - 0.980710392082253970, -0.195466434105376980, 0.980672893834200530, - -0.195654479373345370, - 0.980635359529608120, -0.195842517447657850, 0.980597789169856850, - -0.196030548321400790, - 0.980560182756327840, -0.196218571987660880, 0.980522540290404090, - -0.196406588439524970, - 0.980484861773469380, -0.196594597670080220, 0.980447147206909060, - -0.196782599672414100, - 0.980409396592109910, -0.196970594439614340, 0.980371609930459800, - -0.197158581964768880, - 0.980333787223347960, -0.197346562240965920, 0.980295928472165290, - -0.197534535261294030, - 0.980258033678303550, -0.197722501018841920, 0.980220102843156080, - -0.197910459506698670, - 0.980182135968117430, -0.198098410717953560, 0.980144133054583590, - -0.198286354645696220, - 0.980106094103951770, -0.198474291283016390, 0.980068019117620650, - -0.198662220623004200, - 0.980029908096990090, -0.198850142658750090, 0.979991761043461200, - -0.199038057383344680, - 0.979953577958436740, -0.199225964789878830, 0.979915358843320480, - -0.199413864871443770, - 0.979877103699517640, -0.199601757621130970, 0.979838812528434740, - -0.199789643032032090, - 0.979800485331479790, -0.199977521097239150, 0.979762122110061750, - -0.200165391809844440, - 0.979723722865591170, -0.200353255162940450, 0.979685287599479930, - -0.200541111149619980, - 0.979646816313141210, -0.200728959762976140, 0.979608309007989450, - -0.200916800996102230, - 0.979569765685440520, -0.201104634842091900, 0.979531186346911500, - -0.201292461294039020, - 0.979492570993820810, -0.201480280345037730, 0.979453919627588210, - -0.201668091988182530, - 0.979415232249634780, -0.201855896216568050, 0.979376508861383170, - -0.202043693023289260, - 0.979337749464256780, -0.202231482401441450, 0.979298954059681040, - -0.202419264344120160, - 0.979260122649082020, -0.202607038844421130, 0.979221255233887700, - -0.202794805895440440, - 0.979182351815526930, -0.202982565490274440, 0.979143412395430230, - -0.203170317622019790, - 0.979104436975029250, -0.203358062283773320, 0.979065425555756930, - -0.203545799468632190, - 0.979026378139047580, -0.203733529169693920, 0.978987294726337050, - -0.203921251380056120, - 0.978948175319062200, -0.204108966092816870, 0.978909019918661310, - -0.204296673301074370, - 0.978869828526574120, -0.204484372997927240, 0.978830601144241470, - -0.204672065176474210, - 0.978791337773105670, -0.204859749829814420, 0.978752038414610340, - -0.205047426951047250, - 0.978712703070200420, -0.205235096533272350, 0.978673331741322210, - -0.205422758569589610, - 0.978633924429423210, -0.205610413053099240, 0.978594481135952270, - -0.205798059976901790, - 0.978555001862359550, -0.205985699334097910, 0.978515486610096910, - -0.206173331117788710, - 0.978475935380616830, -0.206360955321075510, 0.978436348175373730, - -0.206548571937059890, - 0.978396724995823090, -0.206736180958843690, 0.978357065843421640, - -0.206923782379529100, - 0.978317370719627650, -0.207111376192218560, 0.978277639625900530, - -0.207298962390014750, - 0.978237872563701090, -0.207486540966020650, 0.978198069534491400, - -0.207674111913339570, - 0.978158230539735050, -0.207861675225075070, 0.978118355580896660, - -0.208049230894330940, - 0.978078444659442380, -0.208236778914211330, 0.978038497776839600, - -0.208424319277820600, - 0.977998514934557140, -0.208611851978263490, 0.977958496134064830, - -0.208799377008644900, - 0.977918441376834370, -0.208986894362070070, 0.977878350664338150, - -0.209174404031644580, - 0.977838223998050430, -0.209361906010474160, 0.977798061379446360, - -0.209549400291664940, - 0.977757862810002760, -0.209736886868323290, 0.977717628291197460, - -0.209924365733555880, - 0.977677357824509930, -0.210111836880469610, 0.977637051411420770, - -0.210299300302171730, - 0.977596709053411890, -0.210486755991769720, 0.977556330751966460, - -0.210674203942371440, - 0.977515916508569280, -0.210861644147084860, 0.977475466324706170, - -0.211049076599018390, - 0.977434980201864260, -0.211236501291280710, 0.977394458141532250, - -0.211423918216980670, - 0.977353900145199960, -0.211611327369227550, 0.977313306214358750, - -0.211798728741130840, - 0.977272676350500860, -0.211986122325800330, 0.977232010555120320, - -0.212173508116346080, - 0.977191308829712280, -0.212360886105878420, 0.977150571175773200, - -0.212548256287508060, - 0.977109797594800880, -0.212735618654345930, 0.977068988088294450, - -0.212922973199503180, - 0.977028142657754390, -0.213110319916091360, 0.976987261304682390, - -0.213297658797222320, - 0.976946344030581670, -0.213484989836008050, 0.976905390836956490, - -0.213672313025560970, - 0.976864401725312640, -0.213859628358993750, 0.976823376697157240, - -0.214046935829419360, - 0.976782315753998650, -0.214234235429950990, 0.976741218897346550, - -0.214421527153702160, - 0.976700086128711840, -0.214608810993786760, 0.976658917449606980, - -0.214796086943318860, - 0.976617712861545640, -0.214983354995412820, 0.976576472366042610, - -0.215170615143183390, - 0.976535195964614470, -0.215357867379745550, 0.976493883658778650, - -0.215545111698214500, - 0.976452535450054060, -0.215732348091705880, 0.976411151339961040, - -0.215919576553335490, - 0.976369731330021140, -0.216106797076219520, 0.976328275421757260, - -0.216294009653474340, - 0.976286783616693630, -0.216481214278216730, 0.976245255916355800, - -0.216668410943563730, - 0.976203692322270560, -0.216855599642632620, 0.976162092835966110, - -0.217042780368540990, - 0.976120457458971910, -0.217229953114406790, 0.976078786192818850, - -0.217417117873348190, - 0.976037079039039020, -0.217604274638483640, 0.975995335999165990, - -0.217791423402931950, - 0.975953557074734300, -0.217978564159812200, 0.975911742267280170, - -0.218165696902243800, - 0.975869891578341030, -0.218352821623346320, 0.975828005009455660, - -0.218539938316239770, - 0.975786082562163930, -0.218727046974044440, 0.975744124238007270, - -0.218914147589880840, - 0.975702130038528570, -0.219101240156869800, 0.975660099965271590, - -0.219288324668132470, - 0.975618034019781750, -0.219475401116790310, 0.975575932203605720, - -0.219662469495965050, - 0.975533794518291360, -0.219849529798778700, 0.975491620965388110, - -0.220036582018353580, - 0.975449411546446380, -0.220223626147812380, 0.975407166263018270, - -0.220410662180277940, - 0.975364885116656980, -0.220597690108873510, 0.975322568108916930, - -0.220784709926722610, - 0.975280215241354220, -0.220971721626949110, 0.975237826515525820, - -0.221158725202677010, - 0.975195401932990370, -0.221345720647030810, 0.975152941495307620, - -0.221532707953135230, - 0.975110445204038890, -0.221719687114115220, 0.975067913060746470, - -0.221906658123096100, - 0.975025345066994120, -0.222093620973203510, 0.974982741224347140, - -0.222280575657563370, - 0.974940101534371830, -0.222467522169301880, 0.974897425998635820, - -0.222654460501545500, - 0.974854714618708430, -0.222841390647421120, 0.974811967396159830, - -0.223028312600055820, - 0.974769184332561770, -0.223215226352576980, 0.974726365429487320, - -0.223402131898112370, - 0.974683510688510670, -0.223589029229789990, 0.974640620111207560, - -0.223775918340738150, - 0.974597693699155050, -0.223962799224085460, 0.974554731453931230, - -0.224149671872960870, - 0.974511733377115720, -0.224336536280493600, 0.974468699470289580, - -0.224523392439813170, - 0.974425629735034990, -0.224710240344049430, 0.974382524172935470, - -0.224897079986332490, - 0.974339382785575860, -0.225083911359792830, 0.974296205574542440, - -0.225270734457561160, - 0.974252992541422500, -0.225457549272768540, 0.974209743687805220, - -0.225644355798546330, - 0.974166459015280320, -0.225831154028026170, 0.974123138525439640, - -0.226017943954340020, - 0.974079782219875680, -0.226204725570620190, 0.974036390100182610, - -0.226391498869999240, - 0.973992962167955830, -0.226578263845610000, 0.973949498424792170, - -0.226765020490585690, - 0.973905998872289570, -0.226951768798059810, 0.973862463512047300, - -0.227138508761166170, - 0.973818892345666100, -0.227325240373038860, 0.973775285374748110, - -0.227511963626812280, - 0.973731642600896400, -0.227698678515621170, 0.973687964025715670, - -0.227885385032600530, - 0.973644249650811980, -0.228072083170885730, 0.973600499477792370, - -0.228258772923612380, - 0.973556713508265560, -0.228445454283916470, 0.973512891743841370, - -0.228632127244934230, - 0.973469034186131070, -0.228818791799802220, 0.973425140836747030, - -0.229005447941657340, - 0.973381211697303290, -0.229192095663636770, 0.973337246769414910, - -0.229378734958878010, - 0.973293246054698250, -0.229565365820518870, 0.973249209554771230, - -0.229751988241697490, - 0.973205137271252800, -0.229938602215552210, 0.973161029205763530, - -0.230125207735221850, - 0.973116885359925130, -0.230311804793845440, 0.973072705735360530, - -0.230498393384562350, - 0.973028490333694210, -0.230684973500512200, 0.972984239156551740, - -0.230871545134835020, - 0.972939952205560180, -0.231058108280671110, 0.972895629482347760, - -0.231244662931161050, - 0.972851270988544180, -0.231431209079445750, 0.972806876725780370, - -0.231617746718666470, - 0.972762446695688570, -0.231804275841964780, 0.972717980899902250, - -0.231990796442482440, - 0.972673479340056430, -0.232177308513361710, 0.972628942017787270, - -0.232363812047745030, - 0.972584368934732210, -0.232550307038775240, 0.972539760092530180, - -0.232736793479595390, - 0.972495115492821190, -0.232923271363348980, 0.972450435137246830, - -0.233109740683179690, - 0.972405719027449770, -0.233296201432231590, 0.972360967165074140, - -0.233482653603649090, - 0.972316179551765300, -0.233669097190576820, 0.972271356189170040, - -0.233855532186159840, - 0.972226497078936270, -0.234041958583543430, 0.972181602222713440, - -0.234228376375873210, - 0.972136671622152230, -0.234414785556295160, 0.972091705278904430, - -0.234601186117955550, - 0.972046703194623500, -0.234787578054000970, 0.972001665370963890, - -0.234973961357578250, - 0.971956591809581720, -0.235160336021834730, 0.971911482512134000, - -0.235346702039917840, - 0.971866337480279400, -0.235533059404975490, 0.971821156715677700, - -0.235719408110155820, - 0.971775940219990140, -0.235905748148607370, 0.971730687994879160, - -0.236092079513478910, - 0.971685400042008540, -0.236278402197919570, 0.971640076363043390, - -0.236464716195078780, - 0.971594716959650160, -0.236651021498106380, 0.971549321833496630, - -0.236837318100152380, - 0.971503890986251780, -0.237023605994367200, 0.971458424419585960, - -0.237209885173901600, - 0.971412922135170940, -0.237396155631906610, 0.971367384134679490, - -0.237582417361533570, - 0.971321810419786160, -0.237768670355934190, 0.971276200992166490, - -0.237954914608260540, - 0.971230555853497380, -0.238141150111664840, 0.971184875005457030, - -0.238327376859299810, - 0.971139158449725090, -0.238513594844318420, 0.971093406187982460, - -0.238699804059873980, - 0.971047618221911100, -0.238886004499120040, 0.971001794553194690, - -0.239072196155210610, - 0.970955935183517970, -0.239258379021299980, 0.970910040114567050, - -0.239444553090542630, - 0.970864109348029470, -0.239630718356093560, 0.970818142885593870, - -0.239816874811108000, - 0.970772140728950350, -0.240003022448741500, 0.970726102879790110, - -0.240189161262149900, - 0.970680029339806130, -0.240375291244489450, 0.970633920110692160, - -0.240561412388916650, - 0.970587775194143630, -0.240747524688588430, 0.970541594591857070, - -0.240933628136661910, - 0.970495378305530560, -0.241119722726294590, 0.970449126336863090, - -0.241305808450644370, - 0.970402838687555500, -0.241491885302869330, 0.970356515359309450, - -0.241677953276128010, - 0.970310156353828110, -0.241864012363579180, 0.970263761672816140, - -0.242050062558382070, - 0.970217331317979160, -0.242236103853696010, 0.970170865291024480, - -0.242422136242680890, - 0.970124363593660280, -0.242608159718496810, 0.970077826227596420, - -0.242794174274304220, - 0.970031253194543970, -0.242980179903263870, 0.969984644496215240, - -0.243166176598536900, - 0.969938000134323960, -0.243352164353284740, 0.969891320110585100, - -0.243538143160669130, - 0.969844604426714830, -0.243724113013852160, 0.969797853084430890, - -0.243910073905996260, - 0.969751066085452140, -0.244096025830264210, 0.969704243431498860, - -0.244281968779819030, - 0.969657385124292450, -0.244467902747824150, 0.969610491165555870, - -0.244653827727443320, - 0.969563561557013180, -0.244839743711840670, 0.969516596300390000, - -0.245025650694180470, - 0.969469595397413060, -0.245211548667627540, 0.969422558849810320, - -0.245397437625346960, - 0.969375486659311280, -0.245583317560504060, 0.969328378827646660, - -0.245769188466264580, - 0.969281235356548530, -0.245955050335794590, 0.969234056247750050, - -0.246140903162260530, - 0.969186841502985950, -0.246326746938829030, 0.969139591123992280, - -0.246512581658667210, - 0.969092305112506210, -0.246698407314942410, 0.969044983470266240, - -0.246884223900822430, - 0.968997626199012420, -0.247070031409475250, 0.968950233300485800, - -0.247255829834069300, - 0.968902804776428870, -0.247441619167773270, 0.968855340628585580, - -0.247627399403756280, - 0.968807840858700970, -0.247813170535187670, 0.968760305468521430, - -0.247998932555237110, - 0.968712734459794780, -0.248184685457074780, 0.968665127834270060, - -0.248370429233870980, - 0.968617485593697540, -0.248556163878796560, 0.968569807739828930, - -0.248741889385022480, - 0.968522094274417380, -0.248927605745720150, 0.968474345199216820, - -0.249113312954061360, - 0.968426560515983190, -0.249299011003218190, 0.968378740226473300, - -0.249484699886362960, - 0.968330884332445190, -0.249670379596668550, 0.968282992835658660, - -0.249856050127307990, - 0.968235065737874320, -0.250041711471454650, 0.968187103040854420, - -0.250227363622282370, - 0.968139104746362440, -0.250413006572965220, 0.968091070856162970, - -0.250598640316677670, - 0.968043001372022260, -0.250784264846594500, 0.967994896295707670, - -0.250969880155890720, - 0.967946755628987800, -0.251155486237741920, 0.967898579373632660, - -0.251341083085323880, - 0.967850367531413620, -0.251526670691812610, 0.967802120104103270, - -0.251712249050384700, - 0.967753837093475510, -0.251897818154216970, 0.967705518501305480, - -0.252083377996486450, - 0.967657164329369880, -0.252268928570370810, 0.967608774579446500, - -0.252454469869047740, - 0.967560349253314360, -0.252640001885695520, 0.967511888352754150, - -0.252825524613492610, - 0.967463391879547550, -0.253011038045617860, 0.967414859835477480, - -0.253196542175250560, - 0.967366292222328510, -0.253382036995570160, 0.967317689041886310, - -0.253567522499756560, - 0.967269050295937790, -0.253752998680989990, 0.967220375986271420, - -0.253938465532451090, - 0.967171666114676640, -0.254123923047320620, 0.967122920682944360, - -0.254309371218780000, - 0.967074139692867040, -0.254494810040010730, 0.967025323146238010, - -0.254680239504194830, - 0.966976471044852070, -0.254865659604514570, 0.966927583390505660, - -0.255051070334152470, - 0.966878660184995910, -0.255236471686291710, 0.966829701430121810, - -0.255421863654115460, - 0.966780707127683270, -0.255607246230807380, 0.966731677279481840, - -0.255792619409551610, - 0.966682611887320080, -0.255977983183532430, 0.966633510953002100, - -0.256163337545934460, - 0.966584374478333120, -0.256348682489942910, 0.966535202465119700, - -0.256534018008743040, - 0.966485994915169840, -0.256719344095520660, 0.966436751830292650, - -0.256904660743461910, - 0.966387473212298900, -0.257089967945753120, 0.966338159063000130, - -0.257275265695581120, - 0.966288809384209690, -0.257460553986133100, 0.966239424177741890, - -0.257645832810596390, - 0.966190003445412500, -0.257831102162158990, 0.966140547189038750, - -0.258016362034009020, - 0.966091055410438830, -0.258201612419334870, 0.966041528111432400, - -0.258386853311325600, - 0.965991965293840570, -0.258572084703170340, 0.965942366959485540, - -0.258757306588058680, - 0.965892733110190860, -0.258942518959180520, 0.965843063747781510, - -0.259127721809726150, - 0.965793358874083680, -0.259312915132886230, 0.965743618490924830, - -0.259498098921851660, - 0.965693842600133690, -0.259683273169813770, 0.965644031203540590, - -0.259868437869964270, - 0.965594184302976830, -0.260053593015495190, 0.965544301900275180, - -0.260238738599598840, - 0.965494383997269500, -0.260423874615468010, 0.965444430595795430, - -0.260609001056295750, - 0.965394441697689400, -0.260794117915275510, 0.965344417304789370, - -0.260979225185601070, - 0.965294357418934660, -0.261164322860466480, 0.965244262041965780, - -0.261349410933066350, - 0.965194131175724720, -0.261534489396595520, 0.965143964822054450, - -0.261719558244249030, - 0.965093762982799590, -0.261904617469222610, 0.965043525659805890, - -0.262089667064712040, - 0.964993252854920320, -0.262274707023913590, 0.964942944569991410, - -0.262459737340023980, - 0.964892600806868890, -0.262644758006240040, 0.964842221567403620, - -0.262829769015759160, - 0.964791806853447900, -0.263014770361779000, 0.964741356666855340, - -0.263199762037497560, - 0.964690871009481030, -0.263384744036113280, 0.964640349883180930, - -0.263569716350824880, - 0.964589793289812760, -0.263754678974831350, 0.964539201231235150, - -0.263939631901332350, - 0.964488573709308410, -0.264124575123527550, 0.964437910725893910, - -0.264309508634617110, - 0.964387212282854290, -0.264494432427801630, 0.964336478382053720, - -0.264679346496281890, - 0.964285709025357480, -0.264864250833259260, 0.964234904214632200, - -0.265049145431935250, - 0.964184063951745830, -0.265234030285511790, 0.964133188238567640, - -0.265418905387191260, - 0.964082277076968140, -0.265603770730176330, 0.964031330468819280, - -0.265788626307669920, - 0.963980348415994110, -0.265973472112875590, 0.963929330920367140, - -0.266158308138996990, - 0.963878277983814200, -0.266343134379238180, 0.963827189608212340, - -0.266527950826803690, - 0.963776065795439840, -0.266712757474898370, 0.963724906547376530, - -0.266897554316727350, - 0.963673711865903230, -0.267082341345496300, 0.963622481752902220, - -0.267267118554410930, - 0.963571216210257320, -0.267451885936677620, 0.963519915239853140, - -0.267636643485503090, - 0.963468578843575950, -0.267821391194094150, 0.963417207023313350, - -0.268006129055658290, - 0.963365799780954050, -0.268190857063403180, 0.963314357118388200, - -0.268375575210536900, - 0.963262879037507070, -0.268560283490267890, 0.963211365540203480, - -0.268744981895804980, - 0.963159816628371360, -0.268929670420357260, 0.963108232303906190, - -0.269114349057134380, - 0.963056612568704340, -0.269299017799346120, 0.963004957424663850, - -0.269483676640202840, - 0.962953266873683880, -0.269668325572915090, 0.962901540917665000, - -0.269852964590693860, - 0.962849779558509030, -0.270037593686750570, 0.962797982798119010, - -0.270222212854296870, - 0.962746150638399410, -0.270406822086544820, 0.962694283081255930, - -0.270591421376706940, - 0.962642380128595710, -0.270776010717996010, 0.962590441782326890, - -0.270960590103625170, - 0.962538468044359160, -0.271145159526808010, 0.962486458916603450, - -0.271329718980758420, - 0.962434414400972100, -0.271514268458690700, 0.962382334499378380, - -0.271698807953819510, - 0.962330219213737400, -0.271883337459359720, 0.962278068545965090, - -0.272067856968526920, - 0.962225882497979020, -0.272252366474536710, 0.962173661071697880, - -0.272436865970605240, - 0.962121404269041580, -0.272621355449948980, 0.962069112091931580, - -0.272805834905784810, - 0.962016784542290560, -0.272990304331329920, 0.961964421622042320, - -0.273174763719801930, - 0.961912023333112210, -0.273359213064418680, 0.961859589677426570, - -0.273543652358398730, - 0.961807120656913540, -0.273728081594960540, 0.961754616273502010, - -0.273912500767323260, - 0.961702076529122540, -0.274096909868706380, 0.961649501425706820, - -0.274281308892329660, - 0.961596890965187860, -0.274465697831413220, 0.961544245149499990, - -0.274650076679177680, - 0.961491563980579000, -0.274834445428843940, 0.961438847460361680, - -0.275018804073633220, - 0.961386095590786250, -0.275203152606767310, 0.961333308373792270, - -0.275387491021468140, - 0.961280485811320640, -0.275571819310958140, 0.961227627905313460, - -0.275756137468460120, - 0.961174734657714080, -0.275940445487197150, 0.961121806070467380, - -0.276124743360392830, - 0.961068842145519350, -0.276309031081271080, 0.961015842884817230, - -0.276493308643055990, - 0.960962808290309780, -0.276677576038972420, 0.960909738363946770, - -0.276861833262245280, - 0.960856633107679660, -0.277046080306099900, 0.960803492523460760, - -0.277230317163762170, - 0.960750316613243950, -0.277414543828458090, 0.960697105378984450, - -0.277598760293414290, - 0.960643858822638590, -0.277782966551857690, 0.960590576946164120, - -0.277967162597015370, - 0.960537259751520050, -0.278151348422115090, 0.960483907240666790, - -0.278335524020384920, - 0.960430519415565790, -0.278519689385053060, 0.960377096278180130, - -0.278703844509348490, - 0.960323637830473920, -0.278887989386500280, 0.960270144074412800, - -0.279072124009737800, - 0.960216615011963430, -0.279256248372291180, 0.960163050645094000, - -0.279440362467390510, - 0.960109450975773940, -0.279624466288266590, 0.960055816005973890, - -0.279808559828150390, - 0.960002145737665960, -0.279992643080273220, 0.959948440172823210, - -0.280176716037866980, - 0.959894699313420530, -0.280360778694163810, 0.959840923161433770, - -0.280544831042396250, - 0.959787111718839900, -0.280728873075797190, 0.959733264987617680, - -0.280912904787600000, - 0.959679382969746750, -0.281096926171038260, 0.959625465667208190, - -0.281280937219346110, - 0.959571513081984520, -0.281464937925757940, 0.959517525216059260, - -0.281648928283508630, - 0.959463502071417510, -0.281832908285833350, 0.959409443650045550, - -0.282016877925967640, - 0.959355349953930790, -0.282200837197147560, 0.959301220985062210, - -0.282384786092609360, - 0.959247056745430090, -0.282568724605589740, 0.959192857237025740, - -0.282752652729325930, - 0.959138622461841890, -0.282936570457055390, 0.959084352421872730, - -0.283120477782015820, - 0.959030047119113660, -0.283304374697445740, 0.958975706555561080, - -0.283488261196583550, - 0.958921330733213170, -0.283672137272668430, 0.958866919654069010, - -0.283856002918939750, - 0.958812473320129310, -0.284039858128637190, 0.958757991733395710, - -0.284223702895001040, - 0.958703474895871600, -0.284407537211271880, 0.958648922809561150, - -0.284591361070690440, - 0.958594335476470220, -0.284775174466498300, 0.958539712898605730, - -0.284958977391937040, - 0.958485055077976100, -0.285142769840248670, 0.958430362016590930, - -0.285326551804675870, - 0.958375633716461170, -0.285510323278461260, 0.958320870179598880, - -0.285694084254848320, - 0.958266071408017670, -0.285877834727080620, 0.958211237403732260, - -0.286061574688402040, - 0.958156368168758820, -0.286245304132057120, 0.958101463705114730, - -0.286429023051290700, - 0.958046524014818600, -0.286612731439347790, 0.957991549099890370, - -0.286796429289474080, - 0.957936538962351420, -0.286980116594915570, 0.957881493604224370, - -0.287163793348918390, - 0.957826413027532910, -0.287347459544729510, 0.957771297234302320, - -0.287531115175595930, - 0.957716146226558870, -0.287714760234765170, 0.957660960006330610, - -0.287898394715485170, - 0.957605738575646350, -0.288082018611004130, 0.957550481936536470, - -0.288265631914570770, - 0.957495190091032570, -0.288449234619434220, 0.957439863041167680, - -0.288632826718843830, - 0.957384500788975860, -0.288816408206049480, 0.957329103336492790, - -0.288999979074301420, - 0.957273670685755200, -0.289183539316850200, 0.957218202838801210, - -0.289367088926947010, - 0.957162699797670210, -0.289550627897843030, 0.957107161564402790, - -0.289734156222790250, - 0.957051588141040970, -0.289917673895040750, 0.956995979529628230, - -0.290101180907847090, - 0.956940335732208820, -0.290284677254462330, 0.956884656750828900, - -0.290468162928139820, - 0.956828942587535370, -0.290651637922133220, 0.956773193244376930, - -0.290835102229696830, - 0.956717408723403050, -0.291018555844085090, 0.956661589026665090, - -0.291201998758552900, - 0.956605734156215080, -0.291385430966355660, 0.956549844114106820, - -0.291568852460749040, - 0.956493918902395100, -0.291752263234989260, 0.956437958523136180, - -0.291935663282332780, - 0.956381962978387730, -0.292119052596036380, 0.956325932270208230, - -0.292302431169357560, - 0.956269866400658030, -0.292485798995553880, 0.956213765371798470, - -0.292669156067883460, - 0.956157629185692140, -0.292852502379604810, 0.956101457844403040, - -0.293035837923976810, - 0.956045251349996410, -0.293219162694258630, 0.955989009704538930, - -0.293402476683710110, - 0.955932732910098280, -0.293585779885591200, 0.955876420968743590, - -0.293769072293162400, - 0.955820073882545420, -0.293952353899684660, 0.955763691653575440, - -0.294135624698419030, - 0.955707274283906560, -0.294318884682627400, 0.955650821775613330, - -0.294502133845571670, - 0.955594334130771110, -0.294685372180514330, 0.955537811351456880, - -0.294868599680718270, - 0.955481253439748770, -0.295051816339446720, 0.955424660397726330, - -0.295235022149963220, - 0.955368032227470350, -0.295418217105532010, 0.955311368931062720, - -0.295601401199417360, - 0.955254670510586990, -0.295784574424884260, 0.955197936968127710, - -0.295967736775197890, - 0.955141168305770780, -0.296150888243623790, 0.955084364525603410, - -0.296334028823428190, - 0.955027525629714160, -0.296517158507877470, 0.954970651620192790, - -0.296700277290238350, - 0.954913742499130520, -0.296883385163778270, 0.954856798268619580, - -0.297066482121764730, - 0.954799818930753720, -0.297249568157465840, 0.954742804487627940, - -0.297432643264150030, - 0.954685754941338340, -0.297615707435086200, 0.954628670293982680, - -0.297798760663543550, - 0.954571550547659630, -0.297981802942791810, 0.954514395704469500, - -0.298164834266100850, - 0.954457205766513490, -0.298347854626741400, 0.954399980735894490, - -0.298530864017984120, - 0.954342720614716480, -0.298713862433100330, 0.954285425405084650, - -0.298896849865361800, - 0.954228095109105670, -0.299079826308040480, 0.954170729728887280, - -0.299262791754408840, - 0.954113329266538800, -0.299445746197739890, 0.954055893724170660, - -0.299628689631306790, - 0.953998423103894490, -0.299811622048383350, 0.953940917407823500, - -0.299994543442243580, - 0.953883376638071770, -0.300177453806161950, 0.953825800796755050, - -0.300360353133413530, - 0.953768189885990330, -0.300543241417273450, 0.953710543907895670, - -0.300726118651017500, - 0.953652862864590500, -0.300908984827921890, 0.953595146758195680, - -0.301091839941263100, - 0.953537395590833280, -0.301274683984317950, 0.953479609364626610, - -0.301457516950363940, - 0.953421788081700310, -0.301640338832678770, 0.953363931744180330, - -0.301823149624540650, - 0.953306040354193860, -0.302005949319228080, 0.953248113913869320, - -0.302188737910019990, - 0.953190152425336670, -0.302371515390195970, 0.953132155890726750, - -0.302554281753035610, - 0.953074124312172200, -0.302737036991819140, 0.953016057691806530, - -0.302919781099827310, - 0.952957956031764700, -0.303102514070341060, 0.952899819334182880, - -0.303285235896641750, - 0.952841647601198720, -0.303467946572011320, 0.952783440834950920, - -0.303650646089731910, - 0.952725199037579570, -0.303833334443086360, 0.952666922211226170, - -0.304016011625357570, - 0.952608610358033350, -0.304198677629829110, 0.952550263480144930, - -0.304381332449784880, - 0.952491881579706320, -0.304563976078509100, 0.952433464658864030, - -0.304746608509286530, - 0.952375012719765880, -0.304929229735402370, 0.952316525764560940, - -0.305111839750142110, - 0.952258003795399600, -0.305294438546791670, 0.952199446814433580, - -0.305477026118637420, - 0.952140854823815830, -0.305659602458966120, 0.952082227825700620, - -0.305842167561065080, - 0.952023565822243570, -0.306024721418221790, 0.951964868815601380, - -0.306207264023724220, - 0.951906136807932350, -0.306389795370860920, 0.951847369801395620, - -0.306572315452920740, - 0.951788567798152130, -0.306754824263192780, 0.951729730800363830, - -0.306937321794966910, - 0.951670858810193860, -0.307119808041533100, 0.951611951829806850, - -0.307302282996181790, - 0.951553009861368590, -0.307484746652204100, 0.951494032907046370, - -0.307667199002891190, - 0.951435020969008340, -0.307849640041534870, 0.951375974049424420, - -0.308032069761427330, - 0.951316892150465550, -0.308214488155861050, 0.951257775274304000, - -0.308396895218129190, - 0.951198623423113230, -0.308579290941525090, 0.951139436599068190, - -0.308761675319342450, - 0.951080214804345010, -0.308944048344875710, 0.951020958041121080, - -0.309126410011419440, - 0.950961666311575080, -0.309308760312268730, 0.950902339617887060, - -0.309491099240719100, - 0.950842977962238160, -0.309673426790066380, 0.950783581346811070, - -0.309855742953607070, - 0.950724149773789610, -0.310038047724637890, 0.950664683245358910, - -0.310220341096455850, - 0.950605181763705340, -0.310402623062358720, 0.950545645331016600, - -0.310584893615644450, - 0.950486073949481700, -0.310767152749611470, 0.950426467621290900, - -0.310949400457558640, - 0.950366826348635780, -0.311131636732785270, 0.950307150133709260, - -0.311313861568590920, - 0.950247438978705230, -0.311496074958275910, 0.950187692885819280, - -0.311678276895140550, - 0.950127911857248100, -0.311860467372486020, 0.950068095895189590, - -0.312042646383613510, - 0.950008245001843000, -0.312224813921824880, 0.949948359179409010, - -0.312406969980422440, - 0.949888438430089300, -0.312589114552708710, 0.949828482756087110, - -0.312771247631986770, - 0.949768492159606680, -0.312953369211560200, 0.949708466642853800, - -0.313135479284732840, - 0.949648406208035480, -0.313317577844809010, 0.949588310857359950, - -0.313499664885093510, - 0.949528180593036670, -0.313681740398891520, 0.949468015417276550, - -0.313863804379508500, - 0.949407815332291570, -0.314045856820250710, 0.949347580340295210, - -0.314227897714424440, - 0.949287310443502120, -0.314409927055336660, 0.949227005644128210, - -0.314591944836294660, - 0.949166665944390700, -0.314773951050606070, 0.949106291346508260, - -0.314955945691579140, - 0.949045881852700560, -0.315137928752522440, 0.948985437465188710, - -0.315319900226744890, - 0.948924958186195160, -0.315501860107555990, 0.948864444017943340, - -0.315683808388265650, - 0.948803894962658490, -0.315865745062183960, 0.948743311022566480, - -0.316047670122621860, - 0.948682692199895090, -0.316229583562890330, 0.948622038496872990, - -0.316411485376300980, - 0.948561349915730270, -0.316593375556165850, 0.948500626458698260, - -0.316775254095797270, - 0.948439868128009620, -0.316957120988508150, 0.948379074925898120, - -0.317138976227611780, - 0.948318246854599090, -0.317320819806421740, 0.948257383916349060, - -0.317502651718252260, - 0.948196486113385580, -0.317684471956417970, 0.948135553447947980, - -0.317866280514233660, - 0.948074585922276230, -0.318048077385014950, 0.948013583538612200, - -0.318229862562077530, - 0.947952546299198670, -0.318411636038737790, 0.947891474206279840, - -0.318593397808312420, - 0.947830367262101010, -0.318775147864118480, 0.947769225468909180, - -0.318956886199473650, - 0.947708048828952100, -0.319138612807695900, 0.947646837344479300, - -0.319320327682103610, - 0.947585591017741090, -0.319502030816015690, 0.947524309850989570, - -0.319683722202751430, - 0.947462993846477700, -0.319865401835630500, 0.947401643006459900, - -0.320047069707973140, - 0.947340257333192050, -0.320228725813099860, 0.947278836828930880, - -0.320410370144331820, - 0.947217381495934820, -0.320592002694990330, 0.947155891336463270, - -0.320773623458397330, - 0.947094366352777220, -0.320955232427875210, 0.947032806547138620, - -0.321136829596746660, - 0.946971211921810880, -0.321318414958334850, 0.946909582479058760, - -0.321499988505963510, - 0.946847918221148000, -0.321681550232956580, 0.946786219150346000, - -0.321863100132638580, - 0.946724485268921170, -0.322044638198334510, 0.946662716579143360, - -0.322226164423369600, - 0.946600913083283530, -0.322407678801069850, 0.946539074783614100, - -0.322589181324761330, - 0.946477201682408680, -0.322770671987770710, 0.946415293781942110, - -0.322952150783425260, - 0.946353351084490590, -0.323133617705052330, 0.946291373592331620, - -0.323315072745979980, - 0.946229361307743820, -0.323496515899536710, 0.946167314233007370, - -0.323677947159051240, - 0.946105232370403450, -0.323859366517852850, 0.946043115722214560, - -0.324040773969271450, - 0.945980964290724760, -0.324222169506636960, 0.945918778078219110, - -0.324403553123280230, - 0.945856557086983910, -0.324584924812532150, 0.945794301319306970, - -0.324766284567724220, - 0.945732010777477150, -0.324947632382188430, 0.945669685463784710, - -0.325128968249257080, - 0.945607325380521280, -0.325310292162262930, 0.945544930529979680, - -0.325491604114539310, - 0.945482500914453740, -0.325672904099419850, 0.945420036536239070, - -0.325854192110238580, - 0.945357537397632290, -0.326035468140330240, 0.945295003500931210, - -0.326216732183029710, - 0.945232434848435000, -0.326397984231672490, 0.945169831442444150, - -0.326579224279594400, - 0.945107193285260610, -0.326760452320131730, 0.945044520379187070, - -0.326941668346621420, - 0.944981812726528150, -0.327122872352400510, 0.944919070329589220, - -0.327304064330806670, - 0.944856293190677210, -0.327485244275178000, 0.944793481312100280, - -0.327666412178853120, - 0.944730634696167800, -0.327847568035170840, 0.944667753345190490, - -0.328028711837470680, - 0.944604837261480260, -0.328209843579092500, 0.944541886447350490, - -0.328390963253376580, - 0.944478900905115550, -0.328572070853663740, 0.944415880637091250, - -0.328753166373294990, - 0.944352825645594750, -0.328934249805612200, 0.944289735932944410, - -0.329115321143957250, - 0.944226611501459810, -0.329296380381672750, 0.944163452353461770, - -0.329477427512101740, - 0.944100258491272660, -0.329658462528587490, 0.944037029917215830, - -0.329839485424473940, - 0.943973766633615980, -0.330020496193105420, 0.943910468642799150, - -0.330201494827826570, - 0.943847135947092690, -0.330382481321982780, 0.943783768548825060, - -0.330563455668919540, - 0.943720366450326200, -0.330744417861982890, 0.943656929653927220, - -0.330925367894519540, - 0.943593458161960390, -0.331106305759876430, 0.943529951976759480, - -0.331287231451400820, - 0.943466411100659320, -0.331468144962440870, 0.943402835535996240, - -0.331649046286344670, - 0.943339225285107720, -0.331829935416461110, 0.943275580350332540, - -0.332010812346139380, - 0.943211900734010620, -0.332191677068729150, 0.943148186438483420, - -0.332372529577580620, - 0.943084437466093490, -0.332553369866044220, 0.943020653819184650, - -0.332734197927471050, - 0.942956835500102120, -0.332915013755212650, 0.942892982511192250, - -0.333095817342620780, - 0.942829094854802710, -0.333276608683047930, 0.942765172533282510, - -0.333457387769846850, - 0.942701215548981900, -0.333638154596370860, 0.942637223904252530, - -0.333818909155973620, - 0.942573197601446870, -0.333999651442009380, 0.942509136642919240, - -0.334180381447832690, - 0.942445041031024890, -0.334361099166798740, 0.942380910768120470, - -0.334541804592262900, - 0.942316745856563780, -0.334722497717581220, 0.942252546298714020, - -0.334903178536110180, - 0.942188312096931770, -0.335083847041206580, 0.942124043253578570, - -0.335264503226227810, - 0.942059739771017310, -0.335445147084531600, 0.941995401651612550, - -0.335625778609476290, - 0.941931028897729620, -0.335806397794420450, 0.941866621511735280, - -0.335987004632723350, - 0.941802179495997650, -0.336167599117744520, 0.941737702852886160, - -0.336348181242844050, - 0.941673191584771360, -0.336528751001382410, 0.941608645694025250, - -0.336709308386720580, - 0.941544065183020810, -0.336889853392220050, 0.941479450054132580, - -0.337070386011242620, - 0.941414800309736340, -0.337250906237150590, 0.941350115952208970, - -0.337431414063306840, - 0.941285396983928660, -0.337611909483074620, 0.941220643407275180, - -0.337792392489817460, - 0.941155855224629190, -0.337972863076899720, 0.941091032438372780, - -0.338153321237685930, - 0.941026175050889260, -0.338333766965541130, 0.940961283064563280, - -0.338514200253830940, - 0.940896356481780830, -0.338694621095921190, 0.940831395304928870, - -0.338875029485178450, - 0.940766399536396070, -0.339055425414969640, 0.940701369178571940, - -0.339235808878661950, - 0.940636304233847590, -0.339416179869623360, 0.940571204704615190, - -0.339596538381222110, - 0.940506070593268300, -0.339776884406826850, 0.940440901902201750, - -0.339957217939806880, - 0.940375698633811540, -0.340137538973531720, 0.940310460790495070, - -0.340317847501371670, - 0.940245188374650880, -0.340498143516697160, 0.940179881388678920, - -0.340678427012879200, - 0.940114539834980280, -0.340858697983289440, 0.940049163715957370, - -0.341038956421299720, - 0.939983753034014050, -0.341219202320282360, 0.939918307791555050, - -0.341399435673610420, - 0.939852827990986680, -0.341579656474657160, 0.939787313634716570, - -0.341759864716796310, - 0.939721764725153340, -0.341940060393402190, 0.939656181264707180, - -0.342120243497849530, - 0.939590563255789270, -0.342300414023513520, 0.939524910700812230, - -0.342480571963769800, - 0.939459223602189920, -0.342660717311994380, 0.939393501962337510, - -0.342840850061563950, - 0.939327745783671400, -0.343020970205855540, 0.939261955068609210, - -0.343201077738246540, - 0.939196129819569900, -0.343381172652115040, 0.939130270038973650, - -0.343561254940839390, - 0.939064375729241950, -0.343741324597798490, 0.938998446892797540, - -0.343921381616371700, - 0.938932483532064600, -0.344101425989938810, 0.938866485649468060, - -0.344281457711880180, - 0.938800453247434770, -0.344461476775576540, 0.938734386328392460, - -0.344641483174408960, - 0.938668284894770170, -0.344821476901759290, 0.938602148948998400, - -0.345001457951009670, - 0.938535978493508560, -0.345181426315542550, 0.938469773530733800, - -0.345361381988741220, - 0.938403534063108060, -0.345541324963989090, 0.938337260093066950, - -0.345721255234670120, - 0.938270951623047190, -0.345901172794168990, 0.938204608655486490, - -0.346081077635870430, - 0.938138231192824360, -0.346260969753160010, 0.938071819237501270, - -0.346440849139423520, - 0.938005372791958840, -0.346620715788047320, 0.937938891858640320, - -0.346800569692418290, - 0.937872376439989890, -0.346980410845923680, 0.937805826538453120, - -0.347160239241951160, - 0.937739242156476970, -0.347340054873889140, 0.937672623296509470, - -0.347519857735126110, - 0.937605969960999990, -0.347699647819051380, 0.937539282152399230, - -0.347879425119054510, - 0.937472559873159250, -0.348059189628525610, 0.937405803125732960, - -0.348238941340855260, - 0.937339011912574960, -0.348418680249434560, 0.937272186236140950, - -0.348598406347654930, - 0.937205326098887960, -0.348778119628908420, 0.937138431503274140, - -0.348957820086587490, - 0.937071502451759190, -0.349137507714084970, 0.937004538946803690, - -0.349317182504794380, - 0.936937540990869900, -0.349496844452109550, 0.936870508586420960, - -0.349676493549424760, - 0.936803441735921560, -0.349856129790134920, 0.936736340441837620, - -0.350035753167635240, - 0.936669204706636170, -0.350215363675321580, 0.936602034532785570, - -0.350394961306590150, - 0.936534829922755500, -0.350574546054837510, 0.936467590879016990, - -0.350754117913461060, - 0.936400317404042060, -0.350933676875858360, 0.936333009500304180, - -0.351113222935427460, - 0.936265667170278260, -0.351292756085567090, 0.936198290416440090, - -0.351472276319676310, - 0.936130879241267030, -0.351651783631154570, 0.936063433647237540, - -0.351831278013402030, - 0.935995953636831410, -0.352010759459819080, 0.935928439212529660, - -0.352190227963806830, - 0.935860890376814640, -0.352369683518766630, 0.935793307132169900, - -0.352549126118100460, - 0.935725689481080370, -0.352728555755210730, 0.935658037426032040, - -0.352907972423500250, - 0.935590350969512370, -0.353087376116372480, 0.935522630114009930, - -0.353266766827231240, - 0.935454874862014620, -0.353446144549480810, 0.935387085216017770, - -0.353625509276525970, - 0.935319261178511610, -0.353804861001772050, 0.935251402751989920, - -0.353984199718624770, - 0.935183509938947610, -0.354163525420490340, 0.935115582741880890, - -0.354342838100775550, - 0.935047621163287430, -0.354522137752887430, 0.934979625205665800, - -0.354701424370233830, - 0.934911594871516090, -0.354880697946222790, 0.934843530163339540, - -0.355059958474262860, - 0.934775431083638700, -0.355239205947763310, 0.934707297634917440, - -0.355418440360133650, - 0.934639129819680780, -0.355597661704783850, 0.934570927640435030, - -0.355776869975124640, - 0.934502691099687870, -0.355956065164566850, 0.934434420199948050, - -0.356135247266522130, - 0.934366114943725790, -0.356314416274402410, 0.934297775333532530, - -0.356493572181620090, - 0.934229401371880820, -0.356672714981588260, 0.934160993061284530, - -0.356851844667720300, - 0.934092550404258980, -0.357030961233429980, 0.934024073403320390, - -0.357210064672131960, - 0.933955562060986730, -0.357389154977240940, 0.933887016379776890, - -0.357568232142172260, - 0.933818436362210960, -0.357747296160341900, 0.933749822010810580, - -0.357926347025166010, - 0.933681173328098410, -0.358105384730061590, 0.933612490316598540, - -0.358284409268445850, - 0.933543772978836170, -0.358463420633736540, 0.933475021317337950, - -0.358642418819351990, - 0.933406235334631520, -0.358821403818710860, 0.933337415033246190, - -0.359000375625232460, - 0.933268560415712050, -0.359179334232336500, 0.933199671484560730, - -0.359358279633443130, - 0.933130748242325230, -0.359537211821973070, 0.933061790691539380, - -0.359716130791347570, - 0.932992798834738960, -0.359895036534988110, 0.932923772674460140, - -0.360073929046317020, - 0.932854712213241120, -0.360252808318756890, 0.932785617453621100, - -0.360431674345730700, - 0.932716488398140250, -0.360610527120662270, 0.932647325049340450, - -0.360789366636975580, - 0.932578127409764420, -0.360968192888095230, 0.932508895481956590, - -0.361147005867446250, - 0.932439629268462360, -0.361325805568454280, 0.932370328771828460, - -0.361504591984545260, - 0.932300993994602760, -0.361683365109145840, 0.932231624939334540, - -0.361862124935682980, - 0.932162221608574430, -0.362040871457584180, 0.932092784004874050, - -0.362219604668277460, - 0.932023312130786490, -0.362398324561191310, 0.931953805988866010, - -0.362577031129754760, - 0.931884265581668150, -0.362755724367397230, 0.931814690911749730, - -0.362934404267548640, - 0.931745081981668720, -0.363113070823639470, 0.931675438793984620, - -0.363291724029100760, - 0.931605761351257830, -0.363470363877363760, 0.931536049656050300, - -0.363648990361860550, - 0.931466303710925090, -0.363827603476023500, 0.931396523518446600, - -0.364006203213285470, - 0.931326709081180430, -0.364184789567079890, 0.931256860401693420, - -0.364363362530840620, - 0.931186977482553750, -0.364541922098002120, 0.931117060326330790, - -0.364720468261999280, - 0.931047108935595280, -0.364899001016267320, 0.930977123312918930, - -0.365077520354242180, - 0.930907103460875130, -0.365256026269360320, 0.930837049382038150, - -0.365434518755058390, - 0.930766961078983710, -0.365612997804773850, 0.930696838554288860, - -0.365791463411944570, - 0.930626681810531760, -0.365969915570008740, 0.930556490850291800, - -0.366148354272405330, - 0.930486265676149780, -0.366326779512573590, 0.930416006290687550, - -0.366505191283953370, - 0.930345712696488470, -0.366683589579984930, 0.930275384896137150, - -0.366861974394109060, - 0.930205022892219070, -0.367040345719767180, 0.930134626687321390, - -0.367218703550400980, - 0.930064196284032360, -0.367397047879452710, 0.929993731684941480, - -0.367575378700365330, - 0.929923232892639670, -0.367753696006581980, 0.929852699909718750, - -0.367931999791546450, - 0.929782132738772190, -0.368110290048703050, 0.929711531382394370, - -0.368288566771496570, - 0.929640895843181330, -0.368466829953372320, 0.929570226123729860, - -0.368645079587776040, - 0.929499522226638560, -0.368823315668153910, 0.929428784154506800, - -0.369001538187952780, - 0.929358011909935500, -0.369179747140620020, 0.929287205495526790, - -0.369357942519603130, - 0.929216364913884040, -0.369536124318350650, 0.929145490167611720, - -0.369714292530311240, - 0.929074581259315860, -0.369892447148934100, 0.929003638191603360, - -0.370070588167669080, - 0.928932660967082820, -0.370248715579966360, 0.928861649588363700, - -0.370426829379276790, - 0.928790604058057020, -0.370604929559051670, 0.928719524378774810, - -0.370783016112742560, - 0.928648410553130520, -0.370961089033801980, 0.928577262583738850, - -0.371139148315682570, - 0.928506080473215590, -0.371317193951837540, 0.928434864224177980, - -0.371495225935720760, - 0.928363613839244370, -0.371673244260786520, 0.928292329321034670, - -0.371851248920489490, - 0.928221010672169440, -0.372029239908285010, 0.928149657895271150, - -0.372207217217628840, - 0.928078270992963140, -0.372385180841977360, 0.928006849967869970, - -0.372563130774787250, - 0.927935394822617890, -0.372741067009515760, 0.927863905559833780, - -0.372918989539620830, - 0.927792382182146320, -0.373096898358560640, 0.927720824692185200, - -0.373274793459793970, - 0.927649233092581180, -0.373452674836780300, 0.927577607385966730, - -0.373630542482979280, - 0.927505947574975180, -0.373808396391851210, 0.927434253662241300, - -0.373986236556857030, - 0.927362525650401110, -0.374164062971457930, 0.927290763542091720, - -0.374341875629115920, - 0.927218967339951790, -0.374519674523293210, 0.927147137046620880, - -0.374697459647452600, - 0.927075272664740100, -0.374875230995057540, 0.927003374196951670, - -0.375052988559571920, - 0.926931441645899130, -0.375230732334459920, 0.926859475014227160, - -0.375408462313186590, - 0.926787474304581750, -0.375586178489217220, 0.926715439519610330, - -0.375763880856017700, - 0.926643370661961230, -0.375941569407054420, 0.926571267734284330, - -0.376119244135794340, - 0.926499130739230510, -0.376296905035704790, 0.926426959679452210, - -0.376474552100253770, - 0.926354754557602860, -0.376652185322909560, 0.926282515376337210, - -0.376829804697141280, - 0.926210242138311380, -0.377007410216418260, 0.926137934846182560, - -0.377185001874210450, - 0.926065593502609310, -0.377362579663988340, 0.925993218110251480, - -0.377540143579222940, - 0.925920808671770070, -0.377717693613385640, 0.925848365189827270, - -0.377895229759948490, - 0.925775887667086740, -0.378072752012383990, 0.925703376106213230, - -0.378250260364165200, - 0.925630830509872720, -0.378427754808765560, 0.925558250880732740, - -0.378605235339659120, - 0.925485637221461490, -0.378782701950320540, 0.925412989534729060, - -0.378960154634224720, - 0.925340307823206310, -0.379137593384847320, 0.925267592089565660, - -0.379315018195664430, - 0.925194842336480530, -0.379492429060152630, 0.925122058566625880, - -0.379669825971788940, - 0.925049240782677580, -0.379847208924051160, 0.924976388987313160, - -0.380024577910417270, - 0.924903503183210910, -0.380201932924366050, 0.924830583373050800, - -0.380379273959376600, - 0.924757629559513910, -0.380556601008928520, 0.924684641745282420, - -0.380733914066502140, - 0.924611619933039970, -0.380911213125578070, 0.924538564125471420, - -0.381088498179637520, - 0.924465474325262600, -0.381265769222162380, 0.924392350535101050, - -0.381443026246634730, - 0.924319192757675160, -0.381620269246537360, 0.924246000995674890, - -0.381797498215353640, - 0.924172775251791200, -0.381974713146567220, 0.924099515528716280, - -0.382151914033662610, - 0.924026221829143850, -0.382329100870124510, 0.923952894155768640, - -0.382506273649438230, - 0.923879532511286740, -0.382683432365089780, 0.923806136898395410, - -0.382860577010565420, - 0.923732707319793290, -0.383037707579352020, 0.923659243778179980, - -0.383214824064937180, - 0.923585746276256670, -0.383391926460808660, 0.923512214816725630, - -0.383569014760454910, - 0.923438649402290370, -0.383746088957365010, 0.923365050035655720, - -0.383923149045028390, - 0.923291416719527640, -0.384100195016935040, 0.923217749456613500, - -0.384277226866575510, - 0.923144048249621930, -0.384454244587440820, 0.923070313101262420, - -0.384631248173022580, - 0.922996544014246250, -0.384808237616812880, 0.922922740991285680, - -0.384985212912304200, - 0.922848904035094120, -0.385162174052989860, 0.922775033148386380, - -0.385339121032363340, - 0.922701128333878630, -0.385516053843918850, 0.922627189594287910, - -0.385692972481151140, - 0.922553216932332830, -0.385869876937555310, 0.922479210350733210, - -0.386046767206627170, - 0.922405169852209880, -0.386223643281862980, 0.922331095439485440, - -0.386400505156759440, - 0.922256987115283030, -0.386577352824813920, 0.922182844882327600, - -0.386754186279524180, - 0.922108668743345180, -0.386931005514388580, 0.922034458701062820, - -0.387107810522905990, - 0.921960214758209220, -0.387284601298575840, 0.921885936917513970, - -0.387461377834897870, - 0.921811625181708120, -0.387638140125372730, 0.921737279553523910, - -0.387814888163501180, - 0.921662900035694730, -0.387991621942784860, 0.921588486630955490, - -0.388168341456725740, - 0.921514039342042010, -0.388345046698826250, 0.921439558171691430, - -0.388521737662589570, - 0.921365043122642340, -0.388698414341519190, 0.921290494197634540, - -0.388875076729119250, - 0.921215911399408730, -0.389051724818894380, 0.921141294730707270, - -0.389228358604349730, - 0.921066644194273640, -0.389404978078990940, 0.920991959792852310, - -0.389581583236324300, - 0.920917241529189520, -0.389758174069856410, 0.920842489406032190, - -0.389934750573094730, - 0.920767703426128790, -0.390111312739546910, 0.920692883592229120, - -0.390287860562721190, - 0.920618029907083970, -0.390464394036126590, 0.920543142373445480, - -0.390640913153272430, - 0.920468220994067110, -0.390817417907668500, 0.920393265771703550, - -0.390993908292825380, - 0.920318276709110590, -0.391170384302253870, 0.920243253809045370, - -0.391346845929465560, - 0.920168197074266340, -0.391523293167972410, 0.920093106507533180, - -0.391699726011286940, - 0.920017982111606570, -0.391876144452922350, 0.919942823889248640, - -0.392052548486392090, - 0.919867631843222950, -0.392228938105210310, 0.919792405976293860, - -0.392405313302891690, - 0.919717146291227360, -0.392581674072951470, 0.919641852790790470, - -0.392758020408905280, - 0.919566525477751530, -0.392934352304269490, 0.919491164354880100, - -0.393110669752560760, - 0.919415769424947070, -0.393286972747296400, 0.919340340690724340, - -0.393463261281994330, - 0.919264878154985370, -0.393639535350172880, 0.919189381820504470, - -0.393815794945351020, - 0.919113851690057770, -0.393992040061048100, 0.919038287766422050, - -0.394168270690784080, - 0.918962690052375630, -0.394344486828079600, 0.918887058550697970, - -0.394520688466455600, - 0.918811393264170050, -0.394696875599433560, 0.918735694195573550, - -0.394873048220535760, - 0.918659961347691900, -0.395049206323284770, 0.918584194723309540, - -0.395225349901203670, - 0.918508394325212250, -0.395401478947816350, 0.918432560156186910, - -0.395577593456646840, - 0.918356692219021720, -0.395753693421220080, 0.918280790516506130, - -0.395929778835061250, - 0.918204855051430900, -0.396105849691696270, 0.918128885826588030, - -0.396281905984651520, - 0.918052882844770380, -0.396457947707453910, 0.917976846108772730, - -0.396633974853630830, - 0.917900775621390500, -0.396809987416710310, 0.917824671385420570, - -0.396985985390220900, - 0.917748533403661250, -0.397161968767691610, 0.917672361678911860, - -0.397337937542652060, - 0.917596156213972950, -0.397513891708632330, 0.917519917011646260, - -0.397689831259163180, - 0.917443644074735220, -0.397865756187775750, 0.917367337406043930, - -0.398041666488001770, - 0.917290997008377910, -0.398217562153373560, 0.917214622884544250, - -0.398393443177423980, - 0.917138215037350710, -0.398569309553686300, 0.917061773469606820, - -0.398745161275694430, - 0.916985298184123000, -0.398920998336982910, 0.916908789183710990, - -0.399096820731086540, - 0.916832246471183890, -0.399272628451540990, 0.916755670049355990, - -0.399448421491882140, - 0.916679059921042700, -0.399624199845646790, 0.916602416089060790, - -0.399799963506371980, - 0.916525738556228210, -0.399975712467595330, 0.916449027325364150, - -0.400151446722855130, - 0.916372282399289140, -0.400327166265690090, 0.916295503780824800, - -0.400502871089639500, - 0.916218691472794220, -0.400678561188243240, 0.916141845478021350, - -0.400854236555041650, - 0.916064965799331720, -0.401029897183575620, 0.915988052439551950, - -0.401205543067386710, - 0.915911105401509880, -0.401381174200016790, 0.915834124688034710, - -0.401556790575008540, - 0.915757110301956720, -0.401732392185905010, 0.915680062246107650, - -0.401907979026249700, - 0.915602980523320230, -0.402083551089586990, 0.915525865136428530, - -0.402259108369461490, - 0.915448716088267830, -0.402434650859418430, 0.915371533381674760, - -0.402610178553003680, - 0.915294317019487050, -0.402785691443763530, 0.915217067004543860, - -0.402961189525244900, - 0.915139783339685260, -0.403136672790995300, 0.915062466027752760, - -0.403312141234562550, - 0.914985115071589310, -0.403487594849495310, 0.914907730474038730, - -0.403663033629342640, - 0.914830312237946200, -0.403838457567654070, 0.914752860366158220, - -0.404013866657979890, - 0.914675374861522390, -0.404189260893870690, 0.914597855726887790, - -0.404364640268877810, - 0.914520302965104450, -0.404540004776553000, 0.914442716579023870, - -0.404715354410448650, - 0.914365096571498560, -0.404890689164117580, 0.914287442945382440, - -0.405066009031113340, - 0.914209755703530690, -0.405241314004989860, 0.914132034848799460, - -0.405416604079301630, - 0.914054280384046570, -0.405591879247603870, 0.913976492312130630, - -0.405767139503452060, - 0.913898670635911680, -0.405942384840402510, 0.913820815358251100, - -0.406117615252011840, - 0.913742926482011390, -0.406292830731837360, 0.913665004010056350, - -0.406468031273437000, - 0.913587047945250810, -0.406643216870369030, 0.913509058290461140, - -0.406818387516192310, - 0.913431035048554720, -0.406993543204466510, 0.913352978222400250, - -0.407168683928751550, - 0.913274887814867760, -0.407343809682607970, 0.913196763828828200, - -0.407518920459596920, - 0.913118606267154240, -0.407694016253280110, 0.913040415132719160, - -0.407869097057219800, - 0.912962190428398210, -0.408044162864978690, 0.912883932157067200, - -0.408219213670120100, - 0.912805640321603500, -0.408394249466208000, 0.912727314924885900, - -0.408569270246806780, - 0.912648955969793900, -0.408744276005481360, 0.912570563459208730, - -0.408919266735797430, - 0.912492137396012650, -0.409094242431320980, 0.912413677783089020, - -0.409269203085618590, - 0.912335184623322750, -0.409444148692257590, 0.912256657919599760, - -0.409619079244805670, - 0.912178097674807180, -0.409793994736831150, 0.912099503891833470, - -0.409968895161902880, - 0.912020876573568340, -0.410143780513590240, 0.911942215722902570, - -0.410318650785463260, - 0.911863521342728520, -0.410493505971092410, 0.911784793435939430, - -0.410668346064048730, - 0.911706032005429880, -0.410843171057903910, 0.911627237054095650, - -0.411017980946230210, - 0.911548408584833990, -0.411192775722600160, 0.911469546600543020, - -0.411367555380587220, - 0.911390651104122430, -0.411542319913765220, 0.911311722098472780, - -0.411717069315708560, - 0.911232759586496190, -0.411891803579992170, 0.911153763571095900, - -0.412066522700191560, - 0.911074734055176360, -0.412241226669882890, 0.910995671041643140, - -0.412415915482642730, - 0.910916574533403360, -0.412590589132048210, 0.910837444533365010, - -0.412765247611677270, - 0.910758281044437570, -0.412939890915108080, 0.910679084069531570, - -0.413114519035919450, - 0.910599853611558930, -0.413289131967690960, 0.910520589673432750, - -0.413463729704002410, - 0.910441292258067250, -0.413638312238434500, 0.910361961368377990, - -0.413812879564568300, - 0.910282597007281760, -0.413987431675985400, 0.910203199177696540, - -0.414161968566268080, - 0.910123767882541680, -0.414336490228999100, 0.910044303124737500, - -0.414510996657761750, - 0.909964804907205660, -0.414685487846140010, 0.909885273232869160, - -0.414859963787718330, - 0.909805708104652220, -0.415034424476081630, 0.909726109525480160, - -0.415208869904815590, - 0.909646477498279540, -0.415383300067506230, 0.909566812025978330, - -0.415557714957740410, - 0.909487113111505430, -0.415732114569105360, 0.909407380757791260, - -0.415906498895188770, - 0.909327614967767260, -0.416080867929579210, 0.909247815744366310, - -0.416255221665865480, - 0.909167983090522380, -0.416429560097637150, 0.909088117009170580, - -0.416603883218484350, - 0.909008217503247450, -0.416778191021997650, 0.908928284575690640, - -0.416952483501768170, - 0.908848318229439120, -0.417126760651387870, 0.908768318467432890, - -0.417301022464448890, - 0.908688285292613360, -0.417475268934544290, 0.908608218707923190, - -0.417649500055267410, - 0.908528118716306120, -0.417823715820212270, 0.908447985320707250, - -0.417997916222973550, - 0.908367818524072890, -0.418172101257146320, 0.908287618329350450, - -0.418346270916326260, - 0.908207384739488700, -0.418520425194109700, 0.908127117757437600, - -0.418694564084093560, - 0.908046817386148340, -0.418868687579875050, 0.907966483628573350, - -0.419042795675052370, - 0.907886116487666260, -0.419216888363223910, 0.907805715966381930, - -0.419390965637988890, - 0.907725282067676440, -0.419565027492946880, 0.907644814794507200, - -0.419739073921698180, - 0.907564314149832630, -0.419913104917843620, 0.907483780136612570, - -0.420087120474984530, - 0.907403212757808110, -0.420261120586722880, 0.907322612016381420, - -0.420435105246661170, - 0.907241977915295820, -0.420609074448402510, 0.907161310457516250, - -0.420783028185550520, - 0.907080609646008450, -0.420956966451709440, 0.906999875483739610, - -0.421130889240483970, - 0.906919107973678140, -0.421304796545479640, 0.906838307118793430, - -0.421478688360302280, - 0.906757472922056550, -0.421652564678558330, 0.906676605386439460, - -0.421826425493854910, - 0.906595704514915330, -0.422000270799799680, 0.906514770310458800, - -0.422174100590000770, - 0.906433802776045460, -0.422347914858067050, 0.906352801914652400, - -0.422521713597607820, - 0.906271767729257660, -0.422695496802232950, 0.906190700222840650, - -0.422869264465553060, - 0.906109599398381980, -0.423043016581179040, 0.906028465258863600, - -0.423216753142722610, - 0.905947297807268460, -0.423390474143796050, 0.905866097046580940, - -0.423564179578011960, - 0.905784862979786550, -0.423737869438983840, 0.905703595609872010, - -0.423911543720325580, - 0.905622294939825270, -0.424085202415651560, 0.905540960972635590, - -0.424258845518576950, - 0.905459593711293250, -0.424432473022717420, 0.905378193158790090, - -0.424606084921689110, - 0.905296759318118820, -0.424779681209108810, 0.905215292192273590, - -0.424953261878593890, - 0.905133791784249690, -0.425126826923762360, 0.905052258097043590, - -0.425300376338232640, - 0.904970691133653250, -0.425473910115623800, 0.904889090897077470, - -0.425647428249555590, - 0.904807457390316540, -0.425820930733648240, 0.904725790616371930, - -0.425994417561522400, - 0.904644090578246240, -0.426167888726799620, 0.904562357278943300, - -0.426341344223101830, - 0.904480590721468250, -0.426514784044051520, 0.904398790908827350, - -0.426688208183271860, - 0.904316957844028320, -0.426861616634386430, 0.904235091530079750, - -0.427035009391019680, - 0.904153191969991780, -0.427208386446796320, 0.904071259166775440, - -0.427381747795341770, - 0.903989293123443340, -0.427555093430282080, 0.903907293843009050, - -0.427728423345243800, - 0.903825261328487510, -0.427901737533854080, 0.903743195582894620, - -0.428075035989740730, - 0.903661096609247980, -0.428248318706531960, 0.903578964410566070, - -0.428421585677856650, - 0.903496798989868450, -0.428594836897344400, 0.903414600350176290, - -0.428768072358625070, - 0.903332368494511820, -0.428941292055329490, 0.903250103425898400, - -0.429114495981088750, - 0.903167805147360720, -0.429287684129534610, 0.903085473661924600, - -0.429460856494299490, - 0.903003108972617150, -0.429634013069016380, 0.902920711082466740, - -0.429807153847318710, - 0.902838279994502830, -0.429980278822840620, 0.902755815711756120, - -0.430153387989216870, - 0.902673318237258830, -0.430326481340082610, 0.902590787574043870, - -0.430499558869073820, - 0.902508223725145940, -0.430672620569826800, 0.902425626693600380, - -0.430845666435978660, - 0.902342996482444200, -0.431018696461167030, 0.902260333094715540, - -0.431191710639029950, - 0.902177636533453620, -0.431364708963206330, 0.902094906801698900, - -0.431537691427335500, - 0.902012143902493180, -0.431710658025057260, 0.901929347838879460, - -0.431883608750012250, - 0.901846518613901750, -0.432056543595841500, 0.901763656230605730, - -0.432229462556186720, - 0.901680760692037730, -0.432402365624690140, 0.901597832001245660, - -0.432575252794994650, - 0.901514870161278740, -0.432748124060743700, 0.901431875175186970, - -0.432920979415581280, - 0.901348847046022030, -0.433093818853151960, 0.901265785776836580, - -0.433266642367100940, - 0.901182691370684520, -0.433439449951074090, 0.901099563830620950, - -0.433612241598717580, - 0.901016403159702330, -0.433785017303678520, 0.900933209360986200, - -0.433957777059604420, - 0.900849982437531450, -0.434130520860143310, 0.900766722392397860, - -0.434303248698943990, - 0.900683429228646970, -0.434475960569655650, 0.900600102949340900, - -0.434648656465928320, - 0.900516743557543520, -0.434821336381412290, 0.900433351056319830, - -0.434994000309758710, - 0.900349925448735600, -0.435166648244619260, 0.900266466737858480, - -0.435339280179646070, - 0.900182974926756810, -0.435511896108492000, 0.900099450018500450, - -0.435684496024810460, - 0.900015892016160280, -0.435857079922255470, 0.899932300922808510, - -0.436029647794481560, - 0.899848676741518580, -0.436202199635143950, 0.899765019475365140, - -0.436374735437898340, - 0.899681329127423930, -0.436547255196401200, 0.899597605700772180, - -0.436719758904309360, - 0.899513849198487980, -0.436892246555280360, 0.899430059623650860, - -0.437064718142972370, - 0.899346236979341570, -0.437237173661044090, 0.899262381268642000, - -0.437409613103154790, - 0.899178492494635330, -0.437582036462964400, 0.899094570660405770, - -0.437754443734133410, - 0.899010615769039070, -0.437926834910322860, 0.898926627823621870, - -0.438099209985194470, - 0.898842606827242370, -0.438271568952410430, 0.898758552782989440, - -0.438443911805633690, - 0.898674465693953820, -0.438616238538527660, 0.898590345563227030, - -0.438788549144756290, - 0.898506192393901950, -0.438960843617984320, 0.898422006189072530, - -0.439133121951876930, - 0.898337786951834310, -0.439305384140099950, 0.898253534685283570, - -0.439477630176319800, - 0.898169249392518080, -0.439649860054203480, 0.898084931076636780, - -0.439822073767418500, - 0.898000579740739880, -0.439994271309633260, 0.897916195387928660, - -0.440166452674516320, - 0.897831778021305650, -0.440338617855737250, 0.897747327643974690, - -0.440510766846965940, - 0.897662844259040860, -0.440682899641872900, 0.897578327869610230, - -0.440855016234129430, - 0.897493778478790310, -0.441027116617407230, 0.897409196089689720, - -0.441199200785378660, - 0.897324580705418320, -0.441371268731716670, 0.897239932329087160, - -0.441543320450094870, - 0.897155250963808550, -0.441715355934187310, 0.897070536612695870, - -0.441887375177668850, - 0.896985789278863970, -0.442059378174214700, 0.896901008965428790, - -0.442231364917500980, - 0.896816195675507300, -0.442403335401204080, 0.896731349412217880, - -0.442575289619001170, - 0.896646470178680150, -0.442747227564570020, 0.896561557978014960, - -0.442919149231588980, - 0.896476612813344120, -0.443091054613736880, 0.896391634687790820, - -0.443262943704693320, - 0.896306623604479550, -0.443434816498138480, 0.896221579566536030, - -0.443606672987752970, - 0.896136502577086770, -0.443778513167218220, 0.896051392639260150, - -0.443950337030216140, - 0.895966249756185220, -0.444122144570429200, 0.895881073930992370, - -0.444293935781540580, - 0.895795865166813530, -0.444465710657234000, 0.895710623466781320, - -0.444637469191193790, - 0.895625348834030110, -0.444809211377104880, 0.895540041271694950, - -0.444980937208652730, - 0.895454700782912450, -0.445152646679523640, 0.895369327370820310, - -0.445324339783404190, - 0.895283921038557580, -0.445496016513981740, 0.895198481789264200, - -0.445667676864944300, - 0.895113009626081760, -0.445839320829980290, 0.895027504552152630, - -0.446010948402778940, - 0.894941966570620750, -0.446182559577030070, 0.894856395684631050, - -0.446354154346423840, - 0.894770791897329550, -0.446525732704651350, 0.894685155211863980, - -0.446697294645404090, - 0.894599485631382700, -0.446868840162374160, 0.894513783159035620, - -0.447040369249254440, - 0.894428047797973800, -0.447211881899738320, 0.894342279551349480, - -0.447383378107519600, - 0.894256478422316040, -0.447554857866293010, 0.894170644414028270, - -0.447726321169753580, - 0.894084777529641990, -0.447897768011597310, 0.893998877772314240, - -0.448069198385520400, - 0.893912945145203250, -0.448240612285219890, 0.893826979651468620, - -0.448412009704393430, - 0.893740981294271040, -0.448583390636739240, 0.893654950076772540, - -0.448754755075955970, - 0.893568886002135910, -0.448926103015743260, 0.893482789073525850, - -0.449097434449801050, - 0.893396659294107720, -0.449268749371829920, 0.893310496667048200, - -0.449440047775531150, - 0.893224301195515320, -0.449611329654606540, 0.893138072882678320, - -0.449782595002758690, - 0.893051811731707450, -0.449953843813690520, 0.892965517745774370, - -0.450125076081105690, - 0.892879190928051680, -0.450296291798708610, 0.892792831281713610, - -0.450467490960204110, - 0.892706438809935390, -0.450638673559297600, 0.892620013515893150, - -0.450809839589695280, - 0.892533555402764580, -0.450980989045103860, 0.892447064473728680, - -0.451152121919230600, - 0.892360540731965360, -0.451323238205783520, 0.892273984180655840, - -0.451494337898471100, - 0.892187394822982480, -0.451665420991002490, 0.892100772662129060, - -0.451836487477087490, - 0.892014117701280470, -0.452007537350436420, 0.891927429943622510, - -0.452178570604760350, - 0.891840709392342720, -0.452349587233770890, 0.891753956050629460, - -0.452520587231180050, - 0.891667169921672280, -0.452691570590700920, 0.891580351008662290, - -0.452862537306046750, - 0.891493499314791380, -0.453033487370931580, 0.891406614843252900, - -0.453204420779070190, - 0.891319697597241390, -0.453375337524177750, 0.891232747579952520, - -0.453546237599970090, - 0.891145764794583180, -0.453717121000163870, 0.891058749244331590, - -0.453887987718476050, - 0.890971700932396860, -0.454058837748624430, 0.890884619861979530, - -0.454229671084327320, - 0.890797506036281490, -0.454400487719303580, 0.890710359458505630, - -0.454571287647272950, - 0.890623180131855930, -0.454742070861955450, 0.890535968059537830, - -0.454912837357071940, - 0.890448723244757880, -0.455083587126343840, 0.890361445690723840, - -0.455254320163493100, - 0.890274135400644600, -0.455425036462242360, 0.890186792377730240, - -0.455595736016314980, - 0.890099416625192320, -0.455766418819434640, 0.890012008146243260, - -0.455937084865326030, - 0.889924566944096720, -0.456107734147714110, 0.889837093021967900, - -0.456278366660324620, - 0.889749586383072780, -0.456448982396883920, 0.889662047030628900, - -0.456619581351118910, - 0.889574474967854580, -0.456790163516757160, 0.889486870197969900, - -0.456960728887526980, - 0.889399232724195520, -0.457131277457156980, 0.889311562549753850, - -0.457301809219376630, - 0.889223859677868210, -0.457472324167916060, 0.889136124111763240, - -0.457642822296505770, - 0.889048355854664570, -0.457813303598877170, 0.888960554909799310, - -0.457983768068762120, - 0.888872721280395630, -0.458154215699893060, 0.888784854969682850, - -0.458324646486003240, - 0.888696955980891600, -0.458495060420826270, 0.888609024317253860, - -0.458665457498096560, - 0.888521059982002260, -0.458835837711549120, 0.888433062978371320, - -0.459006201054919630, - 0.888345033309596350, -0.459176547521944090, 0.888256970978913870, - -0.459346877106359630, - 0.888168875989561730, -0.459517189801903480, 0.888080748344778900, - -0.459687485602313870, - 0.887992588047805560, -0.459857764501329540, 0.887904395101883240, - -0.460028026492689650, - 0.887816169510254440, -0.460198271570134320, 0.887727911276163020, - -0.460368499727404010, - 0.887639620402853930, -0.460538710958240010, 0.887551296893573370, - -0.460708905256384080, - 0.887462940751568840, -0.460879082615578690, 0.887374551980088850, - -0.461049243029566900, - 0.887286130582383150, -0.461219386492092380, 0.887197676561702900, - -0.461389512996899450, - 0.887109189921300170, -0.461559622537733080, 0.887020670664428360, - -0.461729715108338770, - 0.886932118794342190, -0.461899790702462730, 0.886843534314297410, - -0.462069849313851750, - 0.886754917227550840, -0.462239890936253340, 0.886666267537361000, - -0.462409915563415430, - 0.886577585246987040, -0.462579923189086810, 0.886488870359689600, - -0.462749913807016740, - 0.886400122878730600, -0.462919887410955080, 0.886311342807372780, - -0.463089843994652530, - 0.886222530148880640, -0.463259783551860150, 0.886133684906519340, - -0.463429706076329830, - 0.886044807083555600, -0.463599611561814010, 0.885955896683257030, - -0.463769500002065630, - 0.885866953708892790, -0.463939371390838520, 0.885777978163732940, - -0.464109225721886950, - 0.885688970051048960, -0.464279062988965760, 0.885599929374113360, - -0.464448883185830660, - 0.885510856136199950, -0.464618686306237820, 0.885421750340583680, - -0.464788472343943990, - 0.885332611990540590, -0.464958241292706690, 0.885243441089348270, - -0.465127993146283950, - 0.885154237640285110, -0.465297727898434600, 0.885065001646630930, - -0.465467445542917800, - 0.884975733111666660, -0.465637146073493660, 0.884886432038674560, - -0.465806829483922710, - 0.884797098430937790, -0.465976495767966180, 0.884707732291741040, - -0.466146144919385890, - 0.884618333624369920, -0.466315776931944430, 0.884528902432111460, - -0.466485391799404900, - 0.884439438718253810, -0.466654989515530920, 0.884349942486086120, - -0.466824570074086950, - 0.884260413738899190, -0.466994133468838000, 0.884170852479984500, - -0.467163679693549770, - 0.884081258712634990, -0.467333208741988420, 0.883991632440144890, - -0.467502720607920920, - 0.883901973665809470, -0.467672215285114770, 0.883812282392925090, - -0.467841692767338170, - 0.883722558624789660, -0.468011153048359830, 0.883632802364701870, - -0.468180596121949290, - 0.883543013615961880, -0.468350021981876530, 0.883453192381870920, - -0.468519430621912310, - 0.883363338665731580, -0.468688822035827900, 0.883273452470847430, - -0.468858196217395330, - 0.883183533800523390, -0.469027553160387130, 0.883093582658065370, - -0.469196892858576580, - 0.883003599046780830, -0.469366215305737520, 0.882913582969978020, - -0.469535520495644450, - 0.882823534430966620, -0.469704808422072460, 0.882733453433057650, - -0.469874079078797360, - 0.882643339979562790, -0.470043332459595620, 0.882553194073795510, - -0.470212568558244170, - 0.882463015719070150, -0.470381787368520650, 0.882372804918702290, - -0.470550988884203550, - 0.882282561676008710, -0.470720173099071600, 0.882192285994307430, - -0.470889340006904520, - 0.882101977876917580, -0.471058489601482500, 0.882011637327159590, - -0.471227621876586340, - 0.881921264348355050, -0.471396736825997640, 0.881830858943826620, - -0.471565834443498420, - 0.881740421116898320, -0.471734914722871430, 0.881649950870895260, - -0.471903977657900210, - 0.881559448209143780, -0.472073023242368660, 0.881468913134971440, - -0.472242051470061490, - 0.881378345651706920, -0.472411062334764040, 0.881287745762680100, - -0.472580055830262250, - 0.881197113471222090, -0.472749031950342790, 0.881106448780665130, - -0.472917990688792760, - 0.881015751694342870, -0.473086932039400050, 0.880925022215589880, - -0.473255855995953320, - 0.880834260347742040, -0.473424762552241530, 0.880743466094136340, - -0.473593651702054530, - 0.880652639458111010, -0.473762523439182850, 0.880561780443005700, - -0.473931377757417450, - 0.880470889052160750, -0.474100214650549970, 0.880379965288918150, - -0.474269034112372980, - 0.880289009156621010, -0.474437836136679230, 0.880198020658613190, - -0.474606620717262560, - 0.880106999798240360, -0.474775387847917120, 0.880015946578849070, - -0.474944137522437800, - 0.879924861003786860, -0.475112869734620300, 0.879833743076402940, - -0.475281584478260740, - 0.879742592800047410, -0.475450281747155870, 0.879651410178071580, - -0.475618961535103300, - 0.879560195213827890, -0.475787623835901120, 0.879468947910670210, - -0.475956268643348060, - 0.879377668271953290, -0.476124895951243580, 0.879286356301033250, - -0.476293505753387690, - 0.879195012001267480, -0.476462098043581190, 0.879103635376014330, - -0.476630672815625320, - 0.879012226428633530, -0.476799230063322090, 0.878920785162485840, - -0.476967769780474170, - 0.878829311580933360, -0.477136291960884810, 0.878737805687339390, - -0.477304796598357890, - 0.878646267485068130, -0.477473283686698060, 0.878554696977485450, - -0.477641753219710470, - 0.878463094167957870, -0.477810205191200990, 0.878371459059853480, - -0.477978639594976160, - 0.878279791656541580, -0.478147056424843010, 0.878188091961392250, - -0.478315455674609480, - 0.878096359977777130, -0.478483837338083970, 0.878004595709069080, - -0.478652201409075500, - 0.877912799158641840, -0.478820547881393890, 0.877820970329870500, - -0.478988876748849490, - 0.877729109226131570, -0.479157188005253310, 0.877637215850802230, - -0.479325481644417070, - 0.877545290207261350, -0.479493757660153010, 0.877453332298888560, - -0.479662016046274180, - 0.877361342129065140, -0.479830256796594190, 0.877269319701173170, - -0.479998479904927280, - 0.877177265018595940, -0.480166685365088390, 0.877085178084718420, - -0.480334873170893020, - 0.876993058902925890, -0.480503043316157510, 0.876900907476605650, - -0.480671195794698640, - 0.876808723809145650, -0.480839330600333960, 0.876716507903935400, - -0.481007447726881590, - 0.876624259764365310, -0.481175547168160300, 0.876531979393827100, - -0.481343628917989710, - 0.876439666795713610, -0.481511692970189860, 0.876347321973419020, - -0.481679739318581490, - 0.876254944930338510, -0.481847767956986030, 0.876162535669868460, - -0.482015778879225590, - 0.876070094195406600, -0.482183772079122720, 0.875977620510351770, - -0.482351747550500980, - 0.875885114618103810, -0.482519705287184350, 0.875792576522063880, - -0.482687645282997460, - 0.875700006225634600, -0.482855567531765670, 0.875607403732219350, - -0.483023472027314880, - 0.875514769045222850, -0.483191358763471860, 0.875422102168050940, - -0.483359227734063810, - 0.875329403104110890, -0.483527078932918740, 0.875236671856810870, - -0.483694912353865140, - 0.875143908429560360, -0.483862727990732270, 0.875051112825769970, - -0.484030525837350010, - 0.874958285048851650, -0.484198305887549030, 0.874865425102218320, - -0.484366068135160420, - 0.874772532989284150, -0.484533812574016180, 0.874679608713464510, - -0.484701539197948670, - 0.874586652278176110, -0.484869248000791060, 0.874493663686836560, - -0.485036938976377290, - 0.874400642942864790, -0.485204612118541820, 0.874307590049680950, - -0.485372267421119770, - 0.874214505010706300, -0.485539904877946960, 0.874121387829363330, - -0.485707524482859750, - 0.874028238509075740, -0.485875126229695250, 0.873935057053268240, - -0.486042710112291330, - 0.873841843465366860, -0.486210276124486420, 0.873748597748798870, - -0.486377824260119440, - 0.873655319906992630, -0.486545354513030270, 0.873562009943377850, - -0.486712866877059170, - 0.873468667861384880, -0.486880361346047340, 0.873375293664446000, - -0.487047837913836380, - 0.873281887355994210, -0.487215296574268760, 0.873188448939463790, - -0.487382737321187360, - 0.873094978418290090, -0.487550160148436000, 0.873001475795909920, - -0.487717565049858800, - 0.872907941075761080, -0.487884952019301040, 0.872814374261282390, - -0.488052321050608250, - 0.872720775355914300, -0.488219672137626790, 0.872627144363097960, - -0.488387005274203530, - 0.872533481286276170, -0.488554320454186180, 0.872439786128892280, - -0.488721617671423080, - 0.872346058894391540, -0.488888896919763170, 0.872252299586219860, - -0.489056158193056030, - 0.872158508207824480, -0.489223401485151980, 0.872064684762653860, - -0.489390626789901920, - 0.871970829254157810, -0.489557834101157440, 0.871876941685786890, - -0.489725023412770910, - 0.871783022060993120, -0.489892194718595190, 0.871689070383229740, - -0.490059348012483850, - 0.871595086655950980, -0.490226483288291160, 0.871501070882612530, - -0.490393600539871970, - 0.871407023066670950, -0.490560699761082020, 0.871312943211584030, - -0.490727780945777400, - 0.871218831320811020, -0.490894844087815090, 0.871124687397811900, - -0.491061889181052650, - 0.871030511446048260, -0.491228916219348280, 0.870936303468982760, - -0.491395925196560780, - 0.870842063470078980, -0.491562916106549900, 0.870747791452801790, - -0.491729888943175760, - 0.870653487420617430, -0.491896843700299290, 0.870559151376993250, - -0.492063780371782000, - 0.870464783325397670, -0.492230698951486020, 0.870370383269300270, - -0.492397599433274380, - 0.870275951212171940, -0.492564481811010590, 0.870181487157484560, - -0.492731346078558840, - 0.870086991108711460, -0.492898192229784040, 0.869992463069326870, - -0.493065020258551700, - 0.869897903042806340, -0.493231830158727900, 0.869803311032626650, - -0.493398621924179770, - 0.869708687042265670, -0.493565395548774770, 0.869614031075202300, - -0.493732151026381020, - 0.869519343134916860, -0.493898888350867480, 0.869424623224890890, - -0.494065607516103570, - 0.869329871348606840, -0.494232308515959670, 0.869235087509548370, - -0.494398991344306650, - 0.869140271711200560, -0.494565655995015950, 0.869045423957049530, - -0.494732302461959870, - 0.868950544250582380, -0.494898930739011260, 0.868855632595287860, - -0.495065540820043560, - 0.868760688994655310, -0.495232132698931180, 0.868665713452175690, - -0.495398706369549020, - 0.868570705971340900, -0.495565261825772540, 0.868475666555644120, - -0.495731799061477960, - 0.868380595208579800, -0.495898318070542190, 0.868285491933643350, - -0.496064818846842890, - 0.868190356734331310, -0.496231301384258250, 0.868095189614141670, - -0.496397765676667160, - 0.867999990576573510, -0.496564211717949290, 0.867904759625126920, - -0.496730639501984760, - 0.867809496763303320, -0.496897049022654470, 0.867714201994605140, - -0.497063440273840250, - 0.867618875322536230, -0.497229813249424220, 0.867523516750601460, - -0.497396167943289280, - 0.867428126282306920, -0.497562504349319150, 0.867332703921159800, - -0.497728822461397940, - 0.867237249670668400, -0.497895122273410870, 0.867141763534342470, - -0.498061403779243410, - 0.867046245515692650, -0.498227666972781870, 0.866950695618230900, - -0.498393911847913210, - 0.866855113845470430, -0.498560138398525140, 0.866759500200925400, - -0.498726346618505900, - 0.866663854688111130, -0.498892536501744590, 0.866568177310544470, - -0.499058708042130870, - 0.866472468071743050, -0.499224861233555080, 0.866376726975225830, - -0.499390996069908170, - 0.866280954024512990, -0.499557112545081840, 0.866185149223125840, - -0.499723210652968540, - 0.866089312574586770, -0.499889290387461330, 0.865993444082419520, - -0.500055351742453860, - 0.865897543750148820, -0.500221394711840680, 0.865801611581300760, - -0.500387419289516580, - 0.865705647579402380, -0.500553425469377420, 0.865609651747981990, - -0.500719413245319880, - 0.865513624090569090, -0.500885382611240710, 0.865417564610694410, - -0.501051333561038040, - 0.865321473311889800, -0.501217266088609950, 0.865225350197688200, - -0.501383180187855770, - 0.865129195271623800, -0.501549075852675390, 0.865033008537231860, - -0.501714953076969120, - 0.864936789998049020, -0.501880811854638290, 0.864840539657612870, - -0.502046652179584660, - 0.864744257519462380, -0.502212474045710790, 0.864647943587137480, - -0.502378277446919760, - 0.864551597864179340, -0.502544062377115690, 0.864455220354130360, - -0.502709828830202990, - 0.864358811060534030, -0.502875576800086990, 0.864262369986934950, - -0.503041306280673450, - 0.864165897136879300, -0.503207017265868920, 0.864069392513913790, - -0.503372709749581040, - 0.863972856121586810, -0.503538383725717580, 0.863876287963447510, - -0.503704039188187070, - 0.863779688043046720, -0.503869676130898950, 0.863683056363935830, - -0.504035294547763190, - 0.863586392929668100, -0.504200894432690340, 0.863489697743797140, - -0.504366475779592040, - 0.863392970809878420, -0.504532038582380270, 0.863296212131468230, - -0.504697582834967570, - 0.863199421712124160, -0.504863108531267590, 0.863102599555404910, - -0.505028615665194080, - 0.863005745664870320, -0.505194104230662240, 0.862908860044081400, - -0.505359574221587280, - 0.862811942696600330, -0.505525025631885390, 0.862714993625990690, - -0.505690458455473450, - 0.862618012835816740, -0.505855872686268860, 0.862521000329644520, - -0.506021268318189720, - 0.862423956111040610, -0.506186645345155230, 0.862326880183573060, - -0.506352003761084800, - 0.862229772550811240, -0.506517343559898530, 0.862132633216325380, - -0.506682664735517600, - 0.862035462183687210, -0.506847967281863210, 0.861938259456469290, - -0.507013251192858230, - 0.861841025038245330, -0.507178516462425180, 0.861743758932590700, - -0.507343763084487920, - 0.861646461143081300, -0.507508991052970870, 0.861549131673294720, - -0.507674200361798890, - 0.861451770526809320, -0.507839391004897720, 0.861354377707204910, - -0.508004562976194010, - 0.861256953218062170, -0.508169716269614600, 0.861159497062963350, - -0.508334850879087360, - 0.861062009245491480, -0.508499966798540930, 0.860964489769231010, - -0.508665064021904030, - 0.860866938637767310, -0.508830142543106990, 0.860769355854687170, - -0.508995202356080090, - 0.860671741423578380, -0.509160243454754640, 0.860574095348029980, - -0.509325265833062480, - 0.860476417631632070, -0.509490269484936360, 0.860378708277976130, - -0.509655254404309250, - 0.860280967290654510, -0.509820220585115450, 0.860183194673260990, - -0.509985168021289460, - 0.860085390429390140, -0.510150096706766810, 0.859987554562638200, - -0.510315006635483240, - 0.859889687076602290, -0.510479897801375700, 0.859791787974880650, - -0.510644770198381610, - 0.859693857261072610, -0.510809623820439040, 0.859595894938779080, - -0.510974458661486830, - 0.859497901011601730, -0.511139274715464390, 0.859399875483143450, - -0.511304071976312000, - 0.859301818357008470, -0.511468850437970300, 0.859203729636801920, - -0.511633610094381240, - 0.859105609326130450, -0.511798350939486890, 0.859007457428601520, - -0.511963072967230200, - 0.858909273947823900, -0.512127776171554690, 0.858811058887407610, - -0.512292460546404870, - 0.858712812250963520, -0.512457126085725690, 0.858614534042104190, - -0.512621772783462990, - 0.858516224264442740, -0.512786400633562960, 0.858417882921593930, - -0.512951009629972980, - 0.858319510017173440, -0.513115599766640560, 0.858221105554798250, - -0.513280171037514220, - 0.858122669538086140, -0.513444723436543460, 0.858024201970656540, - -0.513609256957677780, - 0.857925702856129790, -0.513773771594868030, 0.857827172198127430, - -0.513938267342065380, - 0.857728610000272120, -0.514102744193221660, 0.857630016266187620, - -0.514267202142289710, - 0.857531390999499150, -0.514431641183222820, 0.857432734203832700, - -0.514596061309975040, - 0.857334045882815590, -0.514760462516501200, 0.857235326040076460, - -0.514924844796756490, - 0.857136574679244980, -0.515089208144697160, 0.857037791803951680, - -0.515253552554280180, - 0.856938977417828760, -0.515417878019462930, 0.856840131524509220, - -0.515582184534203790, - 0.856741254127627470, -0.515746472092461380, 0.856642345230818840, - -0.515910740688195650, - 0.856543404837719960, -0.516074990315366630, 0.856444432951968590, - -0.516239220967935510, - 0.856345429577203610, -0.516403432639863990, 0.856246394717065210, - -0.516567625325114350, - 0.856147328375194470, -0.516731799017649870, 0.856048230555233940, - -0.516895953711434150, - 0.855949101260826910, -0.517060089400431910, 0.855849940495618240, - -0.517224206078608310, - 0.855750748263253920, -0.517388303739929060, 0.855651524567380690, - -0.517552382378360880, - 0.855552269411646860, -0.517716441987871150, 0.855452982799701830, - -0.517880482562427690, - 0.855353664735196030, -0.518044504095999340, 0.855254315221780970, - -0.518208506582555460, - 0.855154934263109620, -0.518372490016066110, 0.855055521862835950, - -0.518536454390502220, - 0.854956078024614930, -0.518700399699834950, 0.854856602752102850, - -0.518864325938036890, - 0.854757096048957220, -0.519028233099080860, 0.854657557918836460, - -0.519192121176940250, - 0.854557988365400530, -0.519355990165589640, 0.854458387392310170, - -0.519519840059003760, - 0.854358755003227440, -0.519683670851158410, 0.854259091201815530, - -0.519847482536030190, - 0.854159395991738850, -0.520011275107596040, 0.854059669376662780, - -0.520175048559833760, - 0.853959911360254180, -0.520338802886721960, 0.853860121946180770, - -0.520502538082239670, - 0.853760301138111410, -0.520666254140367160, 0.853660448939716380, - -0.520829951055084670, - 0.853560565354666840, -0.520993628820373920, 0.853460650386635320, - -0.521157287430216610, - 0.853360704039295430, -0.521320926878595660, 0.853260726316321880, - -0.521484547159494330, - 0.853160717221390420, -0.521648148266897090, 0.853060676758178320, - -0.521811730194788550, - 0.852960604930363630, -0.521975292937154390, 0.852860501741625750, - -0.522138836487980760, - 0.852760367195645300, -0.522302360841254590, 0.852660201296103760, - -0.522465865990963780, - 0.852560004046684080, -0.522629351931096610, 0.852459775451070100, - -0.522792818655642090, - 0.852359515512947090, -0.522956266158590140, 0.852259224236001090, - -0.523119694433931250, - 0.852158901623919830, -0.523283103475656430, 0.852058547680391690, - -0.523446493277757830, - 0.851958162409106380, -0.523609863834227920, 0.851857745813754840, - -0.523773215139060170, - 0.851757297898029120, -0.523936547186248600, 0.851656818665622370, - -0.524099859969787700, - 0.851556308120228980, -0.524263153483673360, 0.851455766265544310, - -0.524426427721901400, - 0.851355193105265200, -0.524589682678468950, 0.851254588643089120, - -0.524752918347373360, - 0.851153952882715340, -0.524916134722613000, 0.851053285827843790, - -0.525079331798186780, - 0.850952587482175730, -0.525242509568094710, 0.850851857849413530, - -0.525405668026336930, - 0.850751096933260790, -0.525568807166914680, 0.850650304737422090, - -0.525731926983829760, - 0.850549481265603480, -0.525895027471084630, 0.850448626521511760, - -0.526058108622682760, - 0.850347740508854980, -0.526221170432628060, 0.850246823231342710, - -0.526384212894925100, - 0.850145874692685210, -0.526547236003579440, 0.850044894896594180, - -0.526710239752597010, - 0.849943883846782210, -0.526873224135984590, 0.849842841546963320, - -0.527036189147750080, - 0.849741768000852550, -0.527199134781901280, 0.849640663212165910, - -0.527362061032447540, - 0.849539527184620890, -0.527524967893398200, 0.849438359921936060, - -0.527687855358763720, - 0.849337161427830780, -0.527850723422555230, 0.849235931706025960, - -0.528013572078784630, - 0.849134670760243630, -0.528176401321464370, 0.849033378594206800, - -0.528339211144607690, - 0.848932055211639610, -0.528502001542228480, 0.848830700616267530, - -0.528664772508341320, - 0.848729314811817130, -0.528827524036961870, 0.848627897802015860, - -0.528990256122106040, - 0.848526449590592650, -0.529152968757790610, 0.848424970181277600, - -0.529315661938033260, - 0.848323459577801640, -0.529478335656851980, 0.848221917783896990, - -0.529640989908265910, - 0.848120344803297230, -0.529803624686294610, 0.848018740639736810, - -0.529966239984958620, - 0.847917105296951410, -0.530128835798278960, 0.847815438778677930, - -0.530291412120277310, - 0.847713741088654380, -0.530453968944976320, 0.847612012230619660, - -0.530616506266399330, - 0.847510252208314330, -0.530779024078570140, 0.847408461025479730, - -0.530941522375513620, - 0.847306638685858320, -0.531104001151255000, 0.847204785193194090, - -0.531266460399820390, - 0.847102900551231500, -0.531428900115236800, 0.847000984763716880, - -0.531591320291531670, - 0.846899037834397240, -0.531753720922733320, 0.846797059767020910, - -0.531916102002870650, - 0.846695050565337450, -0.532078463525973540, 0.846593010233097190, - -0.532240805486072220, - 0.846490938774052130, -0.532403127877197900, 0.846388836191954930, - -0.532565430693382580, - 0.846286702490559710, -0.532727713928658810, 0.846184537673621560, - -0.532889977577059800, - 0.846082341744897050, -0.533052221632619450, 0.845980114708143270, - -0.533214446089372960, - 0.845877856567119000, -0.533376650941355330, 0.845775567325584010, - -0.533538836182603120, - 0.845673246987299070, -0.533701001807152960, 0.845570895556026270, - -0.533863147809042650, - 0.845468513035528830, -0.534025274182310380, 0.845366099429570970, - -0.534187380920995380, - 0.845263654741918220, -0.534349468019137520, 0.845161178976337140, - -0.534511535470777120, - 0.845058672136595470, -0.534673583269955510, 0.844956134226462210, - -0.534835611410714560, - 0.844853565249707120, -0.534997619887097150, 0.844750965210101510, - -0.535159608693146600, - 0.844648334111417820, -0.535321577822907120, 0.844545671957429240, - -0.535483527270423370, - 0.844442978751910660, -0.535645457029741090, 0.844340254498637590, - -0.535807367094906390, - 0.844237499201387020, -0.535969257459966710, 0.844134712863936930, - -0.536131128118969460, - 0.844031895490066410, -0.536292979065963180, 0.843929047083555870, - -0.536454810294997090, - 0.843826167648186740, -0.536616621800121040, 0.843723257187741660, - -0.536778413575385920, - 0.843620315706004150, -0.536940185614842910, 0.843517343206759200, - -0.537101937912544130, - 0.843414339693792760, -0.537263670462542530, 0.843311305170892140, - -0.537425383258891550, - 0.843208239641845440, -0.537587076295645390, 0.843105143110442160, - -0.537748749566859360, - 0.843002015580472940, -0.537910403066588880, 0.842898857055729310, - -0.538072036788890600, - 0.842795667540004120, -0.538233650727821700, 0.842692447037091670, - -0.538395244877439950, - 0.842589195550786710, -0.538556819231804100, 0.842485913084885630, - -0.538718373784973560, - 0.842382599643185850, -0.538879908531008420, 0.842279255229485990, - -0.539041423463969440, - 0.842175879847585570, -0.539202918577918240, 0.842072473501285560, - -0.539364393866917040, - 0.841969036194387680, -0.539525849325028890, 0.841865567930695340, - -0.539687284946317570, - 0.841762068714012490, -0.539848700724847590, 0.841658538548144760, - -0.540010096654684020, - 0.841554977436898440, -0.540171472729892850, 0.841451385384081260, - -0.540332828944540710, - 0.841347762393501950, -0.540494165292695230, 0.841244108468970580, - -0.540655481768424150, - 0.841140423614298080, -0.540816778365796670, 0.841036707833296650, - -0.540978055078882080, - 0.840932961129779780, -0.541139311901750800, 0.840829183507561640, - -0.541300548828474120, - 0.840725374970458070, -0.541461765853123440, 0.840621535522285690, - -0.541622962969771530, - 0.840517665166862550, -0.541784140172491550, 0.840413763908007480, - -0.541945297455357360, - 0.840309831749540770, -0.542106434812443920, 0.840205868695283580, - -0.542267552237826520, - 0.840101874749058400, -0.542428649725581250, 0.839997849914688840, - -0.542589727269785270, - 0.839893794195999520, -0.542750784864515890, 0.839789707596816370, - -0.542911822503851730, - 0.839685590120966110, -0.543072840181871740, 0.839581441772277120, - -0.543233837892655890, - 0.839477262554578550, -0.543394815630284800, 0.839373052471700690, - -0.543555773388839540, - 0.839268811527475230, -0.543716711162402280, 0.839164539725734680, - -0.543877628945055980, - 0.839060237070312740, -0.544038526730883820, 0.838955903565044460, - -0.544199404513970310, - 0.838851539213765760, -0.544360262288400400, 0.838747144020313920, - -0.544521100048259600, - 0.838642717988527300, -0.544681917787634530, 0.838538261122245280, - -0.544842715500612360, - 0.838433773425308340, -0.545003493181281160, 0.838329254901558300, - -0.545164250823729320, - 0.838224705554838080, -0.545324988422046460, 0.838120125388991500, - -0.545485705970322530, - 0.838015514407863820, -0.545646403462648590, 0.837910872615301170, - -0.545807080893116140, - 0.837806200015150940, -0.545967738255817570, 0.837701496611261700, - -0.546128375544845950, - 0.837596762407483040, -0.546288992754295210, 0.837491997407665890, - -0.546449589878259650, - 0.837387201615661940, -0.546610166910834860, 0.837282375035324320, - -0.546770723846116800, - 0.837177517670507300, -0.546931260678202190, 0.837072629525066000, - -0.547091777401188530, - 0.836967710602857020, -0.547252274009174090, 0.836862760907737920, - -0.547412750496257930, - 0.836757780443567190, -0.547573206856539760, 0.836652769214204950, - -0.547733643084120090, - 0.836547727223512010, -0.547894059173100190, 0.836442654475350380, - -0.548054455117581880, - 0.836337550973583530, -0.548214830911667780, 0.836232416722075600, - -0.548375186549461600, - 0.836127251724692270, -0.548535522025067390, 0.836022055985299880, - -0.548695837332590090, - 0.835916829507766360, -0.548856132466135290, 0.835811572295960700, - -0.549016407419809390, - 0.835706284353752600, -0.549176662187719660, 0.835600965685013410, - -0.549336896763974010, - 0.835495616293615350, -0.549497111142680960, 0.835390236183431890, - -0.549657305317949870, - 0.835284825358337370, -0.549817479283890910, 0.835179383822207690, - -0.549977633034614890, - 0.835073911578919410, -0.550137766564233630, 0.834968408632350450, - -0.550297879866859190, - 0.834862874986380010, -0.550457972936604810, 0.834757310644888230, - -0.550618045767584330, - 0.834651715611756440, -0.550778098353912120, 0.834546089890866870, - -0.550938130689703880, - 0.834440433486103190, -0.551098142769075430, 0.834334746401350080, - -0.551258134586143590, - 0.834229028640493420, -0.551418106135026060, 0.834123280207420100, - -0.551578057409841000, - 0.834017501106018130, -0.551737988404707340, 0.833911691340176840, - -0.551897899113745210, - 0.833805850913786340, -0.552057789531074980, 0.833699979830738290, - -0.552217659650817930, - 0.833594078094925140, -0.552377509467096070, 0.833488145710240770, - -0.552537338974032120, - 0.833382182680579730, -0.552697148165749770, 0.833276189009838240, - -0.552856937036373290, - 0.833170164701913190, -0.553016705580027470, 0.833064109760702890, - -0.553176453790838350, - 0.832958024190106670, -0.553336181662932300, 0.832851907994025090, - -0.553495889190436570, - 0.832745761176359460, -0.553655576367479310, 0.832639583741012770, - -0.553815243188189090, - 0.832533375691888680, -0.553974889646695500, 0.832427137032892280, - -0.554134515737128910, - 0.832320867767929680, -0.554294121453620000, 0.832214567900907980, - -0.554453706790300930, - 0.832108237435735590, -0.554613271741304040, 0.832001876376321950, - -0.554772816300762470, - 0.831895484726577590, -0.554932340462810370, 0.831789062490414400, - -0.555091844221582420, - 0.831682609671745120, -0.555251327571213980, 0.831576126274483740, - -0.555410790505841630, - 0.831469612302545240, -0.555570233019602180, 0.831363067759845920, - -0.555729655106633410, - 0.831256492650303210, -0.555889056761073810, 0.831149886977835540, - -0.556048437977062600, - 0.831043250746362320, -0.556207798748739930, 0.830936583959804410, - -0.556367139070246370, - 0.830829886622083570, -0.556526458935723610, 0.830723158737122880, - -0.556685758339313890, - 0.830616400308846310, -0.556845037275160100, 0.830509611341179070, - -0.557004295737405950, - 0.830402791838047550, -0.557163533720196220, 0.830295941803379070, - -0.557322751217676160, - 0.830189061241102370, -0.557481948223991550, 0.830082150155146970, - -0.557641124733289420, - 0.829975208549443950, -0.557800280739716990, 0.829868236427924840, - -0.557959416237422960, - 0.829761233794523050, -0.558118531220556100, 0.829654200653172640, - -0.558277625683266330, - 0.829547137007808910, -0.558436699619704100, 0.829440042862368170, - -0.558595753024020760, - 0.829332918220788250, -0.558754785890368310, 0.829225763087007570, - -0.558913798212899770, - 0.829118577464965980, -0.559072789985768480, 0.829011361358604430, - -0.559231761203128900, - 0.828904114771864870, -0.559390711859136140, 0.828796837708690610, - -0.559549641947945760, - 0.828689530173025820, -0.559708551463714680, 0.828582192168815790, - -0.559867440400600210, - 0.828474823700007130, -0.560026308752760380, 0.828367424770547480, - -0.560185156514354080, - 0.828259995384385660, -0.560343983679540860, 0.828152535545471410, - -0.560502790242481060, - 0.828045045257755800, -0.560661576197336030, 0.827937524525190870, - -0.560820341538267430, - 0.827829973351729920, -0.560979086259438150, 0.827722391741327220, - -0.561137810355011420, - 0.827614779697938400, -0.561296513819151470, 0.827507137225519830, - -0.561455196646023280, - 0.827399464328029470, -0.561613858829792420, 0.827291761009425810, - -0.561772500364625340, - 0.827184027273669130, -0.561931121244689470, 0.827076263124720270, - -0.562089721464152480, - 0.826968468566541600, -0.562248301017183150, 0.826860643603096190, - -0.562406859897951140, - 0.826752788238348520, -0.562565398100626560, 0.826644902476264320, - -0.562723915619380400, - 0.826536986320809960, -0.562882412448384440, 0.826429039775953500, - -0.563040888581811230, - 0.826321062845663530, -0.563199344013834090, 0.826213055533910220, - -0.563357778738627020, - 0.826105017844664610, -0.563516192750364800, 0.825996949781899080, - -0.563674586043223070, - 0.825888851349586780, -0.563832958611378170, 0.825780722551702430, - -0.563991310449006970, - 0.825672563392221390, -0.564149641550287680, 0.825564373875120490, - -0.564307951909398640, - 0.825456154004377550, -0.564466241520519500, 0.825347903783971380, - -0.564624510377830120, - 0.825239623217882250, -0.564782758475511400, 0.825131312310091070, - -0.564940985807745210, - 0.825022971064580220, -0.565099192368713980, 0.824914599485333190, - -0.565257378152600800, - 0.824806197576334330, -0.565415543153589660, 0.824697765341569470, - -0.565573687365865330, - 0.824589302785025290, -0.565731810783613120, 0.824480809910689500, - -0.565889913401019570, - 0.824372286722551250, -0.566047995212271450, 0.824263733224600560, - -0.566206056211556730, - 0.824155149420828570, -0.566364096393063840, 0.824046535315227760, - -0.566522115750982100, - 0.823937890911791370, -0.566680114279501600, 0.823829216214513990, - -0.566838091972813320, - 0.823720511227391430, -0.566996048825108680, 0.823611775954420260, - -0.567153984830580100, - 0.823503010399598500, -0.567311899983420800, 0.823394214566925080, - -0.567469794277824510, - 0.823285388460400110, -0.567627667707986230, 0.823176532084024860, - -0.567785520268101140, - 0.823067645441801670, -0.567943351952365560, 0.822958728537734000, - -0.568101162754976460, - 0.822849781375826430, -0.568258952670131490, 0.822740803960084420, - -0.568416721692029280, - 0.822631796294514990, -0.568574469814869140, 0.822522758383125940, - -0.568732197032851050, - 0.822413690229926390, -0.568889903340175860, 0.822304591838926350, - -0.569047588731045110, - 0.822195463214137170, -0.569205253199661200, 0.822086304359571090, - -0.569362896740227220, - 0.821977115279241550, -0.569520519346947140, 0.821867895977163250, - -0.569678121014025600, - 0.821758646457351750, -0.569835701735668000, 0.821649366723823940, - -0.569993261506080540, - 0.821540056780597610, -0.570150800319470300, 0.821430716631691870, - -0.570308318170044900, - 0.821321346281126740, -0.570465815052012990, 0.821211945732923550, - -0.570623290959583750, - 0.821102514991104650, -0.570780745886967260, 0.820993054059693580, - -0.570938179828374360, - 0.820883562942714580, -0.571095592778016690, 0.820774041644193650, - -0.571252984730106660, - 0.820664490168157460, -0.571410355678857230, 0.820554908518633890, - -0.571567705618482580, - 0.820445296699652050, -0.571725034543197120, 0.820335654715241840, - -0.571882342447216590, - 0.820225982569434690, -0.572039629324757050, 0.820116280266262820, - -0.572196895170035580, - 0.820006547809759680, -0.572354139977269920, 0.819896785203959810, - -0.572511363740678790, - 0.819786992452898990, -0.572668566454481160, 0.819677169560613870, - -0.572825748112897550, - 0.819567316531142230, -0.572982908710148560, 0.819457433368523280, - -0.573140048240455950, - 0.819347520076796900, -0.573297166698042200, 0.819237576660004520, - -0.573454264077130400, - 0.819127603122188240, -0.573611340371944610, 0.819017599467391500, - -0.573768395576709560, - 0.818907565699658950, -0.573925429685650750, 0.818797501823036010, - -0.574082442692994470, - 0.818687407841569680, -0.574239434592967890, 0.818577283759307610, - -0.574396405379798750, - 0.818467129580298660, -0.574553355047715760, 0.818356945308593150, - -0.574710283590948330, - 0.818246730948242070, -0.574867191003726740, 0.818136486503297730, - -0.575024077280281710, - 0.818026211977813440, -0.575180942414845080, 0.817915907375843850, - -0.575337786401649450, - 0.817805572701444270, -0.575494609234928120, 0.817695207958671680, - -0.575651410908915140, - 0.817584813151583710, -0.575808191417845340, 0.817474388284239240, - -0.575964950755954220, - 0.817363933360698460, -0.576121688917478280, 0.817253448385022340, - -0.576278405896654910, - 0.817142933361272970, -0.576435101687721830, 0.817032388293513880, - -0.576591776284917760, - 0.816921813185809480, -0.576748429682482410, 0.816811208042225290, - -0.576905061874655960, - 0.816700572866827850, -0.577061672855679440, 0.816589907663684890, - -0.577218262619794920, - 0.816479212436865390, -0.577374831161244880, 0.816368487190439200, - -0.577531378474272720, - 0.816257731928477390, -0.577687904553122800, 0.816146946655052270, - -0.577844409392039850, - 0.816036131374236810, -0.578000892985269910, 0.815925286090105510, - -0.578157355327059360, - 0.815814410806733780, -0.578313796411655590, 0.815703505528198260, - -0.578470216233306630, - 0.815592570258576790, -0.578626614786261430, 0.815481605001947770, - -0.578782992064769690, - 0.815370609762391290, -0.578939348063081780, 0.815259584543988280, - -0.579095682775449090, - 0.815148529350820830, -0.579251996196123550, 0.815037444186972220, - -0.579408288319357870, - 0.814926329056526620, -0.579564559139405630, 0.814815183963569440, - -0.579720808650521450, - 0.814704008912187080, -0.579877036846960350, 0.814592803906467270, - -0.580033243722978150, - 0.814481568950498610, -0.580189429272831680, 0.814370304048371070, - -0.580345593490778300, - 0.814259009204175270, -0.580501736371076490, 0.814147684422003360, - -0.580657857907985300, - 0.814036329705948410, -0.580813958095764530, 0.813924945060104600, - -0.580970036928674770, - 0.813813530488567190, -0.581126094400977620, 0.813702085995432700, - -0.581282130506935000, - 0.813590611584798510, -0.581438145240810170, 0.813479107260763220, - -0.581594138596866930, - 0.813367573027426570, -0.581750110569369650, 0.813256008888889380, - -0.581906061152583810, - 0.813144414849253590, -0.582061990340775440, 0.813032790912622040, - -0.582217898128211670, - 0.812921137083098770, -0.582373784509160110, 0.812809453364789270, - -0.582529649477889320, - 0.812697739761799490, -0.582685493028668460, 0.812585996278237130, - -0.582841315155767650, - 0.812474222918210480, -0.582997115853457700, 0.812362419685829230, - -0.583152895116010430, - 0.812250586585203880, -0.583308652937698290, 0.812138723620446480, - -0.583464389312794320, - 0.812026830795669730, -0.583620104235572760, 0.811914908114987790, - -0.583775797700308070, - 0.811802955582515470, -0.583931469701276180, 0.811690973202369050, - -0.584087120232753440, - 0.811578960978665890, -0.584242749289016980, 0.811466918915524250, - -0.584398356864344600, - 0.811354847017063730, -0.584553942953015330, 0.811242745287404810, - -0.584709507549308390, - 0.811130613730669190, -0.584865050647504490, 0.811018452350979470, - -0.585020572241884530, - 0.810906261152459670, -0.585176072326730410, 0.810794040139234730, - -0.585331550896324940, - 0.810681789315430780, -0.585487007944951340, 0.810569508685174630, - -0.585642443466894420, - 0.810457198252594770, -0.585797857456438860, 0.810344858021820550, - -0.585953249907870570, - 0.810232487996982330, -0.586108620815476430, 0.810120088182211600, - -0.586263970173543590, - 0.810007658581641140, -0.586419297976360500, 0.809895199199404450, - -0.586574604218216170, - 0.809782710039636530, -0.586729888893400390, 0.809670191106473090, - -0.586885151996203950, - 0.809557642404051260, -0.587040393520917970, 0.809445063936509170, - -0.587195613461834800, - 0.809332455707985950, -0.587350811813247660, 0.809219817722621750, - -0.587505988569450020, - 0.809107149984558240, -0.587661143724736660, 0.808994452497937670, - -0.587816277273402910, - 0.808881725266903610, -0.587971389209745010, 0.808768968295600850, - -0.588126479528059850, - 0.808656181588174980, -0.588281548222645220, 0.808543365148773010, - -0.588436595287799790, - 0.808430518981542720, -0.588591620717822890, 0.808317643090633250, - -0.588746624507014540, - 0.808204737480194720, -0.588901606649675720, 0.808091802154378370, - -0.589056567140108460, - 0.807978837117336310, -0.589211505972614960, 0.807865842373222120, - -0.589366423141498790, - 0.807752817926190360, -0.589521318641063940, 0.807639763780396480, - -0.589676192465615420, - 0.807526679939997160, -0.589831044609458790, 0.807413566409150190, - -0.589985875066900920, - 0.807300423192014450, -0.590140683832248820, 0.807187250292749960, - -0.590295470899810830, - 0.807074047715517610, -0.590450236263895810, 0.806960815464479730, - -0.590604979918813330, - 0.806847553543799330, -0.590759701858874160, 0.806734261957640860, - -0.590914402078389520, - 0.806620940710169650, -0.591069080571671400, 0.806507589805552260, - -0.591223737333032910, - 0.806394209247956240, -0.591378372356787580, 0.806280799041550480, - -0.591532985637249990, - 0.806167359190504420, -0.591687577168735430, 0.806053889698989060, - -0.591842146945560140, - 0.805940390571176280, -0.591996694962040990, 0.805826861811239300, - -0.592151221212495530, - 0.805713303423352230, -0.592305725691242290, 0.805599715411690060, - -0.592460208392600830, - 0.805486097780429230, -0.592614669310891130, 0.805372450533747060, - -0.592769108440434070, - 0.805258773675822210, -0.592923525775551300, 0.805145067210834230, - -0.593077921310565470, - 0.805031331142963660, -0.593232295039799800, 0.804917565476392260, - -0.593386646957578480, - 0.804803770215302920, -0.593540977058226390, 0.804689945363879500, - -0.593695285336069190, - 0.804576090926307110, -0.593849571785433630, 0.804462206906771840, - -0.594003836400646690, - 0.804348293309460780, -0.594158079176036800, 0.804234350138562260, - -0.594312300105932830, - 0.804120377398265810, -0.594466499184664430, 0.804006375092761520, - -0.594620676406562240, - 0.803892343226241260, -0.594774831765957580, 0.803778281802897570, - -0.594928965257182420, - 0.803664190826924090, -0.595083076874569960, 0.803550070302515680, - -0.595237166612453850, - 0.803435920233868120, -0.595391234465168730, 0.803321740625178580, - -0.595545280427049790, - 0.803207531480644940, -0.595699304492433360, 0.803093292804466400, - -0.595853306655656280, - 0.802979024600843250, -0.596007286911056530, 0.802864726873976700, - -0.596161245252972540, - 0.802750399628069160, -0.596315181675743710, 0.802636042867324150, - -0.596469096173710360, - 0.802521656595946430, -0.596622988741213220, 0.802407240818141300, - -0.596776859372594390, - 0.802292795538115720, -0.596930708062196500, 0.802178320760077450, - -0.597084534804362740, - 0.802063816488235440, -0.597238339593437420, 0.801949282726799770, - -0.597392122423765710, - 0.801834719479981310, -0.597545883289693160, 0.801720126751992330, - -0.597699622185566830, - 0.801605504547046150, -0.597853339105733910, 0.801490852869356950, - -0.598007034044542700, - 0.801376171723140240, -0.598160706996342270, 0.801261461112612540, - -0.598314357955482600, - 0.801146721041991360, -0.598467986916314310, 0.801031951515495330, - -0.598621593873188920, - 0.800917152537344300, -0.598775178820458720, 0.800802324111759110, - -0.598928741752476900, - 0.800687466242961610, -0.599082282663597310, 0.800572578935174860, - -0.599235801548174570, - 0.800457662192622820, -0.599389298400564540, 0.800342716019530660, - -0.599542773215123390, - 0.800227740420124790, -0.599696225986208310, 0.800112735398632370, - -0.599849656708177250, - 0.799997700959281910, -0.600003065375388940, 0.799882637106302810, - -0.600156451982203240, - 0.799767543843925680, -0.600309816522980430, 0.799652421176382240, - -0.600463158992081580, - 0.799537269107905010, -0.600616479383868970, 0.799422087642728040, - -0.600769777692705230, - 0.799306876785086160, -0.600923053912954090, 0.799191636539215210, - -0.601076308038980160, - 0.799076366909352350, -0.601229540065148500, 0.798961067899735760, - -0.601382749985825420, - 0.798845739514604580, -0.601535937795377730, 0.798730381758199210, - -0.601689103488172950, - 0.798614994634760820, -0.601842247058580030, 0.798499578148532120, - -0.601995368500968020, - 0.798384132303756380, -0.602148467809707210, 0.798268657104678430, - -0.602301544979168550, - 0.798153152555543750, -0.602454600003723750, 0.798037618660599410, - -0.602607632877745440, - 0.797922055424093000, -0.602760643595607220, 0.797806462850273570, - -0.602913632151683030, - 0.797690840943391160, -0.603066598540348160, 0.797575189707696700, - -0.603219542755978440, - 0.797459509147442460, -0.603372464792950260, 0.797343799266881700, - -0.603525364645641550, - 0.797228060070268700, -0.603678242308430370, 0.797112291561858920, - -0.603831097775695880, - 0.796996493745908750, -0.603983931041818020, 0.796880666626675780, - -0.604136742101177520, - 0.796764810208418830, -0.604289530948155960, 0.796648924495397260, - -0.604442297577135860, - 0.796533009491872000, -0.604595041982500360, 0.796417065202104980, - -0.604747764158633410, - 0.796301091630359110, -0.604900464099919820, 0.796185088780898440, - -0.605053141800745320, - 0.796069056657987990, -0.605205797255496500, 0.795952995265893910, - -0.605358430458560530, - 0.795836904608883570, -0.605511041404325550, 0.795720784691225090, - -0.605663630087180380, - 0.795604635517188070, -0.605816196501514970, 0.795488457091042990, - -0.605968740641719680, - 0.795372249417061310, -0.606121262502186120, 0.795256012499515610, - -0.606273762077306430, - 0.795139746342679590, -0.606426239361473550, 0.795023450950828050, - -0.606578694349081290, - 0.794907126328237010, -0.606731127034524480, 0.794790772479183170, - -0.606883537412198470, - 0.794674389407944550, -0.607035925476499650, 0.794557977118800380, - -0.607188291221825160, - 0.794441535616030590, -0.607340634642572930, 0.794325064903916520, - -0.607492955733141550, - 0.794208564986740640, -0.607645254487930830, 0.794092035868785960, - -0.607797530901341140, - 0.793975477554337170, -0.607949784967773630, 0.793858890047679730, - -0.608102016681630440, - 0.793742273353100210, -0.608254226037314490, 0.793625627474886300, - -0.608406413029229150, - 0.793508952417326660, -0.608558577651779450, 0.793392248184711100, - -0.608710719899370310, - 0.793275514781330630, -0.608862839766408200, 0.793158752211477140, - -0.609014937247299830, - 0.793041960479443640, -0.609167012336453210, 0.792925139589524260, - -0.609319065028276820, - 0.792808289546014120, -0.609471095317180240, 0.792691410353209450, - -0.609623103197573730, - 0.792574502015407690, -0.609775088663868430, 0.792457564536907080, - -0.609927051710476120, - 0.792340597922007170, -0.610078992331809620, 0.792223602175008310, - -0.610230910522282620, - 0.792106577300212390, -0.610382806276309480, 0.791989523301921850, - -0.610534679588305320, - 0.791872440184440470, -0.610686530452686280, 0.791755327952073150, - -0.610838358863869170, - 0.791638186609125880, -0.610990164816271660, 0.791521016159905220, - -0.611141948304312570, - 0.791403816608719500, -0.611293709322410890, 0.791286587959877830, - -0.611445447864987000, - 0.791169330217690200, -0.611597163926461910, 0.791052043386467950, - -0.611748857501257290, - 0.790934727470523290, -0.611900528583796070, 0.790817382474169770, - -0.612052177168501470, - 0.790700008401721610, -0.612203803249797950, 0.790582605257494460, - -0.612355406822110650, - 0.790465173045804880, -0.612506987879865570, 0.790347711770970520, - -0.612658546417489290, - 0.790230221437310030, -0.612810082429409710, 0.790112702049143300, - -0.612961595910055170, - 0.789995153610791090, -0.613113086853854910, 0.789877576126575280, - -0.613264555255239040, - 0.789759969600819070, -0.613416001108638590, 0.789642334037846340, - -0.613567424408485330, - 0.789524669441982190, -0.613718825149211720, 0.789406975817552930, - -0.613870203325251330, - 0.789289253168885650, -0.614021558931038380, 0.789171501500308900, - -0.614172891961007990, - 0.789053720816151880, -0.614324202409595950, 0.788935911120745240, - -0.614475490271239040, - 0.788818072418420280, -0.614626755540375050, 0.788700204713509660, - -0.614777998211442080, - 0.788582308010347120, -0.614929218278879590, 0.788464382313267540, - -0.615080415737127460, - 0.788346427626606340, -0.615231590580626820, 0.788228443954700490, - -0.615382742803819220, - 0.788110431301888070, -0.615533872401147320, 0.787992389672507950, - -0.615684979367054570, - 0.787874319070900220, -0.615836063695985090, 0.787756219501406060, - -0.615987125382383760, - 0.787638090968367450, -0.616138164420696910, 0.787519933476127810, - -0.616289180805370980, - 0.787401747029031430, -0.616440174530853650, 0.787283531631423620, - -0.616591145591593110, - 0.787165287287651010, -0.616742093982038720, 0.787047014002060790, - -0.616893019696640680, - 0.786928711779001810, -0.617043922729849760, 0.786810380622823490, - -0.617194803076117630, - 0.786692020537876790, -0.617345660729896830, 0.786573631528513230, - -0.617496495685640910, - 0.786455213599085770, -0.617647307937803870, 0.786336766753948260, - -0.617798097480841020, - 0.786218290997455660, -0.617948864309208150, 0.786099786333963930, - -0.618099608417362000, - 0.785981252767830150, -0.618250329799760250, 0.785862690303412600, - -0.618401028450860980, - 0.785744098945070360, -0.618551704365123740, 0.785625478697163700, - -0.618702357537008530, - 0.785506829564053930, -0.618852987960976320, 0.785388151550103550, - -0.619003595631488660, - 0.785269444659675850, -0.619154180543008410, 0.785150708897135560, - -0.619304742689998690, - 0.785031944266848080, -0.619455282066924020, 0.784913150773180020, - -0.619605798668249270, - 0.784794328420499230, -0.619756292488440660, 0.784675477213174320, - -0.619906763521964720, - 0.784556597155575240, -0.620057211763289100, 0.784437688252072830, - -0.620207637206882430, - 0.784318750507038920, -0.620358039847213720, 0.784199783924846570, - -0.620508419678753360, - 0.784080788509869950, -0.620658776695972140, 0.783961764266484120, - -0.620809110893341900, - 0.783842711199065230, -0.620959422265335180, 0.783723629311990470, - -0.621109710806425630, - 0.783604518609638200, -0.621259976511087550, 0.783485379096387820, - -0.621410219373796150, - 0.783366210776619720, -0.621560439389027160, 0.783247013654715380, - -0.621710636551257690, - 0.783127787735057310, -0.621860810854965360, 0.783008533022029110, - -0.622010962294628600, - 0.782889249520015480, -0.622161090864726820, 0.782769937233402050, - -0.622311196559740320, - 0.782650596166575730, -0.622461279374149970, 0.782531226323924240, - -0.622611339302437730, - 0.782411827709836530, -0.622761376339086350, 0.782292400328702400, - -0.622911390478579460, - 0.782172944184913010, -0.623061381715401260, 0.782053459282860300, - -0.623211350044037270, - 0.781933945626937630, -0.623361295458973230, 0.781814403221538830, - -0.623511217954696440, - 0.781694832071059390, -0.623661117525694530, 0.781575232179895550, - -0.623810994166456130, - 0.781455603552444590, -0.623960847871470660, 0.781335946193104870, - -0.624110678635228510, - 0.781216260106276090, -0.624260486452220650, 0.781096545296358520, - -0.624410271316939270, - 0.780976801767753750, -0.624560033223877210, 0.780857029524864580, - -0.624709772167528100, - 0.780737228572094490, -0.624859488142386340, 0.780617398913848400, - -0.625009181142947460, - 0.780497540554531910, -0.625158851163707620, 0.780377653498552040, - -0.625308498199164010, - 0.780257737750316590, -0.625458122243814360, 0.780137793314234610, - -0.625607723292157410, - 0.780017820194715990, -0.625757301338692900, 0.779897818396172000, - -0.625906856377921090, - 0.779777787923014550, -0.626056388404343520, 0.779657728779656890, - -0.626205897412462130, - 0.779537640970513260, -0.626355383396779990, 0.779417524499998900, - -0.626504846351800810, - 0.779297379372530300, -0.626654286272029350, 0.779177205592524680, - -0.626803703151971200, - 0.779057003164400630, -0.626953096986132660, 0.778936772092577500, - -0.627102467769020900, - 0.778816512381475980, -0.627251815495144080, 0.778696224035517530, - -0.627401140159011050, - 0.778575907059125050, -0.627550441755131530, 0.778455561456721900, - -0.627699720278016240, - 0.778335187232733210, -0.627848975722176460, 0.778214784391584540, - -0.627998208082124700, - 0.778094352937702790, -0.628147417352374000, 0.777973892875516100, - -0.628296603527438320, - 0.777853404209453150, -0.628445766601832710, 0.777732886943944050, - -0.628594906570072550, - 0.777612341083420030, -0.628744023426674680, 0.777491766632313010, - -0.628893117166156480, - 0.777371163595056310, -0.629042187783036000, 0.777250531976084070, - -0.629191235271832290, - 0.777129871779831620, -0.629340259627065630, 0.777009183010735290, - -0.629489260843256630, - 0.776888465673232440, -0.629638238914926980, 0.776767719771761510, - -0.629787193836599200, - 0.776646945310762060, -0.629936125602796440, 0.776526142294674430, - -0.630085034208043180, - 0.776405310727940390, -0.630233919646864370, 0.776284450615002510, - -0.630382781913785940, - 0.776163561960304340, -0.630531621003334600, 0.776042644768290770, - -0.630680436910037940, - 0.775921699043407690, -0.630829229628424470, 0.775800724790101650, - -0.630977999153023550, - 0.775679722012820650, -0.631126745478365340, 0.775558690716013580, - -0.631275468598980760, - 0.775437630904130540, -0.631424168509401860, 0.775316542581622530, - -0.631572845204161020, - 0.775195425752941420, -0.631721498677792260, 0.775074280422540450, - -0.631870128924829850, - 0.774953106594873930, -0.632018735939809060, 0.774831904274396850, - -0.632167319717265920, - 0.774710673465565550, -0.632315880251737570, 0.774589414172837550, - -0.632464417537761840, - 0.774468126400670860, -0.632612931569877410, 0.774346810153525130, - -0.632761422342624000, - 0.774225465435860680, -0.632909889850541750, 0.774104092252139050, - -0.633058334088172140, - 0.773982690606822900, -0.633206755050057190, 0.773861260504375540, - -0.633355152730739950, - 0.773739801949261840, -0.633503527124764320, 0.773618314945947460, - -0.633651878226674900, - 0.773496799498899050, -0.633800206031017280, 0.773375255612584470, - -0.633948510532337810, - 0.773253683291472590, -0.634096791725183740, 0.773132082540033070, - -0.634245049604103330, - 0.773010453362736990, -0.634393284163645490, 0.772888795764056220, - -0.634541495398360020, - 0.772767109748463850, -0.634689683302797740, 0.772645395320433860, - -0.634837847871509990, - 0.772523652484441330, -0.634985989099049460, 0.772401881244962450, - -0.635134106979969190, - 0.772280081606474320, -0.635282201508823420, 0.772158253573455240, - -0.635430272680167160, - 0.772036397150384520, -0.635578320488556110, 0.771914512341742350, - -0.635726344928547070, - 0.771792599152010150, -0.635874345994697720, 0.771670657585670330, - -0.636022323681566300, - 0.771548687647206300, -0.636170277983712170, 0.771426689341102590, - -0.636318208895695460, - 0.771304662671844830, -0.636466116412077180, 0.771182607643919330, - -0.636614000527419120, - 0.771060524261813820, -0.636761861236284200, 0.770938412530016940, - -0.636909698533235870, - 0.770816272453018540, -0.637057512412838590, 0.770694104035309140, - -0.637205302869657600, - 0.770571907281380810, -0.637353069898259130, 0.770449682195725960, - -0.637500813493210190, - 0.770327428782838890, -0.637648533649078810, 0.770205147047214210, - -0.637796230360433540, - 0.770082836993347900, -0.637943903621844060, 0.769960498625737230, - -0.638091553427880820, - 0.769838131948879840, -0.638239179773115280, 0.769715736967275130, - -0.638386782652119570, - 0.769593313685422940, -0.638534362059466790, 0.769470862107824670, - -0.638681917989730730, - 0.769348382238982280, -0.638829450437486290, 0.769225874083399260, - -0.638976959397309140, - 0.769103337645579700, -0.639124444863775730, 0.768980772930028870, - -0.639271906831463510, - 0.768858179941253270, -0.639419345294950700, 0.768735558683760310, - -0.639566760248816310, - 0.768612909162058380, -0.639714151687640450, 0.768490231380656860, - -0.639861519606003900, - 0.768367525344066270, -0.640008863998488440, 0.768244791056798330, - -0.640156184859676510, - 0.768122028523365420, -0.640303482184151670, 0.767999237748281270, - -0.640450755966498140, - 0.767876418736060610, -0.640598006201301030, 0.767753571491219030, - -0.640745232883146440, - 0.767630696018273380, -0.640892436006621380, 0.767507792321741270, - -0.641039615566313390, - 0.767384860406141730, -0.641186771556811250, 0.767261900275994500, - -0.641333903972704290, - 0.767138911935820400, -0.641481012808583160, 0.767015895390141480, - -0.641628098059038750, - 0.766892850643480670, -0.641775159718663500, 0.766769777700361920, - -0.641922197782050170, - 0.766646676565310380, -0.642069212243792540, 0.766523547242852210, - -0.642216203098485370, - 0.766400389737514230, -0.642363170340724320, 0.766277204053824710, - -0.642510113965105710, - 0.766153990196312920, -0.642657033966226860, 0.766030748169509000, - -0.642803930338685990, - 0.765907477977944340, -0.642950803077082080, 0.765784179626150970, - -0.643097652176015110, - 0.765660853118662500, -0.643244477630085850, 0.765537498460013070, - -0.643391279433895850, - 0.765414115654738270, -0.643538057582047740, 0.765290704707374370, - -0.643684812069144850, - 0.765167265622458960, -0.643831542889791390, 0.765043798404530520, - -0.643978250038592660, - 0.764920303058128410, -0.644124933510154540, 0.764796779587793460, - -0.644271593299083790, - 0.764673227998067140, -0.644418229399988380, 0.764549648293492150, - -0.644564841807476640, - 0.764426040478612070, -0.644711430516158310, 0.764302404557971720, - -0.644857995520643710, - 0.764178740536116670, -0.645004536815543930, 0.764055048417593970, - -0.645151054395471160, - 0.763931328206951090, -0.645297548255038380, 0.763807579908737160, - -0.645444018388859230, - 0.763683803527501870, -0.645590464791548690, 0.763559999067796150, - -0.645736887457722290, - 0.763436166534172010, -0.645883286381996320, 0.763312305931182380, - -0.646029661558988330, - 0.763188417263381270, -0.646176012983316280, 0.763064500535323710, - -0.646322340649599480, - 0.762940555751565720, -0.646468644552457780, 0.762816582916664430, - -0.646614924686512050, - 0.762692582035177980, -0.646761181046383920, 0.762568553111665380, - -0.646907413626696020, - 0.762444496150687210, -0.647053622422071540, 0.762320411156804270, - -0.647199807427135230, - 0.762196298134578900, -0.647345968636512060, 0.762072157088574560, - -0.647492106044828100, - 0.761947988023355390, -0.647638219646710310, 0.761823790943486960, - -0.647784309436786440, - 0.761699565853535380, -0.647930375409685340, 0.761575312758068000, - -0.648076417560036530, - 0.761451031661653620, -0.648222435882470420, 0.761326722568861360, - -0.648368430371618290, - 0.761202385484261780, -0.648514401022112440, 0.761078020412426560, - -0.648660347828585840, - 0.760953627357928150, -0.648806270785672550, 0.760829206325340010, - -0.648952169888007300, - 0.760704757319236920, -0.649098045130225950, 0.760580280344194450, - -0.649243896506964900, - 0.760455775404789260, -0.649389724012861660, 0.760331242505599030, - -0.649535527642554730, - 0.760206681651202420, -0.649681307390683190, 0.760082092846179340, - -0.649827063251887100, - 0.759957476095110330, -0.649972795220807530, 0.759832831402577400, - -0.650118503292086200, - 0.759708158773163440, -0.650264187460365850, 0.759583458211452010, - -0.650409847720290310, - 0.759458729722028210, -0.650555484066503880, 0.759333973309477940, - -0.650701096493652040, - 0.759209188978388070, -0.650846684996380880, 0.759084376733346610, - -0.650992249569337660, - 0.758959536578942440, -0.651137790207170330, 0.758834668519765660, - -0.651283306904527740, - 0.758709772560407390, -0.651428799656059820, 0.758584848705459610, - -0.651574268456416970, - 0.758459896959515430, -0.651719713300250910, 0.758334917327168960, - -0.651865134182213920, - 0.758209909813015280, -0.652010531096959500, 0.758084874421650730, - -0.652155904039141590, - 0.757959811157672300, -0.652301253003415460, 0.757834720025678310, - -0.652446577984436730, - 0.757709601030268080, -0.652591878976862440, 0.757584454176041810, - -0.652737155975350310, - 0.757459279467600720, -0.652882408974558850, 0.757334076909547130, - -0.653027637969147530, - 0.757208846506484570, -0.653172842953776760, 0.757083588263017140, - -0.653318023923107670, - 0.756958302183750490, -0.653463180871802330, 0.756832988273290820, - -0.653608313794523890, - 0.756707646536245670, -0.653753422685936060, 0.756582276977223470, - -0.653898507540703780, - 0.756456879600833740, -0.654043568353492640, 0.756331454411686920, - -0.654188605118969040, - 0.756206001414394540, -0.654333617831800440, 0.756080520613569120, - -0.654478606486655350, - 0.755955012013824420, -0.654623571078202680, 0.755829475619774760, - -0.654768511601112600, - 0.755703911436035880, -0.654913428050056030, 0.755578319467224540, - -0.655058320419704910, - 0.755452699717958250, -0.655203188704731820, 0.755327052192855670, - -0.655348032899810470, - 0.755201376896536550, -0.655492852999615350, 0.755075673833621620, - -0.655637648998821820, - 0.754949943008732640, -0.655782420892106030, 0.754824184426492350, - -0.655927168674145360, - 0.754698398091524500, -0.656071892339617600, 0.754572584008453840, - -0.656216591883201920, - 0.754446742181906440, -0.656361267299578000, 0.754320872616508820, - -0.656505918583426550, - 0.754194975316889170, -0.656650545729428940, 0.754069050287676120, - -0.656795148732268070, - 0.753943097533499640, -0.656939727586627110, 0.753817117058990790, - -0.657084282287190180, - 0.753691108868781210, -0.657228812828642540, 0.753565072967504300, - -0.657373319205670210, - 0.753439009359793580, -0.657517801412960120, 0.753312918050284330, - -0.657662259445200070, - 0.753186799043612520, -0.657806693297078640, 0.753060652344415100, - -0.657951102963285520, - 0.752934477957330150, -0.658095488438511180, 0.752808275886996950, - -0.658239849717446870, - 0.752682046138055340, -0.658384186794785050, 0.752555788715146390, - -0.658528499665218650, - 0.752429503622912390, -0.658672788323441890, 0.752303190865996400, - -0.658817052764149480, - 0.752176850449042810, -0.658961292982037320, 0.752050482376696360, - -0.659105508971802090, - 0.751924086653603550, -0.659249700728141490, 0.751797663284411550, - -0.659393868245753860, - 0.751671212273768430, -0.659538011519338660, 0.751544733626323680, - -0.659682130543596150, - 0.751418227346727470, -0.659826225313227320, 0.751291693439630870, - -0.659970295822934540, - 0.751165131909686480, -0.660114342067420480, 0.751038542761547360, - -0.660258364041389050, - 0.750911925999867890, -0.660402361739545030, 0.750785281629303690, - -0.660546335156593890, - 0.750658609654510700, -0.660690284287242300, 0.750531910080146410, - -0.660834209126197610, - 0.750405182910869330, -0.660978109668168060, 0.750278428151338720, - -0.661121985907862860, - 0.750151645806215070, -0.661265837839992270, 0.750024835880159780, - -0.661409665459266940, - 0.749897998377835330, -0.661553468760398890, 0.749771133303905100, - -0.661697247738101010, - 0.749644240663033480, -0.661841002387086870, 0.749517320459886170, - -0.661984732702070920, - 0.749390372699129560, -0.662128438677768720, 0.749263397385431130, - -0.662272120308896590, - 0.749136394523459370, -0.662415777590171780, 0.749009364117883880, - -0.662559410516312290, - 0.748882306173375150, -0.662703019082037440, 0.748755220694604760, - -0.662846603282066900, - 0.748628107686245440, -0.662990163111121470, 0.748500967152970430, - -0.663133698563923010, - 0.748373799099454560, -0.663277209635194100, 0.748246603530373420, - -0.663420696319658280, - 0.748119380450403600, -0.663564158612039770, 0.747992129864222700, - -0.663707596507064010, - 0.747864851776509410, -0.663851009999457340, 0.747737546191943330, - -0.663994399083946640, - 0.747610213115205150, -0.664137763755260010, 0.747482852550976570, - -0.664281104008126230, - 0.747355464503940190, -0.664424419837275180, 0.747228048978779920, - -0.664567711237437520, - 0.747100605980180130, -0.664710978203344790, 0.746973135512826850, - -0.664854220729729660, - 0.746845637581406540, -0.664997438811325340, 0.746718112190607130, - -0.665140632442866140, - 0.746590559345117310, -0.665283801619087180, 0.746462979049626770, - -0.665426946334724660, - 0.746335371308826320, -0.665570066584515450, 0.746207736127407760, - -0.665713162363197550, - 0.746080073510063780, -0.665856233665509720, 0.745952383461488290, - -0.665999280486191500, - 0.745824665986376090, -0.666142302819983540, 0.745696921089422760, - -0.666285300661627280, - 0.745569148775325430, -0.666428274005865240, 0.745441349048781680, - -0.666571222847440640, - 0.745313521914490520, -0.666714147181097670, 0.745185667377151640, - -0.666857047001581220, - 0.745057785441466060, -0.666999922303637470, 0.744929876112135350, - -0.667142773082013310, - 0.744801939393862630, -0.667285599331456370, 0.744673975291351710, - -0.667428401046715520, - 0.744545983809307370, -0.667571178222540310, 0.744417964952435620, - -0.667713930853681030, - 0.744289918725443260, -0.667856658934889320, 0.744161845133038180, - -0.667999362460917400, - 0.744033744179929290, -0.668142041426518450, 0.743905615870826490, - -0.668284695826446670, - 0.743777460210440890, -0.668427325655456820, 0.743649277203484060, - -0.668569930908304970, - 0.743521066854669120, -0.668712511579747980, 0.743392829168709970, - -0.668855067664543610, - 0.743264564150321600, -0.668997599157450270, 0.743136271804219820, - -0.669140106053227600, - 0.743007952135121720, -0.669282588346636010, 0.742879605147745200, - -0.669425046032436910, - 0.742751230846809050, -0.669567479105392490, 0.742622829237033490, - -0.669709887560265840, - 0.742494400323139180, -0.669852271391821020, 0.742365944109848460, - -0.669994630594823000, - 0.742237460601884000, -0.670136965164037650, 0.742108949803969910, - -0.670279275094231800, - 0.741980411720831070, -0.670421560380173090, 0.741851846357193480, - -0.670563821016630040, - 0.741723253717784140, -0.670706056998372160, 0.741594633807331150, - -0.670848268320169640, - 0.741465986630563290, -0.670990454976794220, 0.741337312192210660, - -0.671132616963017740, - 0.741208610497004260, -0.671274754273613490, 0.741079881549676080, - -0.671416866903355450, - 0.740951125354959110, -0.671558954847018330, 0.740822341917587330, - -0.671701018099378320, - 0.740693531242295760, -0.671843056655211930, 0.740564693333820250, - -0.671985070509296900, - 0.740435828196898020, -0.672127059656411730, 0.740306935836266940, - -0.672269024091335930, - 0.740178016256666240, -0.672410963808849790, 0.740049069462835550, - -0.672552878803734710, - 0.739920095459516200, -0.672694769070772860, 0.739791094251449950, - -0.672836634604747300, - 0.739662065843380010, -0.672978475400442090, 0.739533010240050250, - -0.673120291452642070, - 0.739403927446205760, -0.673262082756132970, 0.739274817466592520, - -0.673403849305701740, - 0.739145680305957510, -0.673545591096136100, 0.739016515969048720, - -0.673687308122224330, - 0.738887324460615110, -0.673829000378756040, 0.738758105785406900, - -0.673970667860521620, - 0.738628859948174840, -0.674112310562312360, 0.738499586953671130, - -0.674253928478920410, - 0.738370286806648620, -0.674395521605139050, 0.738240959511861310, - -0.674537089935762000, - 0.738111605074064260, -0.674678633465584540, 0.737982223498013570, - -0.674820152189402170, - 0.737852814788465980, -0.674961646102011930, 0.737723378950179700, - -0.675103115198211420, - 0.737593915987913570, -0.675244559472799270, 0.737464425906427580, - -0.675385978920574840, - 0.737334908710482910, -0.675527373536338520, 0.737205364404841190, - -0.675668743314891910, - 0.737075792994265730, -0.675810088251036940, 0.736946194483520280, - -0.675951408339577010, - 0.736816568877369900, -0.676092703575315920, 0.736686916180580460, - -0.676233973953058950, - 0.736557236397919150, -0.676375219467611590, 0.736427529534153690, - -0.676516440113781090, - 0.736297795594053170, -0.676657635886374950, 0.736168034582387330, - -0.676798806780201770, - 0.736038246503927350, -0.676939952790071130, 0.735908431363445190, - -0.677081073910793530, - 0.735778589165713590, -0.677222170137180330, 0.735648719915506510, - -0.677363241464043920, - 0.735518823617598900, -0.677504287886197430, 0.735388900276766730, - -0.677645309398454910, - 0.735258949897786840, -0.677786305995631500, 0.735128972485437180, - -0.677927277672543020, - 0.734998968044496710, -0.678068224424006600, 0.734868936579745170, - -0.678209146244839860, - 0.734738878095963500, -0.678350043129861470, 0.734608792597933550, - -0.678490915073891140, - 0.734478680090438370, -0.678631762071749360, 0.734348540578261600, - -0.678772584118257690, - 0.734218374066188280, -0.678913381208238410, 0.734088180559004040, - -0.679054153336514870, - 0.733957960061495940, -0.679194900497911200, 0.733827712578451700, - -0.679335622687252560, - 0.733697438114660370, -0.679476319899364970, 0.733567136674911360, - -0.679616992129075560, - 0.733436808263995710, -0.679757639371212030, 0.733306452886705260, - -0.679898261620603290, - 0.733176070547832740, -0.680038858872078930, 0.733045661252172080, - -0.680179431120469750, - 0.732915225004517780, -0.680319978360607200, 0.732784761809665790, - -0.680460500587323880, - 0.732654271672412820, -0.680600997795453020, 0.732523754597556700, - -0.680741469979829090, - 0.732393210589896040, -0.680881917135287230, 0.732262639654230770, - -0.681022339256663670, - 0.732132041795361290, -0.681162736338795430, 0.732001417018089630, - -0.681303108376520530, - 0.731870765327218290, -0.681443455364677870, 0.731740086727550980, - -0.681583777298107480, - 0.731609381223892630, -0.681724074171649710, 0.731478648821048520, - -0.681864345980146670, - 0.731347889523825570, -0.682004592718440830, 0.731217103337031270, - -0.682144814381375640, - 0.731086290265474340, -0.682285010963795570, 0.730955450313964360, - -0.682425182460546060, - 0.730824583487312160, -0.682565328866473250, 0.730693689790329000, - -0.682705450176424590, - 0.730562769227827590, -0.682845546385248080, 0.730431821804621520, - -0.682985617487792740, - 0.730300847525525490, -0.683125663478908680, 0.730169846395354870, - -0.683265684353446700, - 0.730038818418926260, -0.683405680106258680, 0.729907763601057140, - -0.683545650732197530, - 0.729776681946566090, -0.683685596226116580, 0.729645573460272480, - -0.683825516582870720, - 0.729514438146997010, -0.683965411797315400, 0.729383276011561050, - -0.684105281864307080, - 0.729252087058786970, -0.684245126778703080, 0.729120871293498230, - -0.684384946535361750, - 0.728989628720519420, -0.684524741129142300, 0.728858359344675800, - -0.684664510554904960, - 0.728727063170793830, -0.684804254807510620, 0.728595740203700770, - -0.684943973881821490, - 0.728464390448225200, -0.685083667772700360, 0.728333013909196360, - -0.685223336475011210, - 0.728201610591444610, -0.685362979983618730, 0.728070180499801210, - -0.685502598293388550, - 0.727938723639098620, -0.685642191399187470, 0.727807240014169960, - -0.685781759295883030, - 0.727675729629849610, -0.685921301978343560, 0.727544192490972800, - -0.686060819441438710, - 0.727412628602375770, -0.686200311680038590, 0.727281037968895870, - -0.686339778689014520, - 0.727149420595371020, -0.686479220463238950, 0.727017776486640680, - -0.686618636997584630, - 0.726886105647544970, -0.686758028286925890, 0.726754408082925020, - -0.686897394326137610, - 0.726622683797622850, -0.687036735110095660, 0.726490932796481910, - -0.687176050633676820, - 0.726359155084346010, -0.687315340891759050, 0.726227350666060370, - -0.687454605879221030, - 0.726095519546471000, -0.687593845590942170, 0.725963661730424930, - -0.687733060021803230, - 0.725831777222770370, -0.687872249166685550, 0.725699866028356120, - -0.688011413020471640, - 0.725567928152032300, -0.688150551578044830, 0.725435963598649810, - -0.688289664834289330, - 0.725303972373060770, -0.688428752784090440, 0.725171954480117950, - -0.688567815422334250, - 0.725039909924675370, -0.688706852743907750, 0.724907838711587820, - -0.688845864743699020, - 0.724775740845711280, -0.688984851416597040, 0.724643616331902550, - -0.689123812757491570, - 0.724511465175019630, -0.689262748761273470, 0.724379287379921190, - -0.689401659422834270, - 0.724247082951467000, -0.689540544737066830, 0.724114851894517850, - -0.689679404698864800, - 0.723982594213935520, -0.689818239303122470, 0.723850309914582880, - -0.689957048544735390, - 0.723717999001323500, -0.690095832418599950, 0.723585661479022150, - -0.690234590919613370, - 0.723453297352544380, -0.690373324042674040, 0.723320906626756970, - -0.690512031782681060, - 0.723188489306527460, -0.690650714134534600, 0.723056045396724410, - -0.690789371093135650, - 0.722923574902217700, -0.690928002653386160, 0.722791077827877550, - -0.691066608810189220, - 0.722658554178575610, -0.691205189558448450, 0.722526003959184540, - -0.691343744893068710, - 0.722393427174577550, -0.691482274808955850, 0.722260823829629310, - -0.691620779301016290, - 0.722128193929215350, -0.691759258364157750, 0.721995537478211880, - -0.691897711993288760, - 0.721862854481496340, -0.692036140183318720, 0.721730144943947160, - -0.692174542929158140, - 0.721597408870443770, -0.692312920225718220, 0.721464646265866370, - -0.692451272067911130, - 0.721331857135096290, -0.692589598450650380, 0.721199041483015720, - -0.692727899368849820, - 0.721066199314508110, -0.692866174817424630, 0.720933330634457530, - -0.693004424791290870, - 0.720800435447749190, -0.693142649285365400, 0.720667513759269520, - -0.693280848294566040, - 0.720534565573905270, -0.693419021813811760, 0.720401590896544760, - -0.693557169838022290, - 0.720268589732077190, -0.693695292362118240, 0.720135562085392420, - -0.693833389381021350, - 0.720002507961381650, -0.693971460889654000, 0.719869427364936860, - -0.694109506882939820, - 0.719736320300951030, -0.694247527355803310, 0.719603186774318120, - -0.694385522303169740, - 0.719470026789932990, -0.694523491719965520, 0.719336840352691740, - -0.694661435601117820, - 0.719203627467491220, -0.694799353941554900, 0.719070388139229190, - -0.694937246736205830, - 0.718937122372804490, -0.695075113980000880, 0.718803830173116890, - -0.695212955667870780, - 0.718670511545067230, -0.695350771794747690, 0.718537166493557370, - -0.695488562355564440, - 0.718403795023489830, -0.695626327345254870, 0.718270397139768260, - -0.695764066758753690, - 0.718136972847297490, -0.695901780590996830, 0.718003522150983180, - -0.696039468836920690, - 0.717870045055731710, -0.696177131491462990, 0.717736541566450950, - -0.696314768549562090, - 0.717603011688049080, -0.696452380006157830, 0.717469455425435830, - -0.696589965856190370, - 0.717335872783521730, -0.696727526094601200, 0.717202263767218070, - -0.696865060716332470, - 0.717068628381437480, -0.697002569716327460, 0.716934966631093130, - -0.697140053089530420, - 0.716801278521099540, -0.697277510830886520, 0.716667564056371890, - -0.697414942935341790, - 0.716533823241826680, -0.697552349397843160, 0.716400056082381000, - -0.697689730213338800, - 0.716266262582953120, -0.697827085376777290, 0.716132442748462330, - -0.697964414883108670, - 0.715998596583828690, -0.698101718727283770, 0.715864724093973500, - -0.698238996904254280, - 0.715730825283818590, -0.698376249408972920, 0.715596900158287470, - -0.698513476236393040, - 0.715462948722303760, -0.698650677381469460, 0.715328970980792620, - -0.698787852839157670, - 0.715194966938680120, -0.698925002604414150, 0.715060936600893090, - -0.699062126672196140, - 0.714926879972359490, -0.699199225037462120, 0.714792797058008240, - -0.699336297695171140, - 0.714658687862769090, -0.699473344640283770, 0.714524552391572860, - -0.699610365867761040, - 0.714390390649351390, -0.699747361372564990, 0.714256202641037510, - -0.699884331149658760, - 0.714121988371564820, -0.700021275194006250, 0.713987747845867830, - -0.700158193500572730, - 0.713853481068882470, -0.700295086064323780, 0.713719188045545240, - -0.700431952880226420, - 0.713584868780793640, -0.700568793943248340, 0.713450523279566260, - -0.700705609248358450, - 0.713316151546802610, -0.700842398790526120, 0.713181753587443180, - -0.700979162564722370, - 0.713047329406429340, -0.701115900565918660, 0.712912879008703480, - -0.701252612789087460, - 0.712778402399208980, -0.701389299229202230, 0.712643899582890210, - -0.701525959881237340, - 0.712509370564692320, -0.701662594740168450, 0.712374815349561710, - -0.701799203800971720, - 0.712240233942445510, -0.701935787058624360, 0.712105626348291890, - -0.702072344508104630, - 0.711970992572050100, -0.702208876144391870, 0.711836332618670080, - -0.702345381962465880, - 0.711701646493102970, -0.702481861957308000, 0.711566934200300700, - -0.702618316123900130, - 0.711432195745216430, -0.702754744457225300, 0.711297431132803970, - -0.702891146952267400, - 0.711162640368018350, -0.703027523604011220, 0.711027823455815280, - -0.703163874407442770, - 0.710892980401151680, -0.703300199357548730, 0.710758111208985350, - -0.703436498449316660, - 0.710623215884275020, -0.703572771677735580, 0.710488294431980470, - -0.703709019037794810, - 0.710353346857062420, -0.703845240524484940, 0.710218373164482220, - -0.703981436132797620, - 0.710083373359202800, -0.704117605857725310, 0.709948347446187400, - -0.704253749694261470, - 0.709813295430400840, -0.704389867637400410, 0.709678217316808580, - -0.704525959682137380, - 0.709543113110376770, -0.704662025823468820, 0.709407982816072980, - -0.704798066056391950, - 0.709272826438865690, -0.704934080375904880, 0.709137643983724030, - -0.705070068777006840, - 0.709002435455618250, -0.705206031254697830, 0.708867200859519820, - -0.705341967803978840, - 0.708731940200400650, -0.705477878419852100, 0.708596653483234080, - -0.705613763097320490, - 0.708461340712994160, -0.705749621831387790, 0.708326001894655890, - -0.705885454617058980, - 0.708190637033195400, -0.706021261449339740, 0.708055246133589500, - -0.706157042323237060, - 0.707919829200816310, -0.706292797233758480, 0.707784386239854620, - -0.706428526175912790, - 0.707648917255684350, -0.706564229144709510, 0.707513422253286280, - -0.706699906135159430, - 0.707377901237642100, -0.706835557142273750, 0.707242354213734710, - -0.706971182161065360, - 0.707106781186547570, -0.707106781186547460, 0.706971182161065360, - -0.707242354213734600, - 0.706835557142273860, -0.707377901237642100, 0.706699906135159430, - -0.707513422253286170, - 0.706564229144709620, -0.707648917255684350, 0.706428526175912790, - -0.707784386239854620, - 0.706292797233758480, -0.707919829200816310, 0.706157042323237060, - -0.708055246133589500, - 0.706021261449339740, -0.708190637033195290, 0.705885454617058980, - -0.708326001894655780, - 0.705749621831387790, -0.708461340712994050, 0.705613763097320490, - -0.708596653483234080, - 0.705477878419852210, -0.708731940200400650, 0.705341967803978950, - -0.708867200859519820, - 0.705206031254697830, -0.709002435455618250, 0.705070068777006840, - -0.709137643983723920, - 0.704934080375904990, -0.709272826438865580, 0.704798066056391950, - -0.709407982816072980, - 0.704662025823468930, -0.709543113110376770, 0.704525959682137380, - -0.709678217316808470, - 0.704389867637400410, -0.709813295430400840, 0.704253749694261580, - -0.709948347446187400, - 0.704117605857725430, -0.710083373359202690, 0.703981436132797730, - -0.710218373164482220, - 0.703845240524484940, -0.710353346857062310, 0.703709019037794810, - -0.710488294431980470, - 0.703572771677735580, -0.710623215884275020, 0.703436498449316770, - -0.710758111208985350, - 0.703300199357548730, -0.710892980401151680, 0.703163874407442770, - -0.711027823455815280, - 0.703027523604011220, -0.711162640368018350, 0.702891146952267400, - -0.711297431132803970, - 0.702754744457225300, -0.711432195745216430, 0.702618316123900130, - -0.711566934200300700, - 0.702481861957308000, -0.711701646493102970, 0.702345381962465880, - -0.711836332618670080, - 0.702208876144391870, -0.711970992572049990, 0.702072344508104740, - -0.712105626348291890, - 0.701935787058624360, -0.712240233942445510, 0.701799203800971720, - -0.712374815349561710, - 0.701662594740168570, -0.712509370564692320, 0.701525959881237450, - -0.712643899582890210, - 0.701389299229202230, -0.712778402399208870, 0.701252612789087460, - -0.712912879008703370, - 0.701115900565918660, -0.713047329406429230, 0.700979162564722480, - -0.713181753587443070, - 0.700842398790526230, -0.713316151546802610, 0.700705609248358450, - -0.713450523279566150, - 0.700568793943248450, -0.713584868780793520, 0.700431952880226420, - -0.713719188045545130, - 0.700295086064323780, -0.713853481068882470, 0.700158193500572730, - -0.713987747845867830, - 0.700021275194006360, -0.714121988371564710, 0.699884331149658760, - -0.714256202641037400, - 0.699747361372564990, -0.714390390649351390, 0.699610365867761040, - -0.714524552391572860, - 0.699473344640283770, -0.714658687862768980, 0.699336297695171250, - -0.714792797058008130, - 0.699199225037462120, -0.714926879972359370, 0.699062126672196140, - -0.715060936600892980, - 0.698925002604414150, -0.715194966938680010, 0.698787852839157790, - -0.715328970980792620, - 0.698650677381469580, -0.715462948722303650, 0.698513476236393040, - -0.715596900158287360, - 0.698376249408972920, -0.715730825283818590, 0.698238996904254390, - -0.715864724093973390, - 0.698101718727283880, -0.715998596583828690, 0.697964414883108790, - -0.716132442748462330, - 0.697827085376777290, -0.716266262582953120, 0.697689730213338800, - -0.716400056082380890, - 0.697552349397843270, -0.716533823241826570, 0.697414942935341790, - -0.716667564056371890, - 0.697277510830886630, -0.716801278521099540, 0.697140053089530530, - -0.716934966631093130, - 0.697002569716327460, -0.717068628381437480, 0.696865060716332470, - -0.717202263767218070, - 0.696727526094601200, -0.717335872783521730, 0.696589965856190370, - -0.717469455425435830, - 0.696452380006157830, -0.717603011688049080, 0.696314768549562200, - -0.717736541566450840, - 0.696177131491462990, -0.717870045055731710, 0.696039468836920690, - -0.718003522150983060, - 0.695901780590996830, -0.718136972847297490, 0.695764066758753800, - -0.718270397139768260, - 0.695626327345254870, -0.718403795023489720, 0.695488562355564440, - -0.718537166493557370, - 0.695350771794747800, -0.718670511545067230, 0.695212955667870890, - -0.718803830173116890, - 0.695075113980000880, -0.718937122372804380, 0.694937246736205940, - -0.719070388139229190, - 0.694799353941554900, -0.719203627467491220, 0.694661435601117930, - -0.719336840352691740, - 0.694523491719965520, -0.719470026789932990, 0.694385522303169860, - -0.719603186774318000, - 0.694247527355803310, -0.719736320300951030, 0.694109506882939820, - -0.719869427364936860, - 0.693971460889654000, -0.720002507961381650, 0.693833389381021350, - -0.720135562085392310, - 0.693695292362118350, -0.720268589732077080, 0.693557169838022400, - -0.720401590896544760, - 0.693419021813811880, -0.720534565573905270, 0.693280848294566150, - -0.720667513759269410, - 0.693142649285365510, -0.720800435447749190, 0.693004424791290870, - -0.720933330634457530, - 0.692866174817424740, -0.721066199314508110, 0.692727899368849820, - -0.721199041483015720, - 0.692589598450650380, -0.721331857135096180, 0.692451272067911240, - -0.721464646265866370, - 0.692312920225718220, -0.721597408870443660, 0.692174542929158140, - -0.721730144943947160, - 0.692036140183318830, -0.721862854481496340, 0.691897711993288760, - -0.721995537478211880, - 0.691759258364157750, -0.722128193929215350, 0.691620779301016400, - -0.722260823829629310, - 0.691482274808955850, -0.722393427174577550, 0.691343744893068820, - -0.722526003959184430, - 0.691205189558448450, -0.722658554178575610, 0.691066608810189220, - -0.722791077827877550, - 0.690928002653386280, -0.722923574902217700, 0.690789371093135760, - -0.723056045396724410, - 0.690650714134534720, -0.723188489306527350, 0.690512031782681170, - -0.723320906626756850, - 0.690373324042674040, -0.723453297352544380, 0.690234590919613370, - -0.723585661479022040, - 0.690095832418599950, -0.723717999001323390, 0.689957048544735390, - -0.723850309914582880, - 0.689818239303122470, -0.723982594213935520, 0.689679404698864800, - -0.724114851894517850, - 0.689540544737066940, -0.724247082951466890, 0.689401659422834380, - -0.724379287379921080, - 0.689262748761273470, -0.724511465175019520, 0.689123812757491680, - -0.724643616331902550, - 0.688984851416597150, -0.724775740845711280, 0.688845864743699130, - -0.724907838711587820, - 0.688706852743907750, -0.725039909924675370, 0.688567815422334360, - -0.725171954480117840, - 0.688428752784090550, -0.725303972373060660, 0.688289664834289440, - -0.725435963598649810, - 0.688150551578044830, -0.725567928152032300, 0.688011413020471640, - -0.725699866028356120, - 0.687872249166685550, -0.725831777222770370, 0.687733060021803230, - -0.725963661730424930, - 0.687593845590942170, -0.726095519546470890, 0.687454605879221030, - -0.726227350666060260, - 0.687315340891759160, -0.726359155084346010, 0.687176050633676930, - -0.726490932796481910, - 0.687036735110095660, -0.726622683797622850, 0.686897394326137610, - -0.726754408082924910, - 0.686758028286925890, -0.726886105647544970, 0.686618636997584740, - -0.727017776486640680, - 0.686479220463238950, -0.727149420595371020, 0.686339778689014630, - -0.727281037968895760, - 0.686200311680038700, -0.727412628602375770, 0.686060819441438710, - -0.727544192490972800, - 0.685921301978343670, -0.727675729629849610, 0.685781759295883030, - -0.727807240014169960, - 0.685642191399187470, -0.727938723639098620, 0.685502598293388670, - -0.728070180499801210, - 0.685362979983618730, -0.728201610591444500, 0.685223336475011210, - -0.728333013909196360, - 0.685083667772700360, -0.728464390448225200, 0.684943973881821490, - -0.728595740203700770, - 0.684804254807510620, -0.728727063170793720, 0.684664510554904960, - -0.728858359344675690, - 0.684524741129142300, -0.728989628720519310, 0.684384946535361750, - -0.729120871293498230, - 0.684245126778703080, -0.729252087058786970, 0.684105281864307080, - -0.729383276011561050, - 0.683965411797315510, -0.729514438146996900, 0.683825516582870830, - -0.729645573460272480, - 0.683685596226116690, -0.729776681946565970, 0.683545650732197530, - -0.729907763601057140, - 0.683405680106258790, -0.730038818418926150, 0.683265684353446700, - -0.730169846395354870, - 0.683125663478908800, -0.730300847525525380, 0.682985617487792850, - -0.730431821804621520, - 0.682845546385248080, -0.730562769227827590, 0.682705450176424590, - -0.730693689790328890, - 0.682565328866473250, -0.730824583487312050, 0.682425182460546060, - -0.730955450313964360, - 0.682285010963795570, -0.731086290265474230, 0.682144814381375640, - -0.731217103337031160, - 0.682004592718440830, -0.731347889523825460, 0.681864345980146780, - -0.731478648821048520, - 0.681724074171649820, -0.731609381223892520, 0.681583777298107480, - -0.731740086727550980, - 0.681443455364677990, -0.731870765327218290, 0.681303108376520530, - -0.732001417018089520, - 0.681162736338795430, -0.732132041795361290, 0.681022339256663670, - -0.732262639654230660, - 0.680881917135287340, -0.732393210589896040, 0.680741469979829090, - -0.732523754597556590, - 0.680600997795453130, -0.732654271672412820, 0.680460500587323880, - -0.732784761809665790, - 0.680319978360607200, -0.732915225004517780, 0.680179431120469750, - -0.733045661252171970, - 0.680038858872079040, -0.733176070547832740, 0.679898261620603290, - -0.733306452886705260, - 0.679757639371212030, -0.733436808263995710, 0.679616992129075560, - -0.733567136674911360, - 0.679476319899365080, -0.733697438114660260, 0.679335622687252670, - -0.733827712578451700, - 0.679194900497911200, -0.733957960061495940, 0.679054153336514870, - -0.734088180559004040, - 0.678913381208238410, -0.734218374066188170, 0.678772584118257690, - -0.734348540578261600, - 0.678631762071749470, -0.734478680090438370, 0.678490915073891250, - -0.734608792597933550, - 0.678350043129861580, -0.734738878095963390, 0.678209146244839860, - -0.734868936579745060, - 0.678068224424006600, -0.734998968044496600, 0.677927277672543130, - -0.735128972485437180, - 0.677786305995631500, -0.735258949897786730, 0.677645309398454910, - -0.735388900276766620, - 0.677504287886197430, -0.735518823617598900, 0.677363241464044030, - -0.735648719915506400, - 0.677222170137180450, -0.735778589165713480, 0.677081073910793530, - -0.735908431363445190, - 0.676939952790071240, -0.736038246503927350, 0.676798806780201770, - -0.736168034582387330, - 0.676657635886374950, -0.736297795594053060, 0.676516440113781090, - -0.736427529534153690, - 0.676375219467611700, -0.736557236397919150, 0.676233973953058950, - -0.736686916180580460, - 0.676092703575316030, -0.736816568877369790, 0.675951408339577010, - -0.736946194483520170, - 0.675810088251037060, -0.737075792994265620, 0.675668743314891910, - -0.737205364404841190, - 0.675527373536338630, -0.737334908710482790, 0.675385978920574950, - -0.737464425906427580, - 0.675244559472799270, -0.737593915987913460, 0.675103115198211530, - -0.737723378950179590, - 0.674961646102012040, -0.737852814788465980, 0.674820152189402280, - -0.737982223498013570, - 0.674678633465584540, -0.738111605074064260, 0.674537089935762110, - -0.738240959511861310, - 0.674395521605139050, -0.738370286806648510, 0.674253928478920520, - -0.738499586953671130, - 0.674112310562312360, -0.738628859948174840, 0.673970667860521620, - -0.738758105785406900, - 0.673829000378756150, -0.738887324460615110, 0.673687308122224330, - -0.739016515969048600, - 0.673545591096136100, -0.739145680305957400, 0.673403849305701850, - -0.739274817466592520, - 0.673262082756132970, -0.739403927446205760, 0.673120291452642070, - -0.739533010240050250, - 0.672978475400442090, -0.739662065843379900, 0.672836634604747410, - -0.739791094251449950, - 0.672694769070772970, -0.739920095459516090, 0.672552878803734820, - -0.740049069462835550, - 0.672410963808849900, -0.740178016256666240, 0.672269024091336040, - -0.740306935836266940, - 0.672127059656411840, -0.740435828196898020, 0.671985070509296900, - -0.740564693333820250, - 0.671843056655211930, -0.740693531242295640, 0.671701018099378320, - -0.740822341917587330, - 0.671558954847018330, -0.740951125354959110, 0.671416866903355450, - -0.741079881549676080, - 0.671274754273613490, -0.741208610497004260, 0.671132616963017850, - -0.741337312192210660, - 0.670990454976794220, -0.741465986630563290, 0.670848268320169750, - -0.741594633807331150, - 0.670706056998372160, -0.741723253717784140, 0.670563821016630040, - -0.741851846357193480, - 0.670421560380173090, -0.741980411720830960, 0.670279275094231910, - -0.742108949803969800, - 0.670136965164037760, -0.742237460601884000, 0.669994630594823000, - -0.742365944109848460, - 0.669852271391821130, -0.742494400323139180, 0.669709887560265840, - -0.742622829237033380, - 0.669567479105392490, -0.742751230846809050, 0.669425046032436910, - -0.742879605147745090, - 0.669282588346636010, -0.743007952135121720, 0.669140106053227710, - -0.743136271804219820, - 0.668997599157450270, -0.743264564150321490, 0.668855067664543610, - -0.743392829168709970, - 0.668712511579748090, -0.743521066854669120, 0.668569930908305080, - -0.743649277203484060, - 0.668427325655456820, -0.743777460210440780, 0.668284695826446670, - -0.743905615870826490, - 0.668142041426518560, -0.744033744179929180, 0.667999362460917510, - -0.744161845133038070, - 0.667856658934889440, -0.744289918725443140, 0.667713930853681140, - -0.744417964952435620, - 0.667571178222540310, -0.744545983809307250, 0.667428401046715640, - -0.744673975291351600, - 0.667285599331456480, -0.744801939393862630, 0.667142773082013310, - -0.744929876112135350, - 0.666999922303637470, -0.745057785441465950, 0.666857047001581220, - -0.745185667377151640, - 0.666714147181097670, -0.745313521914490410, 0.666571222847440750, - -0.745441349048781680, - 0.666428274005865350, -0.745569148775325430, 0.666285300661627390, - -0.745696921089422760, - 0.666142302819983540, -0.745824665986375980, 0.665999280486191500, - -0.745952383461488180, - 0.665856233665509720, -0.746080073510063780, 0.665713162363197660, - -0.746207736127407650, - 0.665570066584515560, -0.746335371308826320, 0.665426946334724660, - -0.746462979049626770, - 0.665283801619087180, -0.746590559345117310, 0.665140632442866140, - -0.746718112190607020, - 0.664997438811325340, -0.746845637581406540, 0.664854220729729660, - -0.746973135512826740, - 0.664710978203344900, -0.747100605980180130, 0.664567711237437520, - -0.747228048978779920, - 0.664424419837275180, -0.747355464503940190, 0.664281104008126230, - -0.747482852550976570, - 0.664137763755260010, -0.747610213115205150, 0.663994399083946640, - -0.747737546191943330, - 0.663851009999457340, -0.747864851776509410, 0.663707596507064120, - -0.747992129864222700, - 0.663564158612039880, -0.748119380450403490, 0.663420696319658280, - -0.748246603530373420, - 0.663277209635194100, -0.748373799099454560, 0.663133698563923010, - -0.748500967152970430, - 0.662990163111121470, -0.748628107686245330, 0.662846603282066900, - -0.748755220694604760, - 0.662703019082037440, -0.748882306173375030, 0.662559410516312400, - -0.749009364117883770, - 0.662415777590171780, -0.749136394523459260, 0.662272120308896590, - -0.749263397385431020, - 0.662128438677768720, -0.749390372699129560, 0.661984732702071030, - -0.749517320459886170, - 0.661841002387086870, -0.749644240663033480, 0.661697247738101120, - -0.749771133303904990, - 0.661553468760399000, -0.749897998377835220, 0.661409665459266940, - -0.750024835880159780, - 0.661265837839992270, -0.750151645806214960, 0.661121985907862970, - -0.750278428151338610, - 0.660978109668168060, -0.750405182910869220, 0.660834209126197610, - -0.750531910080146410, - 0.660690284287242300, -0.750658609654510590, 0.660546335156593890, - -0.750785281629303580, - 0.660402361739545030, -0.750911925999867890, 0.660258364041389050, - -0.751038542761547250, - 0.660114342067420480, -0.751165131909686370, 0.659970295822934540, - -0.751291693439630870, - 0.659826225313227430, -0.751418227346727360, 0.659682130543596150, - -0.751544733626323570, - 0.659538011519338770, -0.751671212273768430, 0.659393868245753970, - -0.751797663284411440, - 0.659249700728141490, -0.751924086653603550, 0.659105508971802200, - -0.752050482376696360, - 0.658961292982037320, -0.752176850449042700, 0.658817052764149480, - -0.752303190865996400, - 0.658672788323441890, -0.752429503622912390, 0.658528499665218760, - -0.752555788715146390, - 0.658384186794785050, -0.752682046138055230, 0.658239849717446980, - -0.752808275886996950, - 0.658095488438511290, -0.752934477957330150, 0.657951102963285630, - -0.753060652344415100, - 0.657806693297078640, -0.753186799043612410, 0.657662259445200070, - -0.753312918050284330, - 0.657517801412960120, -0.753439009359793580, 0.657373319205670210, - -0.753565072967504190, - 0.657228812828642650, -0.753691108868781210, 0.657084282287190180, - -0.753817117058990680, - 0.656939727586627110, -0.753943097533499640, 0.656795148732268070, - -0.754069050287676120, - 0.656650545729429050, -0.754194975316889170, 0.656505918583426550, - -0.754320872616508820, - 0.656361267299578000, -0.754446742181906330, 0.656216591883202030, - -0.754572584008453840, - 0.656071892339617710, -0.754698398091524390, 0.655927168674145360, - -0.754824184426492240, - 0.655782420892106030, -0.754949943008732640, 0.655637648998821820, - -0.755075673833621510, - 0.655492852999615460, -0.755201376896536550, 0.655348032899810580, - -0.755327052192855560, - 0.655203188704731930, -0.755452699717958140, 0.655058320419704910, - -0.755578319467224540, - 0.654913428050056150, -0.755703911436035880, 0.654768511601112600, - -0.755829475619774760, - 0.654623571078202680, -0.755955012013824310, 0.654478606486655350, - -0.756080520613569120, - 0.654333617831800550, -0.756206001414394540, 0.654188605118969040, - -0.756331454411686920, - 0.654043568353492640, -0.756456879600833630, 0.653898507540703890, - -0.756582276977223470, - 0.653753422685936170, -0.756707646536245670, 0.653608313794523890, - -0.756832988273290820, - 0.653463180871802330, -0.756958302183750490, 0.653318023923107670, - -0.757083588263017140, - 0.653172842953776760, -0.757208846506484460, 0.653027637969147650, - -0.757334076909547130, - 0.652882408974558960, -0.757459279467600720, 0.652737155975350420, - -0.757584454176041810, - 0.652591878976862550, -0.757709601030268080, 0.652446577984436840, - -0.757834720025678310, - 0.652301253003415460, -0.757959811157672300, 0.652155904039141700, - -0.758084874421650620, - 0.652010531096959500, -0.758209909813015280, 0.651865134182214030, - -0.758334917327168960, - 0.651719713300251020, -0.758459896959515320, 0.651574268456417080, - -0.758584848705459500, - 0.651428799656059820, -0.758709772560407390, 0.651283306904527850, - -0.758834668519765660, - 0.651137790207170330, -0.758959536578942440, 0.650992249569337660, - -0.759084376733346500, - 0.650846684996380990, -0.759209188978387960, 0.650701096493652040, - -0.759333973309477940, - 0.650555484066503990, -0.759458729722028210, 0.650409847720290420, - -0.759583458211452010, - 0.650264187460365960, -0.759708158773163440, 0.650118503292086200, - -0.759832831402577400, - 0.649972795220807530, -0.759957476095110330, 0.649827063251887100, - -0.760082092846179220, - 0.649681307390683190, -0.760206681651202420, 0.649535527642554730, - -0.760331242505599030, - 0.649389724012861770, -0.760455775404789260, 0.649243896506965010, - -0.760580280344194340, - 0.649098045130226060, -0.760704757319236920, 0.648952169888007410, - -0.760829206325340010, - 0.648806270785672550, -0.760953627357928040, 0.648660347828585840, - -0.761078020412426560, - 0.648514401022112550, -0.761202385484261780, 0.648368430371618400, - -0.761326722568861250, - 0.648222435882470420, -0.761451031661653510, 0.648076417560036530, - -0.761575312758068000, - 0.647930375409685460, -0.761699565853535270, 0.647784309436786550, - -0.761823790943486840, - 0.647638219646710420, -0.761947988023355390, 0.647492106044828100, - -0.762072157088574560, - 0.647345968636512060, -0.762196298134578900, 0.647199807427135230, - -0.762320411156804160, - 0.647053622422071650, -0.762444496150687100, 0.646907413626696020, - -0.762568553111665380, - 0.646761181046383920, -0.762692582035177870, 0.646614924686512050, - -0.762816582916664320, - 0.646468644552457890, -0.762940555751565720, 0.646322340649599590, - -0.763064500535323710, - 0.646176012983316390, -0.763188417263381270, 0.646029661558988330, - -0.763312305931182380, - 0.645883286381996440, -0.763436166534172010, 0.645736887457722290, - -0.763559999067796150, - 0.645590464791548800, -0.763683803527501870, 0.645444018388859230, - -0.763807579908737160, - 0.645297548255038380, -0.763931328206951090, 0.645151054395471270, - -0.764055048417593860, - 0.645004536815544040, -0.764178740536116670, 0.644857995520643710, - -0.764302404557971720, - 0.644711430516158420, -0.764426040478612070, 0.644564841807476750, - -0.764549648293492150, - 0.644418229399988380, -0.764673227998067140, 0.644271593299083900, - -0.764796779587793460, - 0.644124933510154540, -0.764920303058128410, 0.643978250038592660, - -0.765043798404530410, - 0.643831542889791500, -0.765167265622458960, 0.643684812069144960, - -0.765290704707374260, - 0.643538057582047850, -0.765414115654738160, 0.643391279433895960, - -0.765537498460013070, - 0.643244477630085850, -0.765660853118662390, 0.643097652176015110, - -0.765784179626150970, - 0.642950803077082080, -0.765907477977944230, 0.642803930338686100, - -0.766030748169509000, - 0.642657033966226860, -0.766153990196312810, 0.642510113965105710, - -0.766277204053824710, - 0.642363170340724320, -0.766400389737514120, 0.642216203098485370, - -0.766523547242852100, - 0.642069212243792540, -0.766646676565310380, 0.641922197782050170, - -0.766769777700361920, - 0.641775159718663500, -0.766892850643480670, 0.641628098059038860, - -0.767015895390141480, - 0.641481012808583160, -0.767138911935820400, 0.641333903972704290, - -0.767261900275994390, - 0.641186771556811250, -0.767384860406141620, 0.641039615566313390, - -0.767507792321741270, - 0.640892436006621380, -0.767630696018273270, 0.640745232883146440, - -0.767753571491219030, - 0.640598006201301030, -0.767876418736060610, 0.640450755966498140, - -0.767999237748281270, - 0.640303482184151670, -0.768122028523365310, 0.640156184859676620, - -0.768244791056798220, - 0.640008863998488440, -0.768367525344066270, 0.639861519606004010, - -0.768490231380656750, - 0.639714151687640450, -0.768612909162058270, 0.639566760248816420, - -0.768735558683760310, - 0.639419345294950700, -0.768858179941253270, 0.639271906831463510, - -0.768980772930028870, - 0.639124444863775730, -0.769103337645579590, 0.638976959397309140, - -0.769225874083399260, - 0.638829450437486400, -0.769348382238982280, 0.638681917989730840, - -0.769470862107824560, - 0.638534362059466790, -0.769593313685422940, 0.638386782652119680, - -0.769715736967275020, - 0.638239179773115390, -0.769838131948879840, 0.638091553427880930, - -0.769960498625737230, - 0.637943903621844170, -0.770082836993347900, 0.637796230360433540, - -0.770205147047214100, - 0.637648533649078810, -0.770327428782838770, 0.637500813493210310, - -0.770449682195725960, - 0.637353069898259130, -0.770571907281380700, 0.637205302869657600, - -0.770694104035309140, - 0.637057512412838590, -0.770816272453018430, 0.636909698533235870, - -0.770938412530016940, - 0.636761861236284200, -0.771060524261813710, 0.636614000527419230, - -0.771182607643919220, - 0.636466116412077180, -0.771304662671844720, 0.636318208895695570, - -0.771426689341102590, - 0.636170277983712170, -0.771548687647206300, 0.636022323681566300, - -0.771670657585670330, - 0.635874345994697720, -0.771792599152010150, 0.635726344928547180, - -0.771914512341742350, - 0.635578320488556230, -0.772036397150384410, 0.635430272680167160, - -0.772158253573455240, - 0.635282201508823530, -0.772280081606474320, 0.635134106979969300, - -0.772401881244962340, - 0.634985989099049460, -0.772523652484441330, 0.634837847871510100, - -0.772645395320433860, - 0.634689683302797850, -0.772767109748463740, 0.634541495398360130, - -0.772888795764056220, - 0.634393284163645490, -0.773010453362736990, 0.634245049604103330, - -0.773132082540033070, - 0.634096791725183740, -0.773253683291472590, 0.633948510532337810, - -0.773375255612584470, - 0.633800206031017280, -0.773496799498899050, 0.633651878226674900, - -0.773618314945947460, - 0.633503527124764320, -0.773739801949261840, 0.633355152730740060, - -0.773861260504375540, - 0.633206755050057190, -0.773982690606822790, 0.633058334088172250, - -0.774104092252138940, - 0.632909889850541860, -0.774225465435860570, 0.632761422342624000, - -0.774346810153525020, - 0.632612931569877520, -0.774468126400670860, 0.632464417537761840, - -0.774589414172837550, - 0.632315880251737680, -0.774710673465565550, 0.632167319717266030, - -0.774831904274396850, - 0.632018735939809060, -0.774953106594873820, 0.631870128924829850, - -0.775074280422540450, - 0.631721498677792370, -0.775195425752941310, 0.631572845204161130, - -0.775316542581622410, - 0.631424168509401860, -0.775437630904130430, 0.631275468598980870, - -0.775558690716013580, - 0.631126745478365340, -0.775679722012820540, 0.630977999153023660, - -0.775800724790101540, - 0.630829229628424470, -0.775921699043407580, 0.630680436910038060, - -0.776042644768290770, - 0.630531621003334600, -0.776163561960304340, 0.630382781913785940, - -0.776284450615002400, - 0.630233919646864480, -0.776405310727940390, 0.630085034208043290, - -0.776526142294674430, - 0.629936125602796550, -0.776646945310762060, 0.629787193836599200, - -0.776767719771761510, - 0.629638238914927100, -0.776888465673232440, 0.629489260843256740, - -0.777009183010735290, - 0.629340259627065750, -0.777129871779831620, 0.629191235271832410, - -0.777250531976084070, - 0.629042187783036000, -0.777371163595056200, 0.628893117166156480, - -0.777491766632312900, - 0.628744023426674790, -0.777612341083419920, 0.628594906570072660, - -0.777732886943944050, - 0.628445766601832710, -0.777853404209453040, 0.628296603527438440, - -0.777973892875515990, - 0.628147417352374120, -0.778094352937702790, 0.627998208082124810, - -0.778214784391584420, - 0.627848975722176570, -0.778335187232733090, 0.627699720278016240, - -0.778455561456721900, - 0.627550441755131530, -0.778575907059124940, 0.627401140159011160, - -0.778696224035517530, - 0.627251815495144190, -0.778816512381475870, 0.627102467769021010, - -0.778936772092577500, - 0.626953096986132770, -0.779057003164400630, 0.626803703151971310, - -0.779177205592524680, - 0.626654286272029460, -0.779297379372530300, 0.626504846351800930, - -0.779417524499998900, - 0.626355383396779990, -0.779537640970513150, 0.626205897412462130, - -0.779657728779656780, - 0.626056388404343520, -0.779777787923014440, 0.625906856377921210, - -0.779897818396171890, - 0.625757301338692900, -0.780017820194715990, 0.625607723292157410, - -0.780137793314234500, - 0.625458122243814360, -0.780257737750316590, 0.625308498199164010, - -0.780377653498552040, - 0.625158851163707730, -0.780497540554531910, 0.625009181142947460, - -0.780617398913848290, - 0.624859488142386450, -0.780737228572094380, 0.624709772167528100, - -0.780857029524864470, - 0.624560033223877320, -0.780976801767753750, 0.624410271316939380, - -0.781096545296358410, - 0.624260486452220650, -0.781216260106276090, 0.624110678635228510, - -0.781335946193104870, - 0.623960847871470770, -0.781455603552444480, 0.623810994166456130, - -0.781575232179895550, - 0.623661117525694640, -0.781694832071059390, 0.623511217954696550, - -0.781814403221538830, - 0.623361295458973340, -0.781933945626937630, 0.623211350044037270, - -0.782053459282860300, - 0.623061381715401370, -0.782172944184912900, 0.622911390478579460, - -0.782292400328702400, - 0.622761376339086460, -0.782411827709836420, 0.622611339302437730, - -0.782531226323924240, - 0.622461279374150080, -0.782650596166575730, 0.622311196559740320, - -0.782769937233402050, - 0.622161090864726930, -0.782889249520015480, 0.622010962294628600, - -0.783008533022029110, - 0.621860810854965360, -0.783127787735057310, 0.621710636551257690, - -0.783247013654715380, - 0.621560439389027270, -0.783366210776619720, 0.621410219373796150, - -0.783485379096387820, - 0.621259976511087660, -0.783604518609638200, 0.621109710806425740, - -0.783723629311990470, - 0.620959422265335180, -0.783842711199065230, 0.620809110893341900, - -0.783961764266484010, - 0.620658776695972140, -0.784080788509869950, 0.620508419678753360, - -0.784199783924846570, - 0.620358039847213830, -0.784318750507038920, 0.620207637206882430, - -0.784437688252072720, - 0.620057211763289210, -0.784556597155575240, 0.619906763521964830, - -0.784675477213174320, - 0.619756292488440660, -0.784794328420499230, 0.619605798668249390, - -0.784913150773180020, - 0.619455282066924020, -0.785031944266848080, 0.619304742689998690, - -0.785150708897135560, - 0.619154180543008410, -0.785269444659675850, 0.619003595631488770, - -0.785388151550103550, - 0.618852987960976320, -0.785506829564053930, 0.618702357537008640, - -0.785625478697163700, - 0.618551704365123860, -0.785744098945070360, 0.618401028450860980, - -0.785862690303412600, - 0.618250329799760250, -0.785981252767830150, 0.618099608417362110, - -0.786099786333963820, - 0.617948864309208260, -0.786218290997455550, 0.617798097480841140, - -0.786336766753948260, - 0.617647307937803980, -0.786455213599085770, 0.617496495685640910, - -0.786573631528513230, - 0.617345660729896940, -0.786692020537876680, 0.617194803076117630, - -0.786810380622823490, - 0.617043922729849760, -0.786928711779001700, 0.616893019696640790, - -0.787047014002060790, - 0.616742093982038830, -0.787165287287650890, 0.616591145591593230, - -0.787283531631423620, - 0.616440174530853650, -0.787401747029031320, 0.616289180805370980, - -0.787519933476127810, - 0.616138164420696910, -0.787638090968367450, 0.615987125382383870, - -0.787756219501405950, - 0.615836063695985090, -0.787874319070900110, 0.615684979367054570, - -0.787992389672507950, - 0.615533872401147430, -0.788110431301888070, 0.615382742803819330, - -0.788228443954700490, - 0.615231590580626820, -0.788346427626606230, 0.615080415737127460, - -0.788464382313267430, - 0.614929218278879590, -0.788582308010347120, 0.614777998211442190, - -0.788700204713509660, - 0.614626755540375050, -0.788818072418420170, 0.614475490271239160, - -0.788935911120745130, - 0.614324202409595950, -0.789053720816151880, 0.614172891961007990, - -0.789171501500308790, - 0.614021558931038490, -0.789289253168885650, 0.613870203325251440, - -0.789406975817552810, - 0.613718825149211830, -0.789524669441982190, 0.613567424408485330, - -0.789642334037846340, - 0.613416001108638590, -0.789759969600819070, 0.613264555255239150, - -0.789877576126575280, - 0.613113086853854910, -0.789995153610791090, 0.612961595910055170, - -0.790112702049143300, - 0.612810082429409710, -0.790230221437310030, 0.612658546417489290, - -0.790347711770970520, - 0.612506987879865570, -0.790465173045804880, 0.612355406822110760, - -0.790582605257494460, - 0.612203803249798060, -0.790700008401721610, 0.612052177168501580, - -0.790817382474169660, - 0.611900528583796070, -0.790934727470523290, 0.611748857501257400, - -0.791052043386467950, - 0.611597163926462020, -0.791169330217690090, 0.611445447864987110, - -0.791286587959877720, - 0.611293709322411010, -0.791403816608719500, 0.611141948304312570, - -0.791521016159905220, - 0.610990164816271770, -0.791638186609125770, 0.610838358863869280, - -0.791755327952073150, - 0.610686530452686280, -0.791872440184440470, 0.610534679588305320, - -0.791989523301921850, - 0.610382806276309480, -0.792106577300212390, 0.610230910522282620, - -0.792223602175008310, - 0.610078992331809620, -0.792340597922007060, 0.609927051710476230, - -0.792457564536906970, - 0.609775088663868430, -0.792574502015407580, 0.609623103197573730, - -0.792691410353209450, - 0.609471095317180240, -0.792808289546014120, 0.609319065028276820, - -0.792925139589524260, - 0.609167012336453210, -0.793041960479443640, 0.609014937247299940, - -0.793158752211477140, - 0.608862839766408200, -0.793275514781330630, 0.608710719899370420, - -0.793392248184711100, - 0.608558577651779450, -0.793508952417326660, 0.608406413029229260, - -0.793625627474886190, - 0.608254226037314490, -0.793742273353100100, 0.608102016681630550, - -0.793858890047679620, - 0.607949784967773740, -0.793975477554337170, 0.607797530901341140, - -0.794092035868785960, - 0.607645254487930830, -0.794208564986740640, 0.607492955733141660, - -0.794325064903916520, - 0.607340634642572930, -0.794441535616030590, 0.607188291221825160, - -0.794557977118800270, - 0.607035925476499760, -0.794674389407944550, 0.606883537412198580, - -0.794790772479183170, - 0.606731127034524480, -0.794907126328237010, 0.606578694349081400, - -0.795023450950828050, - 0.606426239361473550, -0.795139746342679590, 0.606273762077306430, - -0.795256012499515500, - 0.606121262502186230, -0.795372249417061190, 0.605968740641719790, - -0.795488457091042990, - 0.605816196501515080, -0.795604635517188070, 0.605663630087180490, - -0.795720784691225090, - 0.605511041404325550, -0.795836904608883460, 0.605358430458560530, - -0.795952995265893910, - 0.605205797255496500, -0.796069056657987990, 0.605053141800745430, - -0.796185088780898440, - 0.604900464099919930, -0.796301091630359110, 0.604747764158633410, - -0.796417065202104980, - 0.604595041982500360, -0.796533009491872000, 0.604442297577135970, - -0.796648924495397150, - 0.604289530948156070, -0.796764810208418720, 0.604136742101177630, - -0.796880666626675780, - 0.603983931041818020, -0.796996493745908750, 0.603831097775695880, - -0.797112291561858920, - 0.603678242308430370, -0.797228060070268700, 0.603525364645641550, - -0.797343799266881700, - 0.603372464792950370, -0.797459509147442460, 0.603219542755978440, - -0.797575189707696590, - 0.603066598540348280, -0.797690840943391040, 0.602913632151683140, - -0.797806462850273570, - 0.602760643595607220, -0.797922055424093000, 0.602607632877745550, - -0.798037618660599410, - 0.602454600003723860, -0.798153152555543750, 0.602301544979168550, - -0.798268657104678310, - 0.602148467809707320, -0.798384132303756380, 0.601995368500968130, - -0.798499578148532010, - 0.601842247058580030, -0.798614994634760820, 0.601689103488173060, - -0.798730381758199210, - 0.601535937795377730, -0.798845739514604580, 0.601382749985825420, - -0.798961067899735760, - 0.601229540065148620, -0.799076366909352350, 0.601076308038980160, - -0.799191636539215210, - 0.600923053912954090, -0.799306876785086160, 0.600769777692705230, - -0.799422087642728040, - 0.600616479383868970, -0.799537269107905010, 0.600463158992081690, - -0.799652421176382130, - 0.600309816522980430, -0.799767543843925680, 0.600156451982203350, - -0.799882637106302810, - 0.600003065375389060, -0.799997700959281910, 0.599849656708177360, - -0.800112735398632370, - 0.599696225986208310, -0.800227740420124790, 0.599542773215123390, - -0.800342716019530660, - 0.599389298400564540, -0.800457662192622710, 0.599235801548174570, - -0.800572578935174750, - 0.599082282663597310, -0.800687466242961500, 0.598928741752476900, - -0.800802324111759110, - 0.598775178820458720, -0.800917152537344300, 0.598621593873188920, - -0.801031951515495330, - 0.598467986916314310, -0.801146721041991250, 0.598314357955482600, - -0.801261461112612540, - 0.598160706996342380, -0.801376171723140130, 0.598007034044542700, - -0.801490852869356840, - 0.597853339105733910, -0.801605504547046040, 0.597699622185566830, - -0.801720126751992330, - 0.597545883289693270, -0.801834719479981310, 0.597392122423765710, - -0.801949282726799660, - 0.597238339593437530, -0.802063816488235440, 0.597084534804362740, - -0.802178320760077450, - 0.596930708062196500, -0.802292795538115720, 0.596776859372594500, - -0.802407240818141300, - 0.596622988741213330, -0.802521656595946320, 0.596469096173710360, - -0.802636042867324150, - 0.596315181675743820, -0.802750399628069160, 0.596161245252972540, - -0.802864726873976590, - 0.596007286911056530, -0.802979024600843140, 0.595853306655656390, - -0.803093292804466400, - 0.595699304492433470, -0.803207531480644830, 0.595545280427049790, - -0.803321740625178470, - 0.595391234465168730, -0.803435920233868120, 0.595237166612453850, - -0.803550070302515570, - 0.595083076874569960, -0.803664190826924090, 0.594928965257182420, - -0.803778281802897570, - 0.594774831765957580, -0.803892343226241260, 0.594620676406562240, - -0.804006375092761520, - 0.594466499184664540, -0.804120377398265700, 0.594312300105932830, - -0.804234350138562260, - 0.594158079176036800, -0.804348293309460780, 0.594003836400646690, - -0.804462206906771840, - 0.593849571785433630, -0.804576090926307000, 0.593695285336069300, - -0.804689945363879500, - 0.593540977058226390, -0.804803770215302810, 0.593386646957578480, - -0.804917565476392150, - 0.593232295039799800, -0.805031331142963660, 0.593077921310565580, - -0.805145067210834120, - 0.592923525775551410, -0.805258773675822210, 0.592769108440434070, - -0.805372450533747060, - 0.592614669310891130, -0.805486097780429120, 0.592460208392600940, - -0.805599715411689950, - 0.592305725691242400, -0.805713303423352120, 0.592151221212495640, - -0.805826861811239300, - 0.591996694962040990, -0.805940390571176280, 0.591842146945560250, - -0.806053889698988950, - 0.591687577168735550, -0.806167359190504310, 0.591532985637249990, - -0.806280799041550370, - 0.591378372356787580, -0.806394209247956240, 0.591223737333032910, - -0.806507589805552260, - 0.591069080571671510, -0.806620940710169650, 0.590914402078389520, - -0.806734261957640750, - 0.590759701858874280, -0.806847553543799220, 0.590604979918813440, - -0.806960815464479620, - 0.590450236263895920, -0.807074047715517610, 0.590295470899810940, - -0.807187250292749850, - 0.590140683832248940, -0.807300423192014450, 0.589985875066900920, - -0.807413566409150190, - 0.589831044609458900, -0.807526679939997160, 0.589676192465615420, - -0.807639763780396370, - 0.589521318641063940, -0.807752817926190360, 0.589366423141498790, - -0.807865842373222120, - 0.589211505972615070, -0.807978837117336310, 0.589056567140108460, - -0.808091802154378260, - 0.588901606649675840, -0.808204737480194720, 0.588746624507014650, - -0.808317643090633250, - 0.588591620717822890, -0.808430518981542720, 0.588436595287799900, - -0.808543365148773010, - 0.588281548222645330, -0.808656181588174980, 0.588126479528059850, - -0.808768968295600850, - 0.587971389209745120, -0.808881725266903610, 0.587816277273403020, - -0.808994452497937560, - 0.587661143724736770, -0.809107149984558130, 0.587505988569450020, - -0.809219817722621750, - 0.587350811813247660, -0.809332455707985840, 0.587195613461834910, - -0.809445063936509170, - 0.587040393520918080, -0.809557642404051260, 0.586885151996203950, - -0.809670191106473090, - 0.586729888893400500, -0.809782710039636420, 0.586574604218216280, - -0.809895199199404450, - 0.586419297976360500, -0.810007658581641140, 0.586263970173543700, - -0.810120088182211600, - 0.586108620815476430, -0.810232487996982330, 0.585953249907870680, - -0.810344858021820550, - 0.585797857456438860, -0.810457198252594770, 0.585642443466894420, - -0.810569508685174630, - 0.585487007944951450, -0.810681789315430670, 0.585331550896324940, - -0.810794040139234730, - 0.585176072326730410, -0.810906261152459670, 0.585020572241884530, - -0.811018452350979470, - 0.584865050647504490, -0.811130613730669190, 0.584709507549308500, - -0.811242745287404810, - 0.584553942953015330, -0.811354847017063730, 0.584398356864344710, - -0.811466918915524250, - 0.584242749289016980, -0.811578960978665890, 0.584087120232753550, - -0.811690973202369050, - 0.583931469701276300, -0.811802955582515360, 0.583775797700308070, - -0.811914908114987680, - 0.583620104235572760, -0.812026830795669730, 0.583464389312794430, - -0.812138723620446480, - 0.583308652937698290, -0.812250586585203880, 0.583152895116010540, - -0.812362419685829120, - 0.582997115853457700, -0.812474222918210480, 0.582841315155767650, - -0.812585996278237020, - 0.582685493028668460, -0.812697739761799490, 0.582529649477889320, - -0.812809453364789160, - 0.582373784509160220, -0.812921137083098770, 0.582217898128211790, - -0.813032790912621930, - 0.582061990340775550, -0.813144414849253590, 0.581906061152583920, - -0.813256008888889380, - 0.581750110569369760, -0.813367573027426570, 0.581594138596866930, - -0.813479107260763220, - 0.581438145240810280, -0.813590611584798510, 0.581282130506935110, - -0.813702085995432700, - 0.581126094400977620, -0.813813530488567190, 0.580970036928674880, - -0.813924945060104490, - 0.580813958095764530, -0.814036329705948300, 0.580657857907985410, - -0.814147684422003360, - 0.580501736371076600, -0.814259009204175270, 0.580345593490778300, - -0.814370304048371070, - 0.580189429272831680, -0.814481568950498610, 0.580033243722978150, - -0.814592803906467270, - 0.579877036846960350, -0.814704008912187080, 0.579720808650521560, - -0.814815183963569330, - 0.579564559139405740, -0.814926329056526620, 0.579408288319357980, - -0.815037444186972220, - 0.579251996196123550, -0.815148529350820830, 0.579095682775449210, - -0.815259584543988280, - 0.578939348063081890, -0.815370609762391290, 0.578782992064769690, - -0.815481605001947770, - 0.578626614786261430, -0.815592570258576680, 0.578470216233306740, - -0.815703505528198260, - 0.578313796411655590, -0.815814410806733780, 0.578157355327059360, - -0.815925286090105390, - 0.578000892985269910, -0.816036131374236700, 0.577844409392039850, - -0.816146946655052160, - 0.577687904553122800, -0.816257731928477390, 0.577531378474272830, - -0.816368487190439200, - 0.577374831161244880, -0.816479212436865390, 0.577218262619794920, - -0.816589907663684890, - 0.577061672855679550, -0.816700572866827850, 0.576905061874655960, - -0.816811208042225290, - 0.576748429682482520, -0.816921813185809480, 0.576591776284917870, - -0.817032388293513880, - 0.576435101687721830, -0.817142933361272970, 0.576278405896654910, - -0.817253448385022230, - 0.576121688917478390, -0.817363933360698460, 0.575964950755954330, - -0.817474388284239240, - 0.575808191417845340, -0.817584813151583710, 0.575651410908915250, - -0.817695207958671680, - 0.575494609234928230, -0.817805572701444270, 0.575337786401649560, - -0.817915907375843740, - 0.575180942414845190, -0.818026211977813440, 0.575024077280281820, - -0.818136486503297620, - 0.574867191003726740, -0.818246730948241960, 0.574710283590948450, - -0.818356945308593150, - 0.574553355047715760, -0.818467129580298660, 0.574396405379798750, - -0.818577283759307490, - 0.574239434592967890, -0.818687407841569570, 0.574082442692994470, - -0.818797501823036010, - 0.573925429685650750, -0.818907565699658950, 0.573768395576709560, - -0.819017599467391500, - 0.573611340371944610, -0.819127603122188240, 0.573454264077130400, - -0.819237576660004520, - 0.573297166698042320, -0.819347520076796900, 0.573140048240456060, - -0.819457433368523280, - 0.572982908710148680, -0.819567316531142230, 0.572825748112897550, - -0.819677169560613760, - 0.572668566454481160, -0.819786992452898990, 0.572511363740678790, - -0.819896785203959810, - 0.572354139977270030, -0.820006547809759680, 0.572196895170035580, - -0.820116280266262710, - 0.572039629324757050, -0.820225982569434690, 0.571882342447216590, - -0.820335654715241840, - 0.571725034543197120, -0.820445296699652050, 0.571567705618482580, - -0.820554908518633890, - 0.571410355678857340, -0.820664490168157460, 0.571252984730106660, - -0.820774041644193650, - 0.571095592778016690, -0.820883562942714580, 0.570938179828374360, - -0.820993054059693470, - 0.570780745886967370, -0.821102514991104650, 0.570623290959583860, - -0.821211945732923550, - 0.570465815052012990, -0.821321346281126740, 0.570308318170045010, - -0.821430716631691760, - 0.570150800319470300, -0.821540056780597610, 0.569993261506080650, - -0.821649366723823830, - 0.569835701735668110, -0.821758646457351640, 0.569678121014025710, - -0.821867895977163140, - 0.569520519346947250, -0.821977115279241550, 0.569362896740227330, - -0.822086304359571090, - 0.569205253199661200, -0.822195463214137170, 0.569047588731045220, - -0.822304591838926350, - 0.568889903340175970, -0.822413690229926390, 0.568732197032851160, - -0.822522758383125940, - 0.568574469814869250, -0.822631796294514990, 0.568416721692029390, - -0.822740803960084420, - 0.568258952670131490, -0.822849781375826320, 0.568101162754976570, - -0.822958728537734000, - 0.567943351952365670, -0.823067645441801670, 0.567785520268101250, - -0.823176532084024860, - 0.567627667707986230, -0.823285388460400110, 0.567469794277824620, - -0.823394214566925080, - 0.567311899983420800, -0.823503010399598390, 0.567153984830580100, - -0.823611775954420260, - 0.566996048825108680, -0.823720511227391320, 0.566838091972813320, - -0.823829216214513990, - 0.566680114279501710, -0.823937890911791370, 0.566522115750982100, - -0.824046535315227760, - 0.566364096393063950, -0.824155149420828570, 0.566206056211556840, - -0.824263733224600450, - 0.566047995212271560, -0.824372286722551250, 0.565889913401019570, - -0.824480809910689500, - 0.565731810783613230, -0.824589302785025290, 0.565573687365865440, - -0.824697765341569470, - 0.565415543153589770, -0.824806197576334330, 0.565257378152600910, - -0.824914599485333080, - 0.565099192368714090, -0.825022971064580220, 0.564940985807745320, - -0.825131312310090960, - 0.564782758475511400, -0.825239623217882130, 0.564624510377830120, - -0.825347903783971380, - 0.564466241520519500, -0.825456154004377440, 0.564307951909398750, - -0.825564373875120490, - 0.564149641550287680, -0.825672563392221390, 0.563991310449007080, - -0.825780722551702430, - 0.563832958611378170, -0.825888851349586780, 0.563674586043223180, - -0.825996949781898970, - 0.563516192750364910, -0.826105017844664610, 0.563357778738627020, - -0.826213055533910110, - 0.563199344013834090, -0.826321062845663420, 0.563040888581811230, - -0.826429039775953390, - 0.562882412448384550, -0.826536986320809960, 0.562723915619380400, - -0.826644902476264210, - 0.562565398100626560, -0.826752788238348520, 0.562406859897951140, - -0.826860643603096080, - 0.562248301017183150, -0.826968468566541490, 0.562089721464152480, - -0.827076263124720270, - 0.561931121244689470, -0.827184027273669020, 0.561772500364625450, - -0.827291761009425810, - 0.561613858829792420, -0.827399464328029350, 0.561455196646023280, - -0.827507137225519830, - 0.561296513819151470, -0.827614779697938400, 0.561137810355011530, - -0.827722391741327220, - 0.560979086259438260, -0.827829973351729810, 0.560820341538267540, - -0.827937524525190870, - 0.560661576197336030, -0.828045045257755800, 0.560502790242481060, - -0.828152535545471410, - 0.560343983679540860, -0.828259995384385550, 0.560185156514354080, - -0.828367424770547480, - 0.560026308752760380, -0.828474823700007130, 0.559867440400600320, - -0.828582192168815790, - 0.559708551463714790, -0.828689530173025710, 0.559549641947945870, - -0.828796837708690610, - 0.559390711859136140, -0.828904114771864870, 0.559231761203129010, - -0.829011361358604430, - 0.559072789985768480, -0.829118577464965980, 0.558913798212899770, - -0.829225763087007570, - 0.558754785890368310, -0.829332918220788250, 0.558595753024020760, - -0.829440042862368170, - 0.558436699619704100, -0.829547137007808800, 0.558277625683266330, - -0.829654200653172640, - 0.558118531220556100, -0.829761233794523050, 0.557959416237422960, - -0.829868236427924840, - 0.557800280739717100, -0.829975208549443840, 0.557641124733289420, - -0.830082150155146970, - 0.557481948223991660, -0.830189061241102370, 0.557322751217676160, - -0.830295941803379070, - 0.557163533720196340, -0.830402791838047550, 0.557004295737406060, - -0.830509611341179070, - 0.556845037275160100, -0.830616400308846200, 0.556685758339313890, - -0.830723158737122880, - 0.556526458935723720, -0.830829886622083570, 0.556367139070246490, - -0.830936583959804410, - 0.556207798748739930, -0.831043250746362320, 0.556048437977062720, - -0.831149886977835430, - 0.555889056761073920, -0.831256492650303210, 0.555729655106633520, - -0.831363067759845920, - 0.555570233019602290, -0.831469612302545240, 0.555410790505841740, - -0.831576126274483630, - 0.555251327571214090, -0.831682609671745120, 0.555091844221582420, - -0.831789062490414400, - 0.554932340462810370, -0.831895484726577590, 0.554772816300762580, - -0.832001876376321840, - 0.554613271741304040, -0.832108237435735480, 0.554453706790301040, - -0.832214567900907980, - 0.554294121453620110, -0.832320867767929680, 0.554134515737128910, - -0.832427137032892280, - 0.553974889646695610, -0.832533375691888680, 0.553815243188189090, - -0.832639583741012770, - 0.553655576367479310, -0.832745761176359460, 0.553495889190436570, - -0.832851907994024980, - 0.553336181662932410, -0.832958024190106670, 0.553176453790838460, - -0.833064109760702890, - 0.553016705580027580, -0.833170164701913190, 0.552856937036373290, - -0.833276189009838240, - 0.552697148165749770, -0.833382182680579730, 0.552537338974032120, - -0.833488145710240770, - 0.552377509467096070, -0.833594078094925140, 0.552217659650817930, - -0.833699979830738290, - 0.552057789531074980, -0.833805850913786340, 0.551897899113745320, - -0.833911691340176730, - 0.551737988404707450, -0.834017501106018130, 0.551578057409841000, - -0.834123280207419990, - 0.551418106135026060, -0.834229028640493420, 0.551258134586143700, - -0.834334746401350080, - 0.551098142769075430, -0.834440433486103190, 0.550938130689703880, - -0.834546089890866760, - 0.550778098353912230, -0.834651715611756330, 0.550618045767584330, - -0.834757310644888230, - 0.550457972936604810, -0.834862874986380010, 0.550297879866859190, - -0.834968408632350450, - 0.550137766564233630, -0.835073911578919300, 0.549977633034615000, - -0.835179383822207580, - 0.549817479283891020, -0.835284825358337370, 0.549657305317949980, - -0.835390236183431780, - 0.549497111142680960, -0.835495616293615350, 0.549336896763974010, - -0.835600965685013410, - 0.549176662187719770, -0.835706284353752600, 0.549016407419809390, - -0.835811572295960590, - 0.548856132466135290, -0.835916829507766360, 0.548695837332590090, - -0.836022055985299880, - 0.548535522025067390, -0.836127251724692160, 0.548375186549461600, - -0.836232416722075600, - 0.548214830911667780, -0.836337550973583530, 0.548054455117581880, - -0.836442654475350380, - 0.547894059173100190, -0.836547727223511890, 0.547733643084120200, - -0.836652769214204950, - 0.547573206856539870, -0.836757780443567190, 0.547412750496257930, - -0.836862760907737810, - 0.547252274009174090, -0.836967710602857020, 0.547091777401188530, - -0.837072629525066000, - 0.546931260678202190, -0.837177517670507190, 0.546770723846116800, - -0.837282375035324320, - 0.546610166910834860, -0.837387201615661940, 0.546449589878259760, - -0.837491997407665890, - 0.546288992754295210, -0.837596762407483040, 0.546128375544846060, - -0.837701496611261700, - 0.545967738255817680, -0.837806200015150940, 0.545807080893116140, - -0.837910872615301060, - 0.545646403462648590, -0.838015514407863700, 0.545485705970322530, - -0.838120125388991500, - 0.545324988422046460, -0.838224705554837970, 0.545164250823729320, - -0.838329254901558300, - 0.545003493181281160, -0.838433773425308340, 0.544842715500612470, - -0.838538261122245170, - 0.544681917787634530, -0.838642717988527300, 0.544521100048259710, - -0.838747144020313920, - 0.544360262288400400, -0.838851539213765760, 0.544199404513970420, - -0.838955903565044350, - 0.544038526730883930, -0.839060237070312630, 0.543877628945055980, - -0.839164539725734570, - 0.543716711162402390, -0.839268811527475230, 0.543555773388839650, - -0.839373052471700690, - 0.543394815630284800, -0.839477262554578550, 0.543233837892656000, - -0.839581441772277120, - 0.543072840181871850, -0.839685590120966110, 0.542911822503851730, - -0.839789707596816260, - 0.542750784864516000, -0.839893794195999410, 0.542589727269785270, - -0.839997849914688730, - 0.542428649725581360, -0.840101874749058400, 0.542267552237826520, - -0.840205868695283580, - 0.542106434812444030, -0.840309831749540770, 0.541945297455357470, - -0.840413763908007480, - 0.541784140172491660, -0.840517665166862440, 0.541622962969771640, - -0.840621535522285690, - 0.541461765853123560, -0.840725374970458070, 0.541300548828474120, - -0.840829183507561640, - 0.541139311901750910, -0.840932961129779670, 0.540978055078882190, - -0.841036707833296650, - 0.540816778365796670, -0.841140423614298080, 0.540655481768424260, - -0.841244108468970580, - 0.540494165292695230, -0.841347762393501950, 0.540332828944540820, - -0.841451385384081260, - 0.540171472729892970, -0.841554977436898330, 0.540010096654684020, - -0.841658538548144760, - 0.539848700724847700, -0.841762068714012490, 0.539687284946317570, - -0.841865567930695340, - 0.539525849325029010, -0.841969036194387680, 0.539364393866917150, - -0.842072473501285450, - 0.539202918577918240, -0.842175879847585570, 0.539041423463969550, - -0.842279255229485880, - 0.538879908531008420, -0.842382599643185960, 0.538718373784973670, - -0.842485913084885630, - 0.538556819231804210, -0.842589195550786600, 0.538395244877439950, - -0.842692447037091560, - 0.538233650727821700, -0.842795667540004120, 0.538072036788890600, - -0.842898857055729310, - 0.537910403066588990, -0.843002015580472830, 0.537748749566859470, - -0.843105143110442050, - 0.537587076295645510, -0.843208239641845440, 0.537425383258891660, - -0.843311305170892030, - 0.537263670462542530, -0.843414339693792760, 0.537101937912544240, - -0.843517343206759080, - 0.536940185614843020, -0.843620315706004040, 0.536778413575385920, - -0.843723257187741550, - 0.536616621800121150, -0.843826167648186740, 0.536454810294997090, - -0.843929047083555870, - 0.536292979065963180, -0.844031895490066410, 0.536131128118969350, - -0.844134712863936930, - 0.535969257459966710, -0.844237499201387020, 0.535807367094906620, - -0.844340254498637590, - 0.535645457029741090, -0.844442978751910660, 0.535483527270423370, - -0.844545671957429240, - 0.535321577822907010, -0.844648334111417820, 0.535159608693146720, - -0.844750965210101510, - 0.534997619887097260, -0.844853565249707010, 0.534835611410714670, - -0.844956134226462100, - 0.534673583269955510, -0.845058672136595470, 0.534511535470777010, - -0.845161178976337140, - 0.534349468019137520, -0.845263654741918220, 0.534187380920995600, - -0.845366099429570970, - 0.534025274182310380, -0.845468513035528830, 0.533863147809042650, - -0.845570895556026270, - 0.533701001807152960, -0.845673246987299070, 0.533538836182603120, - -0.845775567325583900, - 0.533376650941355560, -0.845877856567118890, 0.533214446089372960, - -0.845980114708143270, - 0.533052221632619670, -0.846082341744896940, 0.532889977577059690, - -0.846184537673621670, - 0.532727713928658810, -0.846286702490559710, 0.532565430693382580, - -0.846388836191954930, - 0.532403127877198010, -0.846490938774052020, 0.532240805486072330, - -0.846593010233097190, - 0.532078463525973540, -0.846695050565337450, 0.531916102002870760, - -0.846797059767020910, - 0.531753720922733320, -0.846899037834397350, 0.531591320291531780, - -0.847000984763716880, - 0.531428900115236910, -0.847102900551231500, 0.531266460399820390, - -0.847204785193193980, - 0.531104001151255000, -0.847306638685858320, 0.530941522375513510, - -0.847408461025479730, - 0.530779024078570250, -0.847510252208314330, 0.530616506266399450, - -0.847612012230619660, - 0.530453968944976320, -0.847713741088654270, 0.530291412120277420, - -0.847815438778677930, - 0.530128835798278850, -0.847917105296951410, 0.529966239984958620, - -0.848018740639736810, - 0.529803624686294830, -0.848120344803297120, 0.529640989908265910, - -0.848221917783896990, - 0.529478335656852090, -0.848323459577801530, 0.529315661938033140, - -0.848424970181277600, - 0.529152968757790720, -0.848526449590592650, 0.528990256122106040, - -0.848627897802015860, - 0.528827524036961980, -0.848729314811817010, 0.528664772508341540, - -0.848830700616267530, - 0.528502001542228480, -0.848932055211639610, 0.528339211144607690, - -0.849033378594206690, - 0.528176401321464370, -0.849134670760243630, 0.528013572078784740, - -0.849235931706025960, - 0.527850723422555460, -0.849337161427830670, 0.527687855358763720, - -0.849438359921935950, - 0.527524967893398200, -0.849539527184620890, 0.527362061032447430, - -0.849640663212165910, - 0.527199134781901390, -0.849741768000852440, 0.527036189147750190, - -0.849842841546963210, - 0.526873224135984700, -0.849943883846782210, 0.526710239752597010, - -0.850044894896594070, - 0.526547236003579330, -0.850145874692685210, 0.526384212894925210, - -0.850246823231342710, - 0.526221170432628170, -0.850347740508854980, 0.526058108622682760, - -0.850448626521511650, - 0.525895027471084740, -0.850549481265603370, 0.525731926983829640, - -0.850650304737422200, - 0.525568807166914680, -0.850751096933260790, 0.525405668026336810, - -0.850851857849413640, - 0.525242509568094710, -0.850952587482175730, 0.525079331798186890, - -0.851053285827843790, - 0.524916134722612890, -0.851153952882715340, 0.524752918347373360, - -0.851254588643089120, - 0.524589682678468840, -0.851355193105265200, 0.524426427721901510, - -0.851455766265544310, - 0.524263153483673470, -0.851556308120228870, 0.524099859969787810, - -0.851656818665622370, - 0.523936547186248600, -0.851757297898029120, 0.523773215139060170, - -0.851857745813754840, - 0.523609863834228030, -0.851958162409106380, 0.523446493277757940, - -0.852058547680391580, - 0.523283103475656430, -0.852158901623919830, 0.523119694433931250, - -0.852259224236001090, - 0.522956266158590140, -0.852359515512947090, 0.522792818655642200, - -0.852459775451070100, - 0.522629351931096720, -0.852560004046683970, 0.522465865990963900, - -0.852660201296103760, - 0.522302360841254700, -0.852760367195645300, 0.522138836487980650, - -0.852860501741625860, - 0.521975292937154390, -0.852960604930363630, 0.521811730194788550, - -0.853060676758178320, - 0.521648148266897090, -0.853160717221390420, 0.521484547159494550, - -0.853260726316321770, - 0.521320926878595550, -0.853360704039295430, 0.521157287430216610, - -0.853460650386635320, - 0.520993628820373810, -0.853560565354666840, 0.520829951055084780, - -0.853660448939716270, - 0.520666254140367270, -0.853760301138111300, 0.520502538082239790, - -0.853860121946180660, - 0.520338802886721960, -0.853959911360254060, 0.520175048559833760, - -0.854059669376662780, - 0.520011275107596040, -0.854159395991738730, 0.519847482536030300, - -0.854259091201815420, - 0.519683670851158520, -0.854358755003227440, 0.519519840059003870, - -0.854458387392310060, - 0.519355990165589530, -0.854557988365400530, 0.519192121176940360, - -0.854657557918836460, - 0.519028233099080970, -0.854757096048957110, 0.518864325938037000, - -0.854856602752102850, - 0.518700399699835170, -0.854956078024614820, 0.518536454390502110, - -0.855055521862835950, - 0.518372490016066220, -0.855154934263109620, 0.518208506582555460, - -0.855254315221781080, - 0.518044504095999340, -0.855353664735196030, 0.517880482562427800, - -0.855452982799701830, - 0.517716441987871150, -0.855552269411646970, 0.517552382378360990, - -0.855651524567380690, - 0.517388303739929060, -0.855750748263253920, 0.517224206078608310, - -0.855849940495618240, - 0.517060089400432130, -0.855949101260826790, 0.516895953711434260, - -0.856048230555233820, - 0.516731799017649980, -0.856147328375194470, 0.516567625325114350, - -0.856246394717065210, - 0.516403432639863990, -0.856345429577203610, 0.516239220967935620, - -0.856444432951968480, - 0.516074990315366630, -0.856543404837719960, 0.515910740688195650, - -0.856642345230818720, - 0.515746472092461380, -0.856741254127627470, 0.515582184534203790, - -0.856840131524509220, - 0.515417878019463150, -0.856938977417828650, 0.515253552554280290, - -0.857037791803951680, - 0.515089208144697270, -0.857136574679244870, 0.514924844796756490, - -0.857235326040076460, - 0.514760462516501200, -0.857334045882815590, 0.514596061309975040, - -0.857432734203832700, - 0.514431641183222930, -0.857531390999499040, 0.514267202142289830, - -0.857630016266187620, - 0.514102744193221660, -0.857728610000272120, 0.513938267342065490, - -0.857827172198127320, - 0.513773771594868030, -0.857925702856129790, 0.513609256957677900, - -0.858024201970656540, - 0.513444723436543570, -0.858122669538086020, 0.513280171037514330, - -0.858221105554798250, - 0.513115599766640560, -0.858319510017173440, 0.512951009629972860, - -0.858417882921594040, - 0.512786400633563070, -0.858516224264442740, 0.512621772783463100, - -0.858614534042104080, - 0.512457126085725800, -0.858712812250963520, 0.512292460546404980, - -0.858811058887407500, - 0.512127776171554690, -0.858909273947823900, 0.511963072967230200, - -0.859007457428601410, - 0.511798350939487000, -0.859105609326130340, 0.511633610094381350, - -0.859203729636801920, - 0.511468850437970520, -0.859301818357008360, 0.511304071976311890, - -0.859399875483143450, - 0.511139274715464390, -0.859497901011601620, 0.510974458661486720, - -0.859595894938779080, - 0.510809623820439040, -0.859693857261072610, 0.510644770198381730, - -0.859791787974880540, - 0.510479897801375700, -0.859889687076602290, 0.510315006635483350, - -0.859987554562638200, - 0.510150096706766700, -0.860085390429390140, 0.509985168021289570, - -0.860183194673260880, - 0.509820220585115560, -0.860280967290654510, 0.509655254404309250, - -0.860378708277976130, - 0.509490269484936360, -0.860476417631632070, 0.509325265833062480, - -0.860574095348029980, - 0.509160243454754750, -0.860671741423578380, 0.508995202356080310, - -0.860769355854687060, - 0.508830142543106990, -0.860866938637767310, 0.508665064021904260, - -0.860964489769230900, - 0.508499966798540810, -0.861062009245491480, 0.508334850879087470, - -0.861159497062963350, - 0.508169716269614710, -0.861256953218062060, 0.508004562976194010, - -0.861354377707204800, - 0.507839391004897940, -0.861451770526809210, 0.507674200361798890, - -0.861549131673294720, - 0.507508991052970870, -0.861646461143081300, 0.507343763084487920, - -0.861743758932590700, - 0.507178516462425290, -0.861841025038245330, 0.507013251192858340, - -0.861938259456469180, - 0.506847967281863320, -0.862035462183687210, 0.506682664735517600, - -0.862132633216325380, - 0.506517343559898530, -0.862229772550811240, 0.506352003761084800, - -0.862326880183573060, - 0.506186645345155450, -0.862423956111040500, 0.506021268318189830, - -0.862521000329644520, - 0.505855872686268860, -0.862618012835816740, 0.505690458455473340, - -0.862714993625990690, - 0.505525025631885510, -0.862811942696600330, 0.505359574221587390, - -0.862908860044081290, - 0.505194104230662240, -0.863005745664870210, 0.505028615665194300, - -0.863102599555404800, - 0.504863108531267480, -0.863199421712124160, 0.504697582834967680, - -0.863296212131468230, - 0.504532038582380380, -0.863392970809878310, 0.504366475779592150, - -0.863489697743797140, - 0.504200894432690560, -0.863586392929667990, 0.504035294547763080, - -0.863683056363935940, - 0.503869676130898950, -0.863779688043046610, 0.503704039188186960, - -0.863876287963447510, - 0.503538383725717580, -0.863972856121586700, 0.503372709749581150, - -0.864069392513913680, - 0.503207017265869030, -0.864165897136879300, 0.503041306280673450, - -0.864262369986934950, - 0.502875576800086880, -0.864358811060534030, 0.502709828830203100, - -0.864455220354130250, - 0.502544062377115800, -0.864551597864179230, 0.502378277446919870, - -0.864647943587137480, - 0.502212474045710900, -0.864744257519462380, 0.502046652179584660, - -0.864840539657612980, - 0.501880811854638400, -0.864936789998049020, 0.501714953076969230, - -0.865033008537231750, - 0.501549075852675390, -0.865129195271623690, 0.501383180187855880, - -0.865225350197688090, - 0.501217266088609950, -0.865321473311889800, 0.501051333561038040, - -0.865417564610694410, - 0.500885382611240940, -0.865513624090568980, 0.500719413245319880, - -0.865609651747981880, - 0.500553425469377640, -0.865705647579402270, 0.500387419289516580, - -0.865801611581300760, - 0.500221394711840680, -0.865897543750148820, 0.500055351742453860, - -0.865993444082419520, - 0.499889290387461380, -0.866089312574586770, 0.499723210652968710, - -0.866185149223125730, - 0.499557112545081890, -0.866280954024512990, 0.499390996069908220, - -0.866376726975225830, - 0.499224861233555030, -0.866472468071743050, 0.499058708042130930, - -0.866568177310544360, - 0.498892536501744750, -0.866663854688111020, 0.498726346618505960, - -0.866759500200925290, - 0.498560138398525200, -0.866855113845470320, 0.498393911847913150, - -0.866950695618231020, - 0.498227666972781870, -0.867046245515692650, 0.498061403779243520, - -0.867141763534342360, - 0.497895122273410930, -0.867237249670668400, 0.497728822461398100, - -0.867332703921159690, - 0.497562504349319090, -0.867428126282306920, 0.497396167943289340, - -0.867523516750601460, - 0.497229813249424340, -0.867618875322536230, 0.497063440273840310, - -0.867714201994605140, - 0.496897049022654640, -0.867809496763303210, 0.496730639501984710, - -0.867904759625126920, - 0.496564211717949340, -0.867999990576573400, 0.496397765676667160, - -0.868095189614141670, - 0.496231301384258310, -0.868190356734331310, 0.496064818846843060, - -0.868285491933643240, - 0.495898318070542240, -0.868380595208579800, 0.495731799061478020, - -0.868475666555644120, - 0.495565261825772490, -0.868570705971340900, 0.495398706369549080, - -0.868665713452175580, - 0.495232132698931350, -0.868760688994655190, 0.495065540820043610, - -0.868855632595287750, - 0.494898930739011310, -0.868950544250582380, 0.494732302461959820, - -0.869045423957049530, - 0.494565655995016010, -0.869140271711200560, 0.494398991344306760, - -0.869235087509548250, - 0.494232308515959730, -0.869329871348606730, 0.494065607516103730, - -0.869424623224890780, - 0.493898888350867430, -0.869519343134916970, 0.493732151026381070, - -0.869614031075202300, - 0.493565395548774880, -0.869708687042265560, 0.493398621924179830, - -0.869803311032626650, - 0.493231830158728070, -0.869897903042806340, 0.493065020258551650, - -0.869992463069326870, - 0.492898192229784090, -0.870086991108711350, 0.492731346078558840, - -0.870181487157484560, - 0.492564481811010650, -0.870275951212171830, 0.492397599433274550, - -0.870370383269300160, - 0.492230698951486080, -0.870464783325397670, 0.492063780371782060, - -0.870559151376993250, - 0.491896843700299240, -0.870653487420617540, 0.491729888943175820, - -0.870747791452801790, - 0.491562916106550060, -0.870842063470078860, 0.491395925196560830, - -0.870936303468982760, - 0.491228916219348330, -0.871030511446048260, 0.491061889181052590, - -0.871124687397811900, - 0.490894844087815140, -0.871218831320810900, 0.490727780945777570, - -0.871312943211583920, - 0.490560699761082080, -0.871407023066670950, 0.490393600539872130, - -0.871501070882612530, - 0.490226483288291100, -0.871595086655951090, 0.490059348012483910, - -0.871689070383229740, - 0.489892194718595300, -0.871783022060993010, 0.489725023412770970, - -0.871876941685786890, - 0.489557834101157550, -0.871970829254157700, 0.489390626789901920, - -0.872064684762653970, - 0.489223401485152030, -0.872158508207824480, 0.489056158193055980, - -0.872252299586219860, - 0.488888896919763230, -0.872346058894391540, 0.488721617671423250, - -0.872439786128892280, - 0.488554320454186230, -0.872533481286276060, 0.488387005274203590, - -0.872627144363097960, - 0.488219672137626740, -0.872720775355914300, 0.488052321050608310, - -0.872814374261282390, - 0.487884952019301210, -0.872907941075760970, 0.487717565049858860, - -0.873001475795909920, - 0.487550160148436050, -0.873094978418290090, 0.487382737321187310, - -0.873188448939463790, - 0.487215296574268820, -0.873281887355994210, 0.487047837913836550, - -0.873375293664446000, - 0.486880361346047400, -0.873468667861384880, 0.486712866877059340, - -0.873562009943377740, - 0.486545354513030270, -0.873655319906992630, 0.486377824260119500, - -0.873748597748798870, - 0.486210276124486530, -0.873841843465366750, 0.486042710112291390, - -0.873935057053268130, - 0.485875126229695420, -0.874028238509075630, 0.485707524482859750, - -0.874121387829363330, - 0.485539904877947020, -0.874214505010706300, 0.485372267421119770, - -0.874307590049680950, - 0.485204612118541880, -0.874400642942864790, 0.485036938976377450, - -0.874493663686836450, - 0.484869248000791120, -0.874586652278176110, 0.484701539197948730, - -0.874679608713464510, - 0.484533812574016120, -0.874772532989284150, 0.484366068135160480, - -0.874865425102218210, - 0.484198305887549140, -0.874958285048851540, 0.484030525837350010, - -0.875051112825769970, - 0.483862727990732320, -0.875143908429560250, 0.483694912353865080, - -0.875236671856810870, - 0.483527078932918740, -0.875329403104110780, 0.483359227734063980, - -0.875422102168050830, - 0.483191358763471910, -0.875514769045222740, 0.483023472027315050, - -0.875607403732219240, - 0.482855567531765670, -0.875700006225634600, 0.482687645282997510, - -0.875792576522063880, - 0.482519705287184520, -0.875885114618103700, 0.482351747550501030, - -0.875977620510351660, - 0.482183772079122830, -0.876070094195406600, 0.482015778879225530, - -0.876162535669868460, - 0.481847767956986080, -0.876254944930338400, 0.481679739318581490, - -0.876347321973419020, - 0.481511692970189920, -0.876439666795713610, 0.481343628917989870, - -0.876531979393827100, - 0.481175547168160360, -0.876624259764365310, 0.481007447726881640, - -0.876716507903935400, - 0.480839330600333900, -0.876808723809145760, 0.480671195794698690, - -0.876900907476605650, - 0.480503043316157670, -0.876993058902925780, 0.480334873170893070, - -0.877085178084718310, - 0.480166685365088440, -0.877177265018595940, 0.479998479904927220, - -0.877269319701173170, - 0.479830256796594250, -0.877361342129065140, 0.479662016046274340, - -0.877453332298888560, - 0.479493757660153060, -0.877545290207261240, 0.479325481644417130, - -0.877637215850802120, - 0.479157188005253310, -0.877729109226131570, 0.478988876748849550, - -0.877820970329870500, - 0.478820547881394050, -0.877912799158641730, 0.478652201409075550, - -0.878004595709069080, - 0.478483837338084080, -0.878096359977777130, 0.478315455674609480, - -0.878188091961392250, - 0.478147056424843120, -0.878279791656541460, 0.477978639594976110, - -0.878371459059853590, - 0.477810205191201040, -0.878463094167957870, 0.477641753219710590, - -0.878554696977485340, - 0.477473283686698060, -0.878646267485068130, 0.477304796598358010, - -0.878737805687339280, - 0.477136291960884750, -0.878829311580933360, 0.476967769780474230, - -0.878920785162485840, - 0.476799230063322250, -0.879012226428633410, 0.476630672815625380, - -0.879103635376014330, - 0.476462098043581310, -0.879195012001267370, 0.476293505753387750, - -0.879286356301033250, - 0.476124895951243630, -0.879377668271953180, 0.475956268643348220, - -0.879468947910670100, - 0.475787623835901120, -0.879560195213827890, 0.475618961535103410, - -0.879651410178071470, - 0.475450281747155870, -0.879742592800047410, 0.475281584478260800, - -0.879833743076402940, - 0.475112869734620470, -0.879924861003786860, 0.474944137522437860, - -0.880015946578848960, - 0.474775387847917230, -0.880106999798240360, 0.474606620717262560, - -0.880198020658613190, - 0.474437836136679340, -0.880289009156620890, 0.474269034112372920, - -0.880379965288918260, - 0.474100214650550020, -0.880470889052160750, 0.473931377757417560, - -0.880561780443005590, - 0.473762523439182850, -0.880652639458111010, 0.473593651702054640, - -0.880743466094136230, - 0.473424762552241530, -0.880834260347742040, 0.473255855995953380, - -0.880925022215589880, - 0.473086932039400220, -0.881015751694342760, 0.472917990688792760, - -0.881106448780665130, - 0.472749031950342900, -0.881197113471221980, 0.472580055830262250, - -0.881287745762680100, - 0.472411062334764100, -0.881378345651706810, 0.472242051470061650, - -0.881468913134971330, - 0.472073023242368660, -0.881559448209143780, 0.471903977657900320, - -0.881649950870895260, - 0.471734914722871430, -0.881740421116898320, 0.471565834443498480, - -0.881830858943826620, - 0.471396736825997810, -0.881921264348354940, 0.471227621876586400, - -0.882011637327159590, - 0.471058489601482610, -0.882101977876917580, 0.470889340006904520, - -0.882192285994307430, - 0.470720173099071710, -0.882282561676008600, 0.470550988884203490, - -0.882372804918702290, - 0.470381787368520710, -0.882463015719070040, 0.470212568558244280, - -0.882553194073795400, - 0.470043332459595620, -0.882643339979562790, 0.469874079078797470, - -0.882733453433057540, - 0.469704808422072460, -0.882823534430966730, 0.469535520495644510, - -0.882913582969978020, - 0.469366215305737630, -0.883003599046780720, 0.469196892858576630, - -0.883093582658065370, - 0.469027553160387240, -0.883183533800523280, 0.468858196217395330, - -0.883273452470847430, - 0.468688822035827960, -0.883363338665731580, 0.468519430621912420, - -0.883453192381870920, - 0.468350021981876530, -0.883543013615961880, 0.468180596121949400, - -0.883632802364701760, - 0.468011153048359830, -0.883722558624789660, 0.467841692767338220, - -0.883812282392925090, - 0.467672215285114710, -0.883901973665809470, 0.467502720607920920, - -0.883991632440144890, - 0.467333208741988530, -0.884081258712634990, 0.467163679693549770, - -0.884170852479984500, - 0.466994133468838110, -0.884260413738899080, 0.466824570074086950, - -0.884349942486086120, - 0.466654989515530970, -0.884439438718253700, 0.466485391799405010, - -0.884528902432111350, - 0.466315776931944480, -0.884618333624369920, 0.466146144919386000, - -0.884707732291740930, - 0.465976495767966130, -0.884797098430937790, 0.465806829483922770, - -0.884886432038674560, - 0.465637146073493770, -0.884975733111666660, 0.465467445542917800, - -0.885065001646630930, - 0.465297727898434650, -0.885154237640285110, 0.465127993146283950, - -0.885243441089348270, - 0.464958241292706740, -0.885332611990540590, 0.464788472343944160, - -0.885421750340583570, - 0.464618686306237820, -0.885510856136199950, 0.464448883185830770, - -0.885599929374113360, - 0.464279062988965760, -0.885688970051048960, 0.464109225721887010, - -0.885777978163732940, - 0.463939371390838460, -0.885866953708892790, 0.463769500002065680, - -0.885955896683257030, - 0.463599611561814120, -0.886044807083555490, 0.463429706076329880, - -0.886133684906519340, - 0.463259783551860260, -0.886222530148880640, 0.463089843994652470, - -0.886311342807372890, - 0.462919887410955130, -0.886400122878730490, 0.462749913807016850, - -0.886488870359689600, - 0.462579923189086810, -0.886577585246987040, 0.462409915563415540, - -0.886666267537360890, - 0.462239890936253280, -0.886754917227550950, 0.462069849313851810, - -0.886843534314297300, - 0.461899790702462840, -0.886932118794342080, 0.461729715108338770, - -0.887020670664428360, - 0.461559622537733190, -0.887109189921300060, 0.461389512996899450, - -0.887197676561702900, - 0.461219386492092430, -0.887286130582383150, 0.461049243029567010, - -0.887374551980088740, - 0.460879082615578690, -0.887462940751568840, 0.460708905256384190, - -0.887551296893573370, - 0.460538710958240010, -0.887639620402853930, 0.460368499727404070, - -0.887727911276163020, - 0.460198271570134270, -0.887816169510254550, 0.460028026492689700, - -0.887904395101883240, - 0.459857764501329650, -0.887992588047805560, 0.459687485602313870, - -0.888080748344778900, - 0.459517189801903590, -0.888168875989561620, 0.459346877106359570, - -0.888256970978913870, - 0.459176547521944150, -0.888345033309596240, 0.459006201054919680, - -0.888433062978371320, - 0.458835837711549120, -0.888521059982002260, 0.458665457498096670, - -0.888609024317253750, - 0.458495060420826220, -0.888696955980891710, 0.458324646486003300, - -0.888784854969682850, - 0.458154215699893230, -0.888872721280395520, 0.457983768068762180, - -0.888960554909799310, - 0.457813303598877290, -0.889048355854664570, 0.457642822296505770, - -0.889136124111763240, - 0.457472324167916110, -0.889223859677868210, 0.457301809219376800, - -0.889311562549753850, - 0.457131277457156980, -0.889399232724195520, 0.456960728887527030, - -0.889486870197969790, - 0.456790163516757220, -0.889574474967854580, 0.456619581351118960, - -0.889662047030628790, - 0.456448982396883860, -0.889749586383072890, 0.456278366660324670, - -0.889837093021967900, - 0.456107734147714220, -0.889924566944096720, 0.455937084865326030, - -0.890012008146243260, - 0.455766418819434750, -0.890099416625192210, 0.455595736016314920, - -0.890186792377730240, - 0.455425036462242420, -0.890274135400644480, 0.455254320163493210, - -0.890361445690723730, - 0.455083587126343840, -0.890448723244757880, 0.454912837357072050, - -0.890535968059537830, - 0.454742070861955450, -0.890623180131855930, 0.454571287647273000, - -0.890710359458505520, - 0.454400487719303750, -0.890797506036281490, 0.454229671084327320, - -0.890884619861979530, - 0.454058837748624540, -0.890971700932396750, 0.453887987718476050, - -0.891058749244331590, - 0.453717121000163930, -0.891145764794583180, 0.453546237599970260, - -0.891232747579952520, - 0.453375337524177750, -0.891319697597241390, 0.453204420779070300, - -0.891406614843252900, - 0.453033487370931580, -0.891493499314791380, 0.452862537306046810, - -0.891580351008662290, - 0.452691570590700860, -0.891667169921672390, 0.452520587231180100, - -0.891753956050629460, - 0.452349587233771000, -0.891840709392342720, 0.452178570604760410, - -0.891927429943622510, - 0.452007537350436530, -0.892014117701280360, 0.451836487477087430, - -0.892100772662129170, - 0.451665420991002540, -0.892187394822982480, 0.451494337898471210, - -0.892273984180655730, - 0.451323238205783520, -0.892360540731965360, 0.451152121919230710, - -0.892447064473728680, - 0.450980989045103810, -0.892533555402764690, 0.450809839589695340, - -0.892620013515893040, - 0.450638673559297760, -0.892706438809935280, 0.450467490960204110, - -0.892792831281713610, - 0.450296291798708730, -0.892879190928051680, 0.450125076081105750, - -0.892965517745774260, - 0.449953843813690580, -0.893051811731707450, 0.449782595002758860, - -0.893138072882678210, - 0.449611329654606600, -0.893224301195515320, 0.449440047775531260, - -0.893310496667048090, - 0.449268749371829920, -0.893396659294107610, 0.449097434449801100, - -0.893482789073525850, - 0.448926103015743260, -0.893568886002136020, 0.448754755075956020, - -0.893654950076772430, - 0.448583390636739300, -0.893740981294271040, 0.448412009704393430, - -0.893826979651468620, - 0.448240612285220000, -0.893912945145203250, 0.448069198385520340, - -0.893998877772314240, - 0.447897768011597310, -0.894084777529641990, 0.447726321169753750, - -0.894170644414028270, - 0.447554857866293010, -0.894256478422316040, 0.447383378107519710, - -0.894342279551349480, - 0.447211881899738260, -0.894428047797973800, 0.447040369249254500, - -0.894513783159035620, - 0.446868840162374330, -0.894599485631382580, 0.446697294645404090, - -0.894685155211863980, - 0.446525732704651400, -0.894770791897329550, 0.446354154346423840, - -0.894856395684630930, - 0.446182559577030120, -0.894941966570620750, 0.446010948402779110, - -0.895027504552152630, - 0.445839320829980350, -0.895113009626081760, 0.445667676864944350, - -0.895198481789264200, - 0.445496016513981740, -0.895283921038557580, 0.445324339783404240, - -0.895369327370820310, - 0.445152646679523590, -0.895454700782912450, 0.444980937208652780, - -0.895540041271694840, - 0.444809211377105000, -0.895625348834030000, 0.444637469191193790, - -0.895710623466781320, - 0.444465710657234110, -0.895795865166813420, 0.444293935781540580, - -0.895881073930992370, - 0.444122144570429260, -0.895966249756185110, 0.443950337030216250, - -0.896051392639260040, - 0.443778513167218220, -0.896136502577086770, 0.443606672987753080, - -0.896221579566535920, - 0.443434816498138430, -0.896306623604479660, 0.443262943704693380, - -0.896391634687790820, - 0.443091054613736990, -0.896476612813344010, 0.442919149231588980, - -0.896561557978014960, - 0.442747227564570130, -0.896646470178680150, 0.442575289619001170, - -0.896731349412217880, - 0.442403335401204130, -0.896816195675507190, 0.442231364917501090, - -0.896901008965428680, - 0.442059378174214760, -0.896985789278863970, 0.441887375177668960, - -0.897070536612695870, - 0.441715355934187310, -0.897155250963808550, 0.441543320450094920, - -0.897239932329087050, - 0.441371268731716620, -0.897324580705418320, 0.441199200785378660, - -0.897409196089689720, - 0.441027116617407340, -0.897493778478790190, 0.440855016234129430, - -0.897578327869610230, - 0.440682899641873020, -0.897662844259040750, 0.440510766846965880, - -0.897747327643974690, - 0.440338617855737300, -0.897831778021305650, 0.440166452674516480, - -0.897916195387928550, - 0.439994271309633260, -0.898000579740739880, 0.439822073767418610, - -0.898084931076636780, - 0.439649860054203420, -0.898169249392518080, 0.439477630176319860, - -0.898253534685283570, - 0.439305384140100060, -0.898337786951834190, 0.439133121951876930, - -0.898422006189072530, - 0.438960843617984430, -0.898506192393901840, 0.438788549144756290, - -0.898590345563227030, - 0.438616238538527710, -0.898674465693953820, 0.438443911805633860, - -0.898758552782989440, - 0.438271568952410480, -0.898842606827242260, 0.438099209985194580, - -0.898926627823621870, - 0.437926834910322860, -0.899010615769039070, 0.437754443734133470, - -0.899094570660405770, - 0.437582036462964340, -0.899178492494635330, 0.437409613103154850, - -0.899262381268642000, - 0.437237173661044200, -0.899346236979341460, 0.437064718142972370, - -0.899430059623650860, - 0.436892246555280470, -0.899513849198487870, 0.436719758904309310, - -0.899597605700772180, - 0.436547255196401250, -0.899681329127423930, 0.436374735437898510, - -0.899765019475365020, - 0.436202199635143950, -0.899848676741518580, 0.436029647794481670, - -0.899932300922808400, - 0.435857079922255470, -0.900015892016160280, 0.435684496024810520, - -0.900099450018500340, - 0.435511896108492170, -0.900182974926756700, 0.435339280179646070, - -0.900266466737858480, - 0.435166648244619370, -0.900349925448735600, 0.434994000309758710, - -0.900433351056319830, - 0.434821336381412350, -0.900516743557543520, 0.434648656465928430, - -0.900600102949340790, - 0.434475960569655710, -0.900683429228646860, 0.434303248698944100, - -0.900766722392397860, - 0.434130520860143310, -0.900849982437531450, 0.433957777059604480, - -0.900933209360986200, - 0.433785017303678520, -0.901016403159702330, 0.433612241598717640, - -0.901099563830620950, - 0.433439449951074200, -0.901182691370684410, 0.433266642367100940, - -0.901265785776836580, - 0.433093818853152010, -0.901348847046022030, 0.432920979415581220, - -0.901431875175186970, - 0.432748124060743760, -0.901514870161278630, 0.432575252794994810, - -0.901597832001245660, - 0.432402365624690140, -0.901680760692037730, 0.432229462556186770, - -0.901763656230605610, - 0.432056543595841450, -0.901846518613901860, 0.431883608750012300, - -0.901929347838879350, - 0.431710658025057370, -0.902012143902493070, 0.431537691427335500, - -0.902094906801698900, - 0.431364708963206440, -0.902177636533453510, 0.431191710639030000, - -0.902260333094715540, - 0.431018696461167080, -0.902342996482444200, 0.430845666435978820, - -0.902425626693600270, - 0.430672620569826860, -0.902508223725145830, 0.430499558869073930, - -0.902590787574043870, - 0.430326481340082610, -0.902673318237258830, 0.430153387989216930, - -0.902755815711756120, - 0.429980278822840570, -0.902838279994502830, 0.429807153847318770, - -0.902920711082466630, - 0.429634013069016500, -0.903003108972617040, 0.429460856494299490, - -0.903085473661924600, - 0.429287684129534720, -0.903167805147360610, 0.429114495981088690, - -0.903250103425898400, - 0.428941292055329550, -0.903332368494511820, 0.428768072358625240, - -0.903414600350176290, - 0.428594836897344400, -0.903496798989868450, 0.428421585677856760, - -0.903578964410565950, - 0.428248318706531910, -0.903661096609247980, 0.428075035989740780, - -0.903743195582894620, - 0.427901737533854240, -0.903825261328487390, 0.427728423345243860, - -0.903907293843009050, - 0.427555093430282200, -0.903989293123443340, 0.427381747795341770, - -0.904071259166775440, - 0.427208386446796370, -0.904153191969991670, 0.427035009391019790, - -0.904235091530079750, - 0.426861616634386490, -0.904316957844028320, 0.426688208183271970, - -0.904398790908827350, - 0.426514784044051520, -0.904480590721468250, 0.426341344223101880, - -0.904562357278943190, - 0.426167888726799620, -0.904644090578246240, 0.425994417561522450, - -0.904725790616371930, - 0.425820930733648300, -0.904807457390316540, 0.425647428249555590, - -0.904889090897077470, - 0.425473910115623910, -0.904970691133653250, 0.425300376338232590, - -0.905052258097043590, - 0.425126826923762410, -0.905133791784249580, 0.424953261878594060, - -0.905215292192273480, - 0.424779681209108810, -0.905296759318118820, 0.424606084921689220, - -0.905378193158789980, - 0.424432473022717420, -0.905459593711293250, 0.424258845518577010, - -0.905540960972635480, - 0.424085202415651670, -0.905622294939825160, 0.423911543720325580, - -0.905703595609872010, - 0.423737869438983950, -0.905784862979786440, 0.423564179578011960, - -0.905866097046580940, - 0.423390474143796100, -0.905947297807268460, 0.423216753142722780, - -0.906028465258863490, - 0.423043016581179100, -0.906109599398381980, 0.422869264465553170, - -0.906190700222840540, - 0.422695496802232950, -0.906271767729257660, 0.422521713597607870, - -0.906352801914652280, - 0.422347914858067000, -0.906433802776045460, 0.422174100590000820, - -0.906514770310458800, - 0.422000270799799790, -0.906595704514915330, 0.421826425493854910, - -0.906676605386439460, - 0.421652564678558380, -0.906757472922056550, 0.421478688360302220, - -0.906838307118793540, - 0.421304796545479700, -0.906919107973678030, 0.421130889240484140, - -0.906999875483739610, - 0.420956966451709440, -0.907080609646008450, 0.420783028185550630, - -0.907161310457516250, - 0.420609074448402510, -0.907241977915295930, 0.420435105246661220, - -0.907322612016381310, - 0.420261120586723050, -0.907403212757808000, 0.420087120474984590, - -0.907483780136612570, - 0.419913104917843730, -0.907564314149832520, 0.419739073921698180, - -0.907644814794507090, - 0.419565027492946940, -0.907725282067676330, 0.419390965637989050, - -0.907805715966381820, - 0.419216888363223960, -0.907886116487666150, 0.419042795675052480, - -0.907966483628573240, - 0.418868687579875110, -0.908046817386148340, 0.418694564084093610, - -0.908127117757437600, - 0.418520425194109700, -0.908207384739488700, 0.418346270916326310, - -0.908287618329350450, - 0.418172101257146430, -0.908367818524072780, 0.417997916222973550, - -0.908447985320707250, - 0.417823715820212380, -0.908528118716306120, 0.417649500055267410, - -0.908608218707923190, - 0.417475268934544340, -0.908688285292613360, 0.417301022464449060, - -0.908768318467432780, - 0.417126760651387870, -0.908848318229439120, 0.416952483501768280, - -0.908928284575690640, - 0.416778191021997590, -0.909008217503247450, 0.416603883218484410, - -0.909088117009170580, - 0.416429560097637320, -0.909167983090522270, 0.416255221665865480, - -0.909247815744366310, - 0.416080867929579320, -0.909327614967767260, 0.415906498895188770, - -0.909407380757791260, - 0.415732114569105420, -0.909487113111505430, 0.415557714957740580, - -0.909566812025978220, - 0.415383300067506290, -0.909646477498279540, 0.415208869904815650, - -0.909726109525480160, - 0.415034424476081630, -0.909805708104652220, 0.414859963787718390, - -0.909885273232869160, - 0.414685487846140010, -0.909964804907205660, 0.414510996657761810, - -0.910044303124737390, - 0.414336490228999210, -0.910123767882541570, 0.414161968566268080, - -0.910203199177696540, - 0.413987431675985510, -0.910282597007281760, 0.413812879564568300, - -0.910361961368377990, - 0.413638312238434560, -0.910441292258067140, 0.413463729704002580, - -0.910520589673432630, - 0.413289131967690960, -0.910599853611558930, 0.413114519035919560, - -0.910679084069531570, - 0.412939890915108020, -0.910758281044437570, 0.412765247611677320, - -0.910837444533365010, - 0.412590589132048380, -0.910916574533403240, 0.412415915482642730, - -0.910995671041643140, - 0.412241226669883000, -0.911074734055176250, 0.412066522700191560, - -0.911153763571095900, - 0.411891803579992220, -0.911232759586496190, 0.411717069315708670, - -0.911311722098472670, - 0.411542319913765280, -0.911390651104122320, 0.411367555380587340, - -0.911469546600543020, - 0.411192775722600160, -0.911548408584833990, 0.411017980946230270, - -0.911627237054095650, - 0.410843171057903910, -0.911706032005429880, 0.410668346064048780, - -0.911784793435939430, - 0.410493505971092520, -0.911863521342728520, 0.410318650785463260, - -0.911942215722902570, - 0.410143780513590350, -0.912020876573568230, 0.409968895161902820, - -0.912099503891833470, - 0.409793994736831200, -0.912178097674807060, 0.409619079244805840, - -0.912256657919599650, - 0.409444148692257590, -0.912335184623322750, 0.409269203085618700, - -0.912413677783089020, - 0.409094242431320920, -0.912492137396012650, 0.408919266735797480, - -0.912570563459208730, - 0.408744276005481520, -0.912648955969793900, 0.408569270246806780, - -0.912727314924885900, - 0.408394249466208110, -0.912805640321603500, 0.408219213670120100, - -0.912883932157067200, - 0.408044162864978740, -0.912962190428398100, 0.407869097057219960, - -0.913040415132719160, - 0.407694016253280170, -0.913118606267154130, 0.407518920459597030, - -0.913196763828828200, - 0.407343809682607970, -0.913274887814867760, 0.407168683928751610, - -0.913352978222400250, - 0.406993543204466460, -0.913431035048554720, 0.406818387516192370, - -0.913509058290461140, - 0.406643216870369140, -0.913587047945250810, 0.406468031273437000, - -0.913665004010056350, - 0.406292830731837470, -0.913742926482011390, 0.406117615252011790, - -0.913820815358251100, - 0.405942384840402570, -0.913898670635911680, 0.405767139503452220, - -0.913976492312130520, - 0.405591879247603870, -0.914054280384046460, 0.405416604079301750, - -0.914132034848799460, - 0.405241314004989860, -0.914209755703530690, 0.405066009031113390, - -0.914287442945382440, - 0.404890689164117750, -0.914365096571498450, 0.404715354410448650, - -0.914442716579023870, - 0.404540004776553110, -0.914520302965104450, 0.404364640268877810, - -0.914597855726887790, - 0.404189260893870750, -0.914675374861522390, 0.404013866657980060, - -0.914752860366158100, - 0.403838457567654130, -0.914830312237946090, 0.403663033629342750, - -0.914907730474038620, - 0.403487594849495310, -0.914985115071589310, 0.403312141234562660, - -0.915062466027752760, - 0.403136672790995240, -0.915139783339685260, 0.402961189525244960, - -0.915217067004543750, - 0.402785691443763640, -0.915294317019487050, 0.402610178553003680, - -0.915371533381674760, - 0.402434650859418540, -0.915448716088267830, 0.402259108369461440, - -0.915525865136428530, - 0.402083551089587040, -0.915602980523320230, 0.401907979026249860, - -0.915680062246107650, - 0.401732392185905010, -0.915757110301956720, 0.401556790575008650, - -0.915834124688034710, - 0.401381174200016790, -0.915911105401509880, 0.401205543067386760, - -0.915988052439551840, - 0.401029897183575790, -0.916064965799331610, 0.400854236555041650, - -0.916141845478021350, - 0.400678561188243350, -0.916218691472794110, 0.400502871089639500, - -0.916295503780824800, - 0.400327166265690150, -0.916372282399289140, 0.400151446722855300, - -0.916449027325364040, - 0.399975712467595390, -0.916525738556228100, 0.399799963506372090, - -0.916602416089060680, - 0.399624199845646790, -0.916679059921042700, 0.399448421491882260, - -0.916755670049355990, - 0.399272628451540930, -0.916832246471183890, 0.399096820731086600, - -0.916908789183710990, - 0.398920998336983020, -0.916985298184122890, 0.398745161275694480, - -0.917061773469606820, - 0.398569309553686360, -0.917138215037350710, 0.398393443177423920, - -0.917214622884544250, - 0.398217562153373620, -0.917290997008377910, 0.398041666488001930, - -0.917367337406043810, - 0.397865756187775750, -0.917443644074735220, 0.397689831259163240, - -0.917519917011646260, - 0.397513891708632330, -0.917596156213972950, 0.397337937542652120, - -0.917672361678911750, - 0.397161968767691720, -0.917748533403661250, 0.396985985390220900, - -0.917824671385420570, - 0.396809987416710420, -0.917900775621390390, 0.396633974853630830, - -0.917976846108772730, - 0.396457947707453960, -0.918052882844770380, 0.396281905984651680, - -0.918128885826587910, - 0.396105849691696320, -0.918204855051430900, 0.395929778835061360, - -0.918280790516506130, - 0.395753693421220080, -0.918356692219021720, 0.395577593456646950, - -0.918432560156186790, - 0.395401478947816300, -0.918508394325212250, 0.395225349901203730, - -0.918584194723309540, - 0.395049206323284880, -0.918659961347691900, 0.394873048220535760, - -0.918735694195573550, - 0.394696875599433670, -0.918811393264169940, 0.394520688466455550, - -0.918887058550697970, - 0.394344486828079650, -0.918962690052375630, 0.394168270690784250, - -0.919038287766421940, - 0.393992040061048100, -0.919113851690057770, 0.393815794945351130, - -0.919189381820504470, - 0.393639535350172880, -0.919264878154985250, 0.393463261281994380, - -0.919340340690724230, - 0.393286972747296570, -0.919415769424946960, 0.393110669752560760, - -0.919491164354880100, - 0.392934352304269600, -0.919566525477751530, 0.392758020408905280, - -0.919641852790790470, - 0.392581674072951530, -0.919717146291227360, 0.392405313302891860, - -0.919792405976293750, - 0.392228938105210370, -0.919867631843222950, 0.392052548486392200, - -0.919942823889248640, - 0.391876144452922350, -0.920017982111606570, 0.391699726011287050, - -0.920093106507533070, - 0.391523293167972350, -0.920168197074266450, 0.391346845929465610, - -0.920243253809045370, - 0.391170384302253980, -0.920318276709110480, 0.390993908292825380, - -0.920393265771703550, - 0.390817417907668610, -0.920468220994067110, 0.390640913153272370, - -0.920543142373445480, - 0.390464394036126650, -0.920618029907083860, 0.390287860562721360, - -0.920692883592229010, - 0.390111312739546910, -0.920767703426128790, 0.389934750573094790, - -0.920842489406032080, - 0.389758174069856410, -0.920917241529189520, 0.389581583236324360, - -0.920991959792852310, - 0.389404978078991100, -0.921066644194273530, 0.389228358604349730, - -0.921141294730707270, - 0.389051724818894500, -0.921215911399408730, 0.388875076729119250, - -0.921290494197634540, - 0.388698414341519250, -0.921365043122642340, 0.388521737662589740, - -0.921439558171691320, - 0.388345046698826300, -0.921514039342041900, 0.388168341456725850, - -0.921588486630955380, - 0.387991621942784910, -0.921662900035694730, 0.387814888163501290, - -0.921737279553523800, - 0.387638140125372680, -0.921811625181708120, 0.387461377834897920, - -0.921885936917513970, - 0.387284601298575890, -0.921960214758209110, 0.387107810522905990, - -0.922034458701062820, - 0.386931005514388690, -0.922108668743345070, 0.386754186279524130, - -0.922182844882327600, - 0.386577352824813980, -0.922256987115283030, 0.386400505156759610, - -0.922331095439485330, - 0.386223643281862980, -0.922405169852209880, 0.386046767206627280, - -0.922479210350733100, - 0.385869876937555310, -0.922553216932332830, 0.385692972481151200, - -0.922627189594287800, - 0.385516053843919020, -0.922701128333878520, 0.385339121032363340, - -0.922775033148386380, - 0.385162174052989970, -0.922848904035094120, 0.384985212912304200, - -0.922922740991285680, - 0.384808237616812930, -0.922996544014246250, 0.384631248173022740, - -0.923070313101262420, - 0.384454244587440870, -0.923144048249621820, 0.384277226866575620, - -0.923217749456613500, - 0.384100195016935040, -0.923291416719527640, 0.383923149045028500, - -0.923365050035655610, - 0.383746088957365010, -0.923438649402290370, 0.383569014760454960, - -0.923512214816725520, - 0.383391926460808770, -0.923585746276256560, 0.383214824064937180, - -0.923659243778179980, - 0.383037707579352130, -0.923732707319793180, 0.382860577010565360, - -0.923806136898395410, - 0.382683432365089840, -0.923879532511286740, 0.382506273649438400, - -0.923952894155768640, - 0.382329100870124510, -0.924026221829143850, 0.382151914033662720, - -0.924099515528716280, - 0.381974713146567220, -0.924172775251791200, 0.381797498215353690, - -0.924246000995674890, - 0.381620269246537520, -0.924319192757675160, 0.381443026246634730, - -0.924392350535101050, - 0.381265769222162490, -0.924465474325262600, 0.381088498179637520, - -0.924538564125471420, - 0.380911213125578130, -0.924611619933039970, 0.380733914066502090, - -0.924684641745282530, - 0.380556601008928570, -0.924757629559513910, 0.380379273959376710, - -0.924830583373050800, - 0.380201932924366050, -0.924903503183210910, 0.380024577910417380, - -0.924976388987313050, - 0.379847208924051110, -0.925049240782677580, 0.379669825971789000, - -0.925122058566625770, - 0.379492429060152740, -0.925194842336480420, 0.379315018195664430, - -0.925267592089565550, - 0.379137593384847430, -0.925340307823206200, 0.378960154634224720, - -0.925412989534729060, - 0.378782701950320600, -0.925485637221461490, 0.378605235339659290, - -0.925558250880732620, - 0.378427754808765620, -0.925630830509872720, 0.378250260364165310, - -0.925703376106213120, - 0.378072752012383990, -0.925775887667086740, 0.377895229759948550, - -0.925848365189827270, - 0.377717693613385810, -0.925920808671769960, 0.377540143579222940, - -0.925993218110251480, - 0.377362579663988450, -0.926065593502609310, 0.377185001874210450, - -0.926137934846182560, - 0.377007410216418310, -0.926210242138311270, 0.376829804697141220, - -0.926282515376337210, - 0.376652185322909620, -0.926354754557602860, 0.376474552100253880, - -0.926426959679452100, - 0.376296905035704790, -0.926499130739230510, 0.376119244135794390, - -0.926571267734284220, - 0.375941569407054420, -0.926643370661961230, 0.375763880856017750, - -0.926715439519610330, - 0.375586178489217330, -0.926787474304581750, 0.375408462313186590, - -0.926859475014227160, - 0.375230732334460030, -0.926931441645899130, 0.375052988559571860, - -0.927003374196951670, - 0.374875230995057600, -0.927075272664740100, 0.374697459647452770, - -0.927147137046620880, - 0.374519674523293210, -0.927218967339951790, 0.374341875629116030, - -0.927290763542091720, - 0.374164062971457990, -0.927362525650401110, 0.373986236556857090, - -0.927434253662241300, - 0.373808396391851370, -0.927505947574975180, 0.373630542482979280, - -0.927577607385966730, - 0.373452674836780410, -0.927649233092581180, 0.373274793459794030, - -0.927720824692185200, - 0.373096898358560690, -0.927792382182146320, 0.372918989539620770, - -0.927863905559833780, - 0.372741067009515810, -0.927935394822617890, 0.372563130774787370, - -0.928006849967869970, - 0.372385180841977360, -0.928078270992963140, 0.372207217217628950, - -0.928149657895271150, - 0.372029239908284960, -0.928221010672169440, 0.371851248920489540, - -0.928292329321034560, - 0.371673244260786630, -0.928363613839244370, 0.371495225935720760, - -0.928434864224177980, - 0.371317193951837600, -0.928506080473215480, 0.371139148315682510, - -0.928577262583738850, - 0.370961089033802040, -0.928648410553130520, 0.370783016112742720, - -0.928719524378774700, - 0.370604929559051670, -0.928790604058057020, 0.370426829379276900, - -0.928861649588363700, - 0.370248715579966360, -0.928932660967082820, 0.370070588167669130, - -0.929003638191603360, - 0.369892447148934270, -0.929074581259315750, 0.369714292530311240, - -0.929145490167611720, - 0.369536124318350760, -0.929216364913883930, 0.369357942519603190, - -0.929287205495526790, - 0.369179747140620070, -0.929358011909935500, 0.369001538187952780, - -0.929428784154506800, - 0.368823315668153960, -0.929499522226638560, 0.368645079587776150, - -0.929570226123729860, - 0.368466829953372320, -0.929640895843181330, 0.368288566771496680, - -0.929711531382394370, - 0.368110290048703050, -0.929782132738772190, 0.367931999791546500, - -0.929852699909718750, - 0.367753696006582090, -0.929923232892639560, 0.367575378700365330, - -0.929993731684941480, - 0.367397047879452820, -0.930064196284032360, 0.367218703550400930, - -0.930134626687321390, - 0.367040345719767240, -0.930205022892219070, 0.366861974394109220, - -0.930275384896137040, - 0.366683589579984930, -0.930345712696488470, 0.366505191283953480, - -0.930416006290687550, - 0.366326779512573590, -0.930486265676149780, 0.366148354272405390, - -0.930556490850291800, - 0.365969915570008910, -0.930626681810531650, 0.365791463411944570, - -0.930696838554288860, - 0.365612997804773960, -0.930766961078983710, 0.365434518755058390, - -0.930837049382038150, - 0.365256026269360380, -0.930907103460875020, 0.365077520354242180, - -0.930977123312918930, - 0.364899001016267380, -0.931047108935595170, 0.364720468261999390, - -0.931117060326330790, - 0.364541922098002180, -0.931186977482553750, 0.364363362530840730, - -0.931256860401693420, - 0.364184789567079840, -0.931326709081180430, 0.364006203213285530, - -0.931396523518446600, - 0.363827603476023610, -0.931466303710925090, 0.363648990361860550, - -0.931536049656050300, - 0.363470363877363870, -0.931605761351257830, 0.363291724029100700, - -0.931675438793984620, - 0.363113070823639530, -0.931745081981668720, 0.362934404267548750, - -0.931814690911749620, - 0.362755724367397230, -0.931884265581668150, 0.362577031129754870, - -0.931953805988865900, - 0.362398324561191310, -0.932023312130786490, 0.362219604668277570, - -0.932092784004874050, - 0.362040871457584350, -0.932162221608574320, 0.361862124935682980, - -0.932231624939334540, - 0.361683365109145950, -0.932300993994602640, 0.361504591984545260, - -0.932370328771828460, - 0.361325805568454340, -0.932439629268462360, 0.361147005867446190, - -0.932508895481956700, - 0.360968192888095290, -0.932578127409764420, 0.360789366636975690, - -0.932647325049340340, - 0.360610527120662270, -0.932716488398140250, 0.360431674345730810, - -0.932785617453620990, - 0.360252808318756830, -0.932854712213241230, 0.360073929046317080, - -0.932923772674460140, - 0.359895036534988280, -0.932992798834738850, 0.359716130791347570, - -0.933061790691539380, - 0.359537211821973180, -0.933130748242325110, 0.359358279633443080, - -0.933199671484560730, - 0.359179334232336560, -0.933268560415712050, 0.359000375625232630, - -0.933337415033246080, - 0.358821403818710920, -0.933406235334631520, 0.358642418819352100, - -0.933475021317337950, - 0.358463420633736540, -0.933543772978836170, 0.358284409268445900, - -0.933612490316598540, - 0.358105384730061760, -0.933681173328098300, 0.357926347025166070, - -0.933749822010810580, - 0.357747296160342010, -0.933818436362210960, 0.357568232142172260, - -0.933887016379776890, - 0.357389154977241000, -0.933955562060986730, 0.357210064672131900, - -0.934024073403320500, - 0.357030961233430030, -0.934092550404258870, 0.356851844667720410, - -0.934160993061284420, - 0.356672714981588260, -0.934229401371880820, 0.356493572181620200, - -0.934297775333532530, - 0.356314416274402360, -0.934366114943725900, 0.356135247266522180, - -0.934434420199948050, - 0.355956065164567010, -0.934502691099687870, 0.355776869975124640, - -0.934570927640435030, - 0.355597661704783960, -0.934639129819680780, 0.355418440360133590, - -0.934707297634917440, - 0.355239205947763370, -0.934775431083638700, 0.355059958474263030, - -0.934843530163339430, - 0.354880697946222790, -0.934911594871516090, 0.354701424370233940, - -0.934979625205665800, - 0.354522137752887430, -0.935047621163287430, 0.354342838100775600, - -0.935115582741880890, - 0.354163525420490510, -0.935183509938947500, 0.353984199718624830, - -0.935251402751989810, - 0.353804861001772160, -0.935319261178511500, 0.353625509276525970, - -0.935387085216017770, - 0.353446144549480870, -0.935454874862014620, 0.353266766827231180, - -0.935522630114009930, - 0.353087376116372530, -0.935590350969512370, 0.352907972423500360, - -0.935658037426032040, - 0.352728555755210730, -0.935725689481080370, 0.352549126118100580, - -0.935793307132169900, - 0.352369683518766630, -0.935860890376814640, 0.352190227963806890, - -0.935928439212529660, - 0.352010759459819240, -0.935995953636831300, 0.351831278013402030, - -0.936063433647237540, - 0.351651783631154680, -0.936130879241266920, 0.351472276319676260, - -0.936198290416440090, - 0.351292756085567150, -0.936265667170278260, 0.351113222935427630, - -0.936333009500304180, - 0.350933676875858360, -0.936400317404042060, 0.350754117913461170, - -0.936467590879016880, - 0.350574546054837570, -0.936534829922755500, 0.350394961306590200, - -0.936602034532785570, - 0.350215363675321740, -0.936669204706636060, 0.350035753167635300, - -0.936736340441837620, - 0.349856129790135030, -0.936803441735921560, 0.349676493549424760, - -0.936870508586420960, - 0.349496844452109600, -0.936937540990869900, 0.349317182504794320, - -0.937004538946803690, - 0.349137507714085030, -0.937071502451759190, 0.348957820086587600, - -0.937138431503274140, - 0.348778119628908420, -0.937205326098887960, 0.348598406347655040, - -0.937272186236140950, - 0.348418680249434510, -0.937339011912574960, 0.348238941340855310, - -0.937405803125732850, - 0.348059189628525780, -0.937472559873159140, 0.347879425119054510, - -0.937539282152399230, - 0.347699647819051490, -0.937605969960999990, 0.347519857735126110, - -0.937672623296509470, - 0.347340054873889190, -0.937739242156476970, 0.347160239241951330, - -0.937805826538453010, - 0.346980410845923680, -0.937872376439989890, 0.346800569692418400, - -0.937938891858640210, - 0.346620715788047320, -0.938005372791958840, 0.346440849139423580, - -0.938071819237501160, - 0.346260969753160170, -0.938138231192824360, 0.346081077635870480, - -0.938204608655486490, - 0.345901172794169100, -0.938270951623047080, 0.345721255234670120, - -0.938337260093066950, - 0.345541324963989150, -0.938403534063108060, 0.345361381988741170, - -0.938469773530733800, - 0.345181426315542610, -0.938535978493508560, 0.345001457951009780, - -0.938602148948998290, - 0.344821476901759290, -0.938668284894770170, 0.344641483174409070, - -0.938734386328392460, - 0.344461476775576480, -0.938800453247434770, 0.344281457711880230, - -0.938866485649468060, - 0.344101425989938980, -0.938932483532064490, 0.343921381616371700, - -0.938998446892797540, - 0.343741324597798600, -0.939064375729241950, 0.343561254940839330, - -0.939130270038973650, - 0.343381172652115100, -0.939196129819569900, 0.343201077738246710, - -0.939261955068609100, - 0.343020970205855540, -0.939327745783671400, 0.342840850061564060, - -0.939393501962337510, - 0.342660717311994380, -0.939459223602189920, 0.342480571963769850, - -0.939524910700812120, - 0.342300414023513690, -0.939590563255789160, 0.342120243497849590, - -0.939656181264707070, - 0.341940060393402300, -0.939721764725153340, 0.341759864716796310, - -0.939787313634716570, - 0.341579656474657210, -0.939852827990986680, 0.341399435673610360, - -0.939918307791555050, - 0.341219202320282410, -0.939983753034013940, 0.341038956421299830, - -0.940049163715957370, - 0.340858697983289440, -0.940114539834980280, 0.340678427012879310, - -0.940179881388678810, - 0.340498143516697100, -0.940245188374650880, 0.340317847501371730, - -0.940310460790495070, - 0.340137538973531880, -0.940375698633811540, 0.339957217939806880, - -0.940440901902201750, - 0.339776884406826960, -0.940506070593268300, 0.339596538381222060, - -0.940571204704615190, - 0.339416179869623410, -0.940636304233847590, 0.339235808878662120, - -0.940701369178571940, - 0.339055425414969640, -0.940766399536396070, 0.338875029485178560, - -0.940831395304928870, - 0.338694621095921190, -0.940896356481780830, 0.338514200253831000, - -0.940961283064563280, - 0.338333766965541290, -0.941026175050889260, 0.338153321237685990, - -0.941091032438372780, - 0.337972863076899830, -0.941155855224629190, 0.337792392489817460, - -0.941220643407275180, - 0.337611909483074680, -0.941285396983928660, 0.337431414063306790, - -0.941350115952208970, - 0.337250906237150650, -0.941414800309736230, 0.337070386011242730, - -0.941479450054132580, - 0.336889853392220050, -0.941544065183020810, 0.336709308386720700, - -0.941608645694025140, - 0.336528751001382350, -0.941673191584771360, 0.336348181242844100, - -0.941737702852886160, - 0.336167599117744690, -0.941802179495997650, 0.335987004632723350, - -0.941866621511735280, - 0.335806397794420560, -0.941931028897729510, 0.335625778609476230, - -0.941995401651612550, - 0.335445147084531660, -0.942059739771017310, 0.335264503226227970, - -0.942124043253578460, - 0.335083847041206580, -0.942188312096931770, 0.334903178536110290, - -0.942252546298714020, - 0.334722497717581220, -0.942316745856563780, 0.334541804592262960, - -0.942380910768120470, - 0.334361099166798900, -0.942445041031024890, 0.334180381447832740, - -0.942509136642919240, - 0.333999651442009490, -0.942573197601446870, 0.333818909155973620, - -0.942637223904252530, - 0.333638154596370920, -0.942701215548981900, 0.333457387769846790, - -0.942765172533282510, - 0.333276608683047980, -0.942829094854802710, 0.333095817342620890, - -0.942892982511192130, - 0.332915013755212650, -0.942956835500102120, 0.332734197927471160, - -0.943020653819184650, - 0.332553369866044220, -0.943084437466093490, 0.332372529577580680, - -0.943148186438483420, - 0.332191677068729320, -0.943211900734010620, 0.332010812346139380, - -0.943275580350332540, - 0.331829935416461220, -0.943339225285107720, 0.331649046286344620, - -0.943402835535996240, - 0.331468144962440920, -0.943466411100659320, 0.331287231451400990, - -0.943529951976759370, - 0.331106305759876430, -0.943593458161960390, 0.330925367894519650, - -0.943656929653927110, - 0.330744417861982890, -0.943720366450326200, 0.330563455668919590, - -0.943783768548825060, - 0.330382481321982950, -0.943847135947092690, 0.330201494827826620, - -0.943910468642799150, - 0.330020496193105530, -0.943973766633615980, 0.329839485424473940, - -0.944037029917215830, - 0.329658462528587550, -0.944100258491272660, 0.329477427512101680, - -0.944163452353461770, - 0.329296380381672800, -0.944226611501459810, 0.329115321143957360, - -0.944289735932944410, - 0.328934249805612200, -0.944352825645594750, 0.328753166373295100, - -0.944415880637091250, - 0.328572070853663690, -0.944478900905115550, 0.328390963253376630, - -0.944541886447350380, - 0.328209843579092660, -0.944604837261480260, 0.328028711837470730, - -0.944667753345190490, - 0.327847568035170960, -0.944730634696167800, 0.327666412178853060, - -0.944793481312100280, - 0.327485244275178060, -0.944856293190677210, 0.327304064330806830, - -0.944919070329589220, - 0.327122872352400510, -0.944981812726528150, 0.326941668346621530, - -0.945044520379187070, - 0.326760452320131790, -0.945107193285260610, 0.326579224279594460, - -0.945169831442444150, - 0.326397984231672660, -0.945232434848434890, 0.326216732183029770, - -0.945295003500931100, - 0.326035468140330350, -0.945357537397632290, 0.325854192110238580, - -0.945420036536239070, - 0.325672904099419900, -0.945482500914453740, 0.325491604114539260, - -0.945544930529979680, - 0.325310292162262980, -0.945607325380521280, 0.325128968249257190, - -0.945669685463784710, - 0.324947632382188430, -0.945732010777477150, 0.324766284567724330, - -0.945794301319306860, - 0.324584924812532150, -0.945856557086983910, 0.324403553123280290, - -0.945918778078219110, - 0.324222169506637130, -0.945980964290724760, 0.324040773969271450, - -0.946043115722214560, - 0.323859366517852960, -0.946105232370403340, 0.323677947159051180, - -0.946167314233007370, - 0.323496515899536760, -0.946229361307743820, 0.323315072745980150, - -0.946291373592331510, - 0.323133617705052330, -0.946353351084490590, 0.322952150783425370, - -0.946415293781942110, - 0.322770671987770710, -0.946477201682408680, 0.322589181324761390, - -0.946539074783614100, - 0.322407678801070020, -0.946600913083283530, 0.322226164423369650, - -0.946662716579143360, - 0.322044638198334620, -0.946724485268921170, 0.321863100132638580, - -0.946786219150346000, - 0.321681550232956640, -0.946847918221148000, 0.321499988505963450, - -0.946909582479058760, - 0.321318414958334910, -0.946971211921810880, 0.321136829596746780, - -0.947032806547138620, - 0.320955232427875210, -0.947094366352777220, 0.320773623458397440, - -0.947155891336463270, - 0.320592002694990330, -0.947217381495934820, 0.320410370144331880, - -0.947278836828930880, - 0.320228725813100020, -0.947340257333191940, 0.320047069707973140, - -0.947401643006459900, - 0.319865401835630610, -0.947462993846477700, 0.319683722202751370, - -0.947524309850989570, - 0.319502030816015750, -0.947585591017741090, 0.319320327682103720, - -0.947646837344479190, - 0.319138612807695900, -0.947708048828952100, 0.318956886199473770, - -0.947769225468909180, - 0.318775147864118480, -0.947830367262101010, 0.318593397808312470, - -0.947891474206279730, - 0.318411636038737960, -0.947952546299198560, 0.318229862562077580, - -0.948013583538612200, - 0.318048077385015060, -0.948074585922276230, 0.317866280514233660, - -0.948135553447947980, - 0.317684471956418020, -0.948196486113385580, 0.317502651718252260, - -0.948257383916349060, - 0.317320819806421790, -0.948318246854599090, 0.317138976227611890, - -0.948379074925898120, - 0.316957120988508150, -0.948439868128009620, 0.316775254095797380, - -0.948500626458698260, - 0.316593375556165850, -0.948561349915730270, 0.316411485376301090, - -0.948622038496872990, - 0.316229583562890490, -0.948682692199895090, 0.316047670122621860, - -0.948743311022566480, - 0.315865745062184070, -0.948803894962658380, 0.315683808388265600, - -0.948864444017943340, - 0.315501860107556040, -0.948924958186195160, 0.315319900226745050, - -0.948985437465188710, - 0.315137928752522440, -0.949045881852700560, 0.314955945691579250, - -0.949106291346508260, - 0.314773951050606070, -0.949166665944390700, 0.314591944836294710, - -0.949227005644128210, - 0.314409927055336820, -0.949287310443502010, 0.314227897714424500, - -0.949347580340295210, - 0.314045856820250820, -0.949407815332291460, 0.313863804379508500, - -0.949468015417276550, - 0.313681740398891570, -0.949528180593036670, 0.313499664885093450, - -0.949588310857359950, - 0.313317577844809070, -0.949648406208035480, 0.313135479284732950, - -0.949708466642853800, - 0.312953369211560200, -0.949768492159606680, 0.312771247631986880, - -0.949828482756087000, - 0.312589114552708660, -0.949888438430089300, 0.312406969980422500, - -0.949948359179409010, - 0.312224813921825050, -0.950008245001843000, 0.312042646383613510, - -0.950068095895189590, - 0.311860467372486130, -0.950127911857248100, 0.311678276895140550, - -0.950187692885819280, - 0.311496074958275970, -0.950247438978705230, 0.311313861568591090, - -0.950307150133709140, - 0.311131636732785270, -0.950366826348635780, 0.310949400457558760, - -0.950426467621290900, - 0.310767152749611470, -0.950486073949481700, 0.310584893615644560, - -0.950545645331016600, - 0.310402623062358880, -0.950605181763705230, 0.310220341096455910, - -0.950664683245358910, - 0.310038047724638000, -0.950724149773789610, 0.309855742953607130, - -0.950783581346811070, - 0.309673426790066490, -0.950842977962238160, 0.309491099240719050, - -0.950902339617887060, - 0.309308760312268780, -0.950961666311575080, 0.309126410011419550, - -0.951020958041121080, - 0.308944048344875710, -0.951080214804345010, 0.308761675319342570, - -0.951139436599068190, - 0.308579290941525030, -0.951198623423113230, 0.308396895218129240, - -0.951257775274304000, - 0.308214488155861220, -0.951316892150465550, 0.308032069761427330, - -0.951375974049424420, - 0.307849640041534980, -0.951435020969008340, 0.307667199002891190, - -0.951494032907046370, - 0.307484746652204160, -0.951553009861368590, 0.307302282996181950, - -0.951611951829806730, - 0.307119808041533100, -0.951670858810193860, 0.306937321794967020, - -0.951729730800363720, - 0.306754824263192780, -0.951788567798152130, 0.306572315452920800, - -0.951847369801395620, - 0.306389795370861080, -0.951906136807932230, 0.306207264023724280, - -0.951964868815601380, - 0.306024721418221900, -0.952023565822243570, 0.305842167561065080, - -0.952082227825700620, - 0.305659602458966230, -0.952140854823815830, 0.305477026118637360, - -0.952199446814433580, - 0.305294438546791720, -0.952258003795399600, 0.305111839750142220, - -0.952316525764560830, - 0.304929229735402430, -0.952375012719765880, 0.304746608509286640, - -0.952433464658864030, - 0.304563976078509050, -0.952491881579706320, 0.304381332449784940, - -0.952550263480144930, - 0.304198677629829270, -0.952608610358033240, 0.304016011625357570, - -0.952666922211226170, - 0.303833334443086470, -0.952725199037579570, 0.303650646089731910, - -0.952783440834950920, - 0.303467946572011370, -0.952841647601198720, 0.303285235896641910, - -0.952899819334182880, - 0.303102514070341060, -0.952957956031764700, 0.302919781099827420, - -0.953016057691806530, - 0.302737036991819140, -0.953074124312172200, 0.302554281753035670, - -0.953132155890726750, - 0.302371515390196130, -0.953190152425336560, 0.302188737910020040, - -0.953248113913869320, - 0.302005949319228200, -0.953306040354193750, 0.301823149624540650, - -0.953363931744180330, - 0.301640338832678880, -0.953421788081700310, 0.301457516950363940, - -0.953479609364626610, - 0.301274683984318000, -0.953537395590833280, 0.301091839941263210, - -0.953595146758195680, - 0.300908984827921890, -0.953652862864590500, 0.300726118651017620, - -0.953710543907895560, - 0.300543241417273400, -0.953768189885990330, 0.300360353133413580, - -0.953825800796755050, - 0.300177453806162120, -0.953883376638071770, 0.299994543442243580, - -0.953940917407823500, - 0.299811622048383460, -0.953998423103894490, 0.299628689631306790, - -0.954055893724170660, - 0.299445746197739950, -0.954113329266538800, 0.299262791754409010, - -0.954170729728887280, - 0.299079826308040480, -0.954228095109105670, 0.298896849865361910, - -0.954285425405084650, - 0.298713862433100390, -0.954342720614716480, 0.298530864017984230, - -0.954399980735894490, - 0.298347854626741570, -0.954457205766513490, 0.298164834266100910, - -0.954514395704469500, - 0.297981802942791920, -0.954571550547659630, 0.297798760663543550, - -0.954628670293982680, - 0.297615707435086310, -0.954685754941338340, 0.297432643264150030, - -0.954742804487627940, - 0.297249568157465890, -0.954799818930753720, 0.297066482121764840, - -0.954856798268619580, - 0.296883385163778270, -0.954913742499130520, 0.296700277290238460, - -0.954970651620192790, - 0.296517158507877410, -0.955027525629714160, 0.296334028823428240, - -0.955084364525603410, - 0.296150888243623960, -0.955141168305770670, 0.295967736775197890, - -0.955197936968127710, - 0.295784574424884370, -0.955254670510586990, 0.295601401199417360, - -0.955311368931062720, - 0.295418217105532070, -0.955368032227470240, 0.295235022149963390, - -0.955424660397726330, - 0.295051816339446720, -0.955481253439748770, 0.294868599680718380, - -0.955537811351456770, - 0.294685372180514330, -0.955594334130771110, 0.294502133845571720, - -0.955650821775613220, - 0.294318884682627570, -0.955707274283906560, 0.294135624698419080, - -0.955763691653575440, - 0.293952353899684770, -0.955820073882545420, 0.293769072293162400, - -0.955876420968743590, - 0.293585779885591310, -0.955932732910098170, 0.293402476683710060, - -0.955989009704538930, - 0.293219162694258680, -0.956045251349996410, 0.293035837923976920, - -0.956101457844403040, - 0.292852502379604810, -0.956157629185692140, 0.292669156067883570, - -0.956213765371798470, - 0.292485798995553830, -0.956269866400658140, 0.292302431169357610, - -0.956325932270208230, - 0.292119052596036540, -0.956381962978387620, 0.291935663282332780, - -0.956437958523136180, - 0.291752263234989370, -0.956493918902394990, 0.291568852460749040, - -0.956549844114106820, - 0.291385430966355720, -0.956605734156215080, 0.291201998758553020, - -0.956661589026664980, - 0.291018555844085090, -0.956717408723403050, 0.290835102229696940, - -0.956773193244376930, - 0.290651637922133220, -0.956828942587535370, 0.290468162928139870, - -0.956884656750828900, - 0.290284677254462330, -0.956940335732208940, 0.290101180907847140, - -0.956995979529628230, - 0.289917673895040860, -0.957051588141040970, 0.289734156222790250, - -0.957107161564402790, - 0.289550627897843140, -0.957162699797670100, 0.289367088926946960, - -0.957218202838801210, - 0.289183539316850310, -0.957273670685755200, 0.288999979074301530, - -0.957329103336492790, - 0.288816408206049480, -0.957384500788975860, 0.288632826718843940, - -0.957439863041167570, - 0.288449234619434170, -0.957495190091032570, 0.288265631914570830, - -0.957550481936536470, - 0.288082018611004300, -0.957605738575646240, 0.287898394715485170, - -0.957660960006330610, - 0.287714760234765280, -0.957716146226558870, 0.287531115175595930, - -0.957771297234302320, - 0.287347459544729570, -0.957826413027532910, 0.287163793348918560, - -0.957881493604224250, - 0.286980116594915570, -0.957936538962351420, 0.286796429289474190, - -0.957991549099890370, - 0.286612731439347790, -0.958046524014818600, 0.286429023051290750, - -0.958101463705114620, - 0.286245304132057120, -0.958156368168758820, 0.286061574688402100, - -0.958211237403732260, - 0.285877834727080730, -0.958266071408017670, 0.285694084254848320, - -0.958320870179598880, - 0.285510323278461380, -0.958375633716461170, 0.285326551804675810, - -0.958430362016591040, - 0.285142769840248720, -0.958485055077976100, 0.284958977391937150, - -0.958539712898605730, - 0.284775174466498300, -0.958594335476470220, 0.284591361070690550, - -0.958648922809561040, - 0.284407537211271820, -0.958703474895871600, 0.284223702895001100, - -0.958757991733395710, - 0.284039858128637360, -0.958812473320129200, 0.283856002918939750, - -0.958866919654069010, - 0.283672137272668550, -0.958921330733213060, 0.283488261196583550, - -0.958975706555561080, - 0.283304374697445790, -0.959030047119113550, 0.283120477782015990, - -0.959084352421872730, - 0.282936570457055390, -0.959138622461841890, 0.282752652729326040, - -0.959192857237025740, - 0.282568724605589740, -0.959247056745430090, 0.282384786092609420, - -0.959301220985062210, - 0.282200837197147500, -0.959355349953930790, 0.282016877925967690, - -0.959409443650045550, - 0.281832908285833460, -0.959463502071417510, 0.281648928283508680, - -0.959517525216059260, - 0.281464937925758050, -0.959571513081984520, 0.281280937219346110, - -0.959625465667208300, - 0.281096926171038320, -0.959679382969746750, 0.280912904787600120, - -0.959733264987617680, - 0.280728873075797190, -0.959787111718839900, 0.280544831042396360, - -0.959840923161433660, - 0.280360778694163810, -0.959894699313420530, 0.280176716037867040, - -0.959948440172823210, - 0.279992643080273380, -0.960002145737665850, 0.279808559828150390, - -0.960055816005973890, - 0.279624466288266700, -0.960109450975773940, 0.279440362467390510, - -0.960163050645094000, - 0.279256248372291240, -0.960216615011963430, 0.279072124009737970, - -0.960270144074412800, - 0.278887989386500280, -0.960323637830473920, 0.278703844509348600, - -0.960377096278180130, - 0.278519689385053060, -0.960430519415565790, 0.278335524020384970, - -0.960483907240666790, - 0.278151348422115090, -0.960537259751520050, 0.277967162597015430, - -0.960590576946164120, - 0.277782966551857800, -0.960643858822638470, 0.277598760293414290, - -0.960697105378984450, - 0.277414543828458200, -0.960750316613243950, 0.277230317163762120, - -0.960803492523460760, - 0.277046080306099950, -0.960856633107679660, 0.276861833262245390, - -0.960909738363946770, - 0.276677576038972420, -0.960962808290309780, 0.276493308643056100, - -0.961015842884817230, - 0.276309031081271030, -0.961068842145519350, 0.276124743360392890, - -0.961121806070467380, - 0.275940445487197320, -0.961174734657714080, 0.275756137468460120, - -0.961227627905313460, - 0.275571819310958250, -0.961280485811320640, 0.275387491021468140, - -0.961333308373792270, - 0.275203152606767370, -0.961386095590786250, 0.275018804073633380, - -0.961438847460361570, - 0.274834445428843940, -0.961491563980579000, 0.274650076679177790, - -0.961544245149499990, - 0.274465697831413220, -0.961596890965187860, 0.274281308892329710, - -0.961649501425706820, - 0.274096909868706330, -0.961702076529122540, 0.273912500767323320, - -0.961754616273502010, - 0.273728081594960650, -0.961807120656913540, 0.273543652358398730, - -0.961859589677426570, - 0.273359213064418790, -0.961912023333112100, 0.273174763719801870, - -0.961964421622042320, - 0.272990304331329980, -0.962016784542290560, 0.272805834905784920, - -0.962069112091931580, - 0.272621355449948980, -0.962121404269041580, 0.272436865970605350, - -0.962173661071697770, - 0.272252366474536660, -0.962225882497979020, 0.272067856968526980, - -0.962278068545965090, - 0.271883337459359890, -0.962330219213737400, 0.271698807953819510, - -0.962382334499378380, - 0.271514268458690810, -0.962434414400971990, 0.271329718980758420, - -0.962486458916603450, - 0.271145159526808070, -0.962538468044359160, 0.270960590103625330, - -0.962590441782326780, - 0.270776010717996010, -0.962642380128595710, 0.270591421376707050, - -0.962694283081255930, - 0.270406822086544820, -0.962746150638399410, 0.270222212854296930, - -0.962797982798119010, - 0.270037593686750510, -0.962849779558509030, 0.269852964590693910, - -0.962901540917665000, - 0.269668325572915200, -0.962953266873683880, 0.269483676640202840, - -0.963004957424663850, - 0.269299017799346230, -0.963056612568704340, 0.269114349057134330, - -0.963108232303906190, - 0.268929670420357310, -0.963159816628371360, 0.268744981895805090, - -0.963211365540203480, - 0.268560283490267890, -0.963262879037507070, 0.268375575210537010, - -0.963314357118388090, - 0.268190857063403180, -0.963365799780954050, 0.268006129055658350, - -0.963417207023313350, - 0.267821391194094320, -0.963468578843575950, 0.267636643485503090, - -0.963519915239853140, - 0.267451885936677740, -0.963571216210257210, 0.267267118554410930, - -0.963622481752902220, - 0.267082341345496350, -0.963673711865903230, 0.266897554316727510, - -0.963724906547376410, - 0.266712757474898420, -0.963776065795439840, 0.266527950826803810, - -0.963827189608212340, - 0.266343134379238180, -0.963878277983814200, 0.266158308138997050, - -0.963929330920367140, - 0.265973472112875530, -0.963980348415994110, 0.265788626307669970, - -0.964031330468819280, - 0.265603770730176440, -0.964082277076968140, 0.265418905387191260, - -0.964133188238567640, - 0.265234030285511900, -0.964184063951745720, 0.265049145431935200, - -0.964234904214632200, - 0.264864250833259320, -0.964285709025357370, 0.264679346496282050, - -0.964336478382053720, - 0.264494432427801630, -0.964387212282854290, 0.264309508634617220, - -0.964437910725893910, - 0.264124575123527490, -0.964488573709308410, 0.263939631901332410, - -0.964539201231235150, - 0.263754678974831510, -0.964589793289812650, 0.263569716350824880, - -0.964640349883180930, - 0.263384744036113390, -0.964690871009480920, 0.263199762037497560, - -0.964741356666855340, - 0.263014770361779060, -0.964791806853447900, 0.262829769015759330, - -0.964842221567403510, - 0.262644758006240100, -0.964892600806868890, 0.262459737340024090, - -0.964942944569991410, - 0.262274707023913590, -0.964993252854920320, 0.262089667064712100, - -0.965043525659805890, - 0.261904617469222560, -0.965093762982799590, 0.261719558244249080, - -0.965143964822054450, - 0.261534489396595630, -0.965194131175724720, 0.261349410933066350, - -0.965244262041965780, - 0.261164322860466590, -0.965294357418934660, 0.260979225185601020, - -0.965344417304789370, - 0.260794117915275570, -0.965394441697689400, 0.260609001056295920, - -0.965444430595795430, - 0.260423874615468010, -0.965494383997269500, 0.260238738599598950, - -0.965544301900275070, - 0.260053593015495130, -0.965594184302976830, 0.259868437869964330, - -0.965644031203540590, - 0.259683273169813930, -0.965693842600133690, 0.259498098921851660, - -0.965743618490924830, - 0.259312915132886350, -0.965793358874083570, 0.259127721809726150, - -0.965843063747781510, - 0.258942518959180580, -0.965892733110190860, 0.258757306588058840, - -0.965942366959485540, - 0.258572084703170390, -0.965991965293840570, 0.258386853311325710, - -0.966041528111432400, - 0.258201612419334870, -0.966091055410438830, 0.258016362034009070, - -0.966140547189038750, - 0.257831102162158930, -0.966190003445412620, 0.257645832810596440, - -0.966239424177741890, - 0.257460553986133210, -0.966288809384209580, 0.257275265695581120, - -0.966338159063000130, - 0.257089967945753230, -0.966387473212298790, 0.256904660743461850, - -0.966436751830292650, - 0.256719344095520720, -0.966485994915169840, 0.256534018008743200, - -0.966535202465119700, - 0.256348682489942910, -0.966584374478333120, 0.256163337545934570, - -0.966633510953002100, - 0.255977983183532380, -0.966682611887320190, 0.255792619409551670, - -0.966731677279481840, - 0.255607246230807550, -0.966780707127683270, 0.255421863654115460, - -0.966829701430121810, - 0.255236471686291820, -0.966878660184995910, 0.255051070334152530, - -0.966927583390505660, - 0.254865659604514630, -0.966976471044852070, 0.254680239504194990, - -0.967025323146237900, - 0.254494810040010790, -0.967074139692867040, 0.254309371218780110, - -0.967122920682944360, - 0.254123923047320620, -0.967171666114676640, 0.253938465532451140, - -0.967220375986271310, - 0.253752998680989940, -0.967269050295937790, 0.253567522499756610, - -0.967317689041886310, - 0.253382036995570270, -0.967366292222328510, 0.253196542175250560, - -0.967414859835477480, - 0.253011038045617980, -0.967463391879547440, 0.252825524613492610, - -0.967511888352754150, - 0.252640001885695580, -0.967560349253314360, 0.252454469869047900, - -0.967608774579446380, - 0.252268928570370810, -0.967657164329369880, 0.252083377996486560, - -0.967705518501305480, - 0.251897818154216910, -0.967753837093475510, 0.251712249050384750, - -0.967802120104103270, - 0.251526670691812780, -0.967850367531413620, 0.251341083085323880, - -0.967898579373632660, - 0.251155486237742030, -0.967946755628987800, 0.250969880155890720, - -0.967994896295707670, - 0.250784264846594550, -0.968043001372022260, 0.250598640316677830, - -0.968091070856162970, - 0.250413006572965280, -0.968139104746362330, 0.250227363622282540, - -0.968187103040854420, - 0.250041711471454650, -0.968235065737874320, 0.249856050127308050, - -0.968282992835658660, - 0.249670379596668520, -0.968330884332445300, 0.249484699886363010, - -0.968378740226473300, - 0.249299011003218300, -0.968426560515983190, 0.249113312954061360, - -0.968474345199216820, - 0.248927605745720260, -0.968522094274417270, 0.248741889385022420, - -0.968569807739828930, - 0.248556163878796620, -0.968617485593697540, 0.248370429233871150, - -0.968665127834269950, - 0.248184685457074780, -0.968712734459794780, 0.247998932555237220, - -0.968760305468521430, - 0.247813170535187620, -0.968807840858700970, 0.247627399403756330, - -0.968855340628585580, - 0.247441619167773440, -0.968902804776428870, 0.247255829834069320, - -0.968950233300485800, - 0.247070031409475370, -0.968997626199012310, 0.246884223900822430, - -0.969044983470266240, - 0.246698407314942500, -0.969092305112506100, 0.246512581658667380, - -0.969139591123992280, - 0.246326746938829060, -0.969186841502985950, 0.246140903162260640, - -0.969234056247750050, - 0.245955050335794590, -0.969281235356548530, 0.245769188466264670, - -0.969328378827646660, - 0.245583317560504000, -0.969375486659311280, 0.245397437625346990, - -0.969422558849810320, - 0.245211548667627680, -0.969469595397412950, 0.245025650694180470, - -0.969516596300390000, - 0.244839743711840750, -0.969563561557013180, 0.244653827727443320, - -0.969610491165555870, - 0.244467902747824210, -0.969657385124292450, 0.244281968779819170, - -0.969704243431498750, - 0.244096025830264210, -0.969751066085452140, 0.243910073905996370, - -0.969797853084430890, - 0.243724113013852130, -0.969844604426714830, 0.243538143160669180, - -0.969891320110585100, - 0.243352164353284880, -0.969938000134323960, 0.243166176598536930, - -0.969984644496215240, - 0.242980179903263980, -0.970031253194543970, 0.242794174274304190, - -0.970077826227596420, - 0.242608159718496890, -0.970124363593660280, 0.242422136242681050, - -0.970170865291024360, - 0.242236103853696040, -0.970217331317979160, 0.242050062558382180, - -0.970263761672816140, - 0.241864012363579210, -0.970310156353828110, 0.241677953276128090, - -0.970356515359309450, - 0.241491885302869300, -0.970402838687555500, 0.241305808450644390, - -0.970449126336863090, - 0.241119722726294730, -0.970495378305530450, 0.240933628136661910, - -0.970541594591857070, - 0.240747524688588540, -0.970587775194143630, 0.240561412388916620, - -0.970633920110692160, - 0.240375291244489500, -0.970680029339806130, 0.240189161262150040, - -0.970726102879790110, - 0.240003022448741500, -0.970772140728950350, 0.239816874811108110, - -0.970818142885593870, - 0.239630718356093560, -0.970864109348029470, 0.239444553090542720, - -0.970910040114567050, - 0.239258379021300120, -0.970955935183517970, 0.239072196155210660, - -0.971001794553194690, - 0.238886004499120170, -0.971047618221911100, 0.238699804059873950, - -0.971093406187982460, - 0.238513594844318500, -0.971139158449725090, 0.238327376859299970, - -0.971184875005457030, - 0.238141150111664870, -0.971230555853497380, 0.237954914608260650, - -0.971276200992166490, - 0.237768670355934210, -0.971321810419786160, 0.237582417361533650, - -0.971367384134679490, - 0.237396155631906550, -0.971412922135170940, 0.237209885173901620, - -0.971458424419585960, - 0.237023605994367340, -0.971503890986251780, 0.236837318100152380, - -0.971549321833496630, - 0.236651021498106460, -0.971594716959650160, 0.236464716195078750, - -0.971640076363043390, - 0.236278402197919620, -0.971685400042008540, 0.236092079513479050, - -0.971730687994879160, - 0.235905748148607370, -0.971775940219990140, 0.235719408110155930, - -0.971821156715677700, - 0.235533059404975460, -0.971866337480279400, 0.235346702039917920, - -0.971911482512134000, - 0.235160336021834860, -0.971956591809581600, 0.234973961357578310, - -0.972001665370963890, - 0.234787578054001080, -0.972046703194623380, 0.234601186117955550, - -0.972091705278904430, - 0.234414785556295250, -0.972136671622152120, 0.234228376375873380, - -0.972181602222713440, - 0.234041958583543460, -0.972226497078936270, 0.233855532186159950, - -0.972271356189170040, - 0.233669097190576820, -0.972316179551765300, 0.233482653603649170, - -0.972360967165074140, - 0.233296201432231560, -0.972405719027449770, 0.233109740683179740, - -0.972450435137246830, - 0.232923271363349120, -0.972495115492821190, 0.232736793479595420, - -0.972539760092530180, - 0.232550307038775330, -0.972584368934732210, 0.232363812047745010, - -0.972628942017787270, - 0.232177308513361770, -0.972673479340056430, 0.231990796442482580, - -0.972717980899902250, - 0.231804275841964780, -0.972762446695688570, 0.231617746718666580, - -0.972806876725780370, - 0.231431209079445730, -0.972851270988544180, 0.231244662931161110, - -0.972895629482347760, - 0.231058108280671280, -0.972939952205560070, 0.230871545134835070, - -0.972984239156551740, - 0.230684973500512310, -0.973028490333694100, 0.230498393384562320, - -0.973072705735360530, - 0.230311804793845530, -0.973116885359925130, 0.230125207735222020, - -0.973161029205763530, - 0.229938602215552260, -0.973205137271252800, 0.229751988241697600, - -0.973249209554771120, - 0.229565365820518870, -0.973293246054698250, 0.229378734958878120, - -0.973337246769414800, - 0.229192095663636740, -0.973381211697303290, 0.229005447941657390, - -0.973425140836747030, - 0.228818791799802360, -0.973469034186130950, 0.228632127244934230, - -0.973512891743841370, - 0.228445454283916550, -0.973556713508265560, 0.228258772923612350, - -0.973600499477792370, - 0.228072083170885790, -0.973644249650811870, 0.227885385032600700, - -0.973687964025715670, - 0.227698678515621170, -0.973731642600896400, 0.227511963626812390, - -0.973775285374748000, - 0.227325240373038830, -0.973818892345666100, 0.227138508761166260, - -0.973862463512047300, - 0.226951768798059980, -0.973905998872289460, 0.226765020490585720, - -0.973949498424792170, - 0.226578263845610110, -0.973992962167955830, 0.226391498869999210, - -0.974036390100182610, - 0.226204725570620270, -0.974079782219875680, 0.226017943954340190, - -0.974123138525439520, - 0.225831154028026200, -0.974166459015280320, 0.225644355798546440, - -0.974209743687805110, - 0.225457549272768540, -0.974252992541422500, 0.225270734457561240, - -0.974296205574542330, - 0.225083911359792780, -0.974339382785575860, 0.224897079986332540, - -0.974382524172935470, - 0.224710240344049570, -0.974425629735034990, 0.224523392439813170, - -0.974468699470289580, - 0.224336536280493690, -0.974511733377115720, 0.224149671872960840, - -0.974554731453931230, - 0.223962799224085520, -0.974597693699155050, 0.223775918340738290, - -0.974640620111207560, - 0.223589029229790020, -0.974683510688510670, 0.223402131898112480, - -0.974726365429487320, - 0.223215226352576960, -0.974769184332561770, 0.223028312600055870, - -0.974811967396159830, - 0.222841390647421280, -0.974854714618708430, 0.222654460501545550, - -0.974897425998635820, - 0.222467522169301990, -0.974940101534371720, 0.222280575657563370, - -0.974982741224347140, - 0.222093620973203590, -0.975025345066994120, 0.221906658123096260, - -0.975067913060746360, - 0.221719687114115240, -0.975110445204038890, 0.221532707953135340, - -0.975152941495307620, - 0.221345720647030810, -0.975195401932990370, 0.221158725202677100, - -0.975237826515525820, - 0.220971721626949060, -0.975280215241354220, 0.220784709926722670, - -0.975322568108916930, - 0.220597690108873650, -0.975364885116656870, 0.220410662180277940, - -0.975407166263018270, - 0.220223626147812460, -0.975449411546446380, 0.220036582018353550, - -0.975491620965388110, - 0.219849529798778750, -0.975533794518291360, 0.219662469495965180, - -0.975575932203605610, - 0.219475401116790340, -0.975618034019781750, 0.219288324668132580, - -0.975660099965271590, - 0.219101240156869770, -0.975702130038528570, 0.218914147589880900, - -0.975744124238007270, - 0.218727046974044600, -0.975786082562163930, 0.218539938316239830, - -0.975828005009455550, - 0.218352821623346430, -0.975869891578341030, 0.218165696902243770, - -0.975911742267280170, - 0.217978564159812290, -0.975953557074734300, 0.217791423402932120, - -0.975995335999165880, - 0.217604274638483670, -0.976037079039039020, 0.217417117873348300, - -0.976078786192818850, - 0.217229953114406790, -0.976120457458971910, 0.217042780368541080, - -0.976162092835966110, - 0.216855599642632570, -0.976203692322270560, 0.216668410943563790, - -0.976245255916355800, - 0.216481214278216900, -0.976286783616693630, 0.216294009653474370, - -0.976328275421757260, - 0.216106797076219600, -0.976369731330021140, 0.215919576553335460, - -0.976411151339961040, - 0.215732348091705940, -0.976452535450054060, 0.215545111698214660, - -0.976493883658778540, - 0.215357867379745550, -0.976535195964614470, 0.215170615143183500, - -0.976576472366042610, - 0.214983354995412820, -0.976617712861545640, 0.214796086943318920, - -0.976658917449606980, - 0.214608810993786920, -0.976700086128711840, 0.214421527153702190, - -0.976741218897346550, - 0.214234235429951100, -0.976782315753998650, 0.214046935829419330, - -0.976823376697157240, - 0.213859628358993830, -0.976864401725312640, 0.213672313025561140, - -0.976905390836956490, - 0.213484989836008080, -0.976946344030581560, 0.213297658797222430, - -0.976987261304682390, - 0.213110319916091360, -0.977028142657754390, 0.212922973199503260, - -0.977068988088294450, - 0.212735618654345870, -0.977109797594800880, 0.212548256287508120, - -0.977150571175773200, - 0.212360886105878580, -0.977191308829712280, 0.212173508116346080, - -0.977232010555120320, - 0.211986122325800410, -0.977272676350500860, 0.211798728741130820, - -0.977313306214358750, - 0.211611327369227610, -0.977353900145199960, 0.211423918216980810, - -0.977394458141532250, - 0.211236501291280710, -0.977434980201864260, 0.211049076599018500, - -0.977475466324706050, - 0.210861644147084830, -0.977515916508569280, 0.210674203942371490, - -0.977556330751966460, - 0.210486755991769890, -0.977596709053411780, 0.210299300302171750, - -0.977637051411420770, - 0.210111836880469720, -0.977677357824509930, 0.209924365733555860, - -0.977717628291197570, - 0.209736886868323370, -0.977757862810002760, 0.209549400291665110, - -0.977798061379446360, - 0.209361906010474190, -0.977838223998050430, 0.209174404031644700, - -0.977878350664338150, - 0.208986894362070070, -0.977918441376834370, 0.208799377008644980, - -0.977958496134064830, - 0.208611851978263460, -0.977998514934557140, 0.208424319277820650, - -0.978038497776839600, - 0.208236778914211470, -0.978078444659442380, 0.208049230894330940, - -0.978118355580896660, - 0.207861675225075150, -0.978158230539735050, 0.207674111913339540, - -0.978198069534491400, - 0.207486540966020700, -0.978237872563701090, 0.207298962390014880, - -0.978277639625900420, - 0.207111376192218560, -0.978317370719627650, 0.206923782379529210, - -0.978357065843421640, - 0.206736180958843660, -0.978396724995823090, 0.206548571937059940, - -0.978436348175373730, - 0.206360955321075680, -0.978475935380616830, 0.206173331117788770, - -0.978515486610096910, - 0.205985699334098050, -0.978555001862359550, 0.205798059976901760, - -0.978594481135952270, - 0.205610413053099320, -0.978633924429423100, 0.205422758569589780, - -0.978673331741322210, - 0.205235096533272380, -0.978712703070200420, 0.205047426951047380, - -0.978752038414610340, - 0.204859749829814420, -0.978791337773105670, 0.204672065176474290, - -0.978830601144241470, - 0.204484372997927180, -0.978869828526574120, 0.204296673301074430, - -0.978909019918661310, - 0.204108966092817010, -0.978948175319062200, 0.203921251380056150, - -0.978987294726337050, - 0.203733529169694010, -0.979026378139047580, 0.203545799468632190, - -0.979065425555756930, - 0.203358062283773370, -0.979104436975029250, 0.203170317622019920, - -0.979143412395430230, - 0.202982565490274460, -0.979182351815526930, 0.202794805895440550, - -0.979221255233887700, - 0.202607038844421110, -0.979260122649082020, 0.202419264344120220, - -0.979298954059681040, - 0.202231482401441620, -0.979337749464256780, 0.202043693023289280, - -0.979376508861383170, - 0.201855896216568160, -0.979415232249634780, 0.201668091988182500, - -0.979453919627588210, - 0.201480280345037820, -0.979492570993820700, 0.201292461294039190, - -0.979531186346911390, - 0.201104634842091960, -0.979569765685440520, 0.200916800996102370, - -0.979608309007989450, - 0.200728959762976140, -0.979646816313141210, 0.200541111149620090, - -0.979685287599479930, - 0.200353255162940420, -0.979723722865591170, 0.200165391809844500, - -0.979762122110061640, - 0.199977521097239290, -0.979800485331479680, 0.199789643032032120, - -0.979838812528434740, - 0.199601757621131050, -0.979877103699517640, 0.199413864871443750, - -0.979915358843320480, - 0.199225964789878890, -0.979953577958436740, 0.199038057383344820, - -0.979991761043461200, - 0.198850142658750120, -0.980029908096989980, 0.198662220623004320, - -0.980068019117620650, - 0.198474291283016360, -0.980106094103951770, 0.198286354645696270, - -0.980144133054583590, - 0.198098410717953730, -0.980182135968117320, 0.197910459506698720, - -0.980220102843155970, - 0.197722501018842030, -0.980258033678303550, 0.197534535261294000, - -0.980295928472165290, - 0.197346562240966000, -0.980333787223347960, 0.197158581964769040, - -0.980371609930459690, - 0.196970594439614370, -0.980409396592109910, 0.196782599672414240, - -0.980447147206909060, - 0.196594597670080220, -0.980484861773469380, 0.196406588439525050, - -0.980522540290404090, - 0.196218571987660850, -0.980560182756327950, 0.196030548321400880, - -0.980597789169856850, - 0.195842517447657990, -0.980635359529608120, 0.195654479373345370, - -0.980672893834200530, - 0.195466434105377090, -0.980710392082253970, 0.195278381650666520, - -0.980747854272389750, - 0.195090322016128330, -0.980785280403230430, 0.194902255208676660, - -0.980822670473399990, - 0.194714181235225990, -0.980860024481523870, 0.194526100102691720, - -0.980897342426228390, - 0.194338011817988600, -0.980934624306141640, 0.194149916388032530, - -0.980971870119892840, - 0.193961813819739010, -0.981009079866112630, 0.193773704120023840, - -0.981046253543432780, - 0.193585587295803750, -0.981083391150486590, 0.193397463353994740, - -0.981120492685908730, - 0.193209332301514080, -0.981157558148334830, 0.193021194145278320, - -0.981194587536402320, - 0.192833048892205290, -0.981231580848749730, 0.192644896549212240, - -0.981268538084016710, - 0.192456737123216840, -0.981305459240844670, 0.192268570621137590, - -0.981342344317875930, - 0.192080397049892380, -0.981379193313754560, 0.191892216416400310, - -0.981416006227125550, - 0.191704028727579940, -0.981452783056635520, 0.191515833990350240, - -0.981489523800932130, - 0.191327632211630990, -0.981526228458664660, 0.191139423398341420, - -0.981562897028483650, - 0.190951207557401860, -0.981599529509040720, 0.190762984695732250, - -0.981636125898989080, - 0.190574754820252800, -0.981672686196983110, 0.190386517937884580, - -0.981709210401678800, - 0.190198274055548120, -0.981745698511732990, 0.190010023180165050, - -0.981782150525804310, - 0.189821765318656580, -0.981818566442552500, 0.189633500477944220, - -0.981854946260638630, - 0.189445228664950340, -0.981891289978724990, 0.189256949886596720, - -0.981927597595475540, - 0.189068664149806280, -0.981963869109555240, 0.188880371461501330, - -0.982000104519630490, - 0.188692071828605260, -0.982036303824369020, 0.188503765258041080, - -0.982072467022439890, - 0.188315451756732120, -0.982108594112513610, 0.188127131331602530, - -0.982144685093261580, - 0.187938803989575850, -0.982180739963357200, 0.187750469737576840, - -0.982216758721474510, - 0.187562128582529740, -0.982252741366289370, 0.187373780531359110, - -0.982288687896478830, - 0.187185425590990440, -0.982324598310721160, 0.186997063768348510, - -0.982360472607696210, - 0.186808695070359330, -0.982396310786084690, 0.186620319503948420, - -0.982432112844569110, - 0.186431937076041640, -0.982467878781833170, 0.186243547793565670, - -0.982503608596561720, - 0.186055151663446630, -0.982539302287441240, 0.185866748692611720, - -0.982574959853159240, - 0.185678338887987790, -0.982610581292404750, 0.185489922256501900, - -0.982646166603868050, - 0.185301498805082040, -0.982681715786240860, 0.185113068540655510, - -0.982717228838215990, - 0.184924631470150870, -0.982752705758487830, 0.184736187600495930, - -0.982788146545751970, - 0.184547736938619640, -0.982823551198705240, 0.184359279491450640, - -0.982858919716046110, - 0.184170815265917720, -0.982894252096474070, 0.183982344268950600, - -0.982929548338690060, - 0.183793866507478390, -0.982964808441396440, 0.183605381988431350, - -0.983000032403296590, - 0.183416890718739230, -0.983035220223095640, 0.183228392705332140, - -0.983070371899499640, - 0.183039887955141060, -0.983105487431216290, 0.182851376475096310, - -0.983140566816954500, - 0.182662858272129360, -0.983175610055424420, 0.182474333353171260, - -0.983210617145337640, - 0.182285801725153320, -0.983245588085407070, 0.182097263395007760, - -0.983280522874346970, - 0.181908718369666160, -0.983315421510872810, 0.181720166656061170, - -0.983350283993701500, - 0.181531608261125130, -0.983385110321551180, 0.181343043191790590, - -0.983419900493141540, - 0.181154471454990920, -0.983454654507193270, 0.180965893057658980, - -0.983489372362428730, - 0.180777308006728670, -0.983524054057571260, 0.180588716309133280, - -0.983558699591345900, - 0.180400117971807270, -0.983593308962478650, 0.180211513001684590, - -0.983627882169697210, - 0.180022901405699510, -0.983662419211730250, 0.179834283190787180, - -0.983696920087308020, - 0.179645658363882100, -0.983731384795162090, 0.179457026931919950, - -0.983765813334025240, - 0.179268388901835880, -0.983800205702631490, 0.179079744280565390, - -0.983834561899716630, - 0.178891093075044830, -0.983868881924017220, 0.178702435292209940, - -0.983903165774271500, - 0.178513770938997590, -0.983937413449218920, 0.178325100022344140, - -0.983971624947600270, - 0.178136422549186320, -0.984005800268157870, 0.177947738526461670, - -0.984039939409634970, - 0.177759047961107140, -0.984074042370776450, 0.177570350860060790, - -0.984108109150328540, - 0.177381647230260200, -0.984142139747038570, 0.177192937078643310, - -0.984176134159655320, - 0.177004220412148860, -0.984210092386929030, 0.176815497237715000, - -0.984244014427611110, - 0.176626767562280960, -0.984277900280454370, 0.176438031392785350, - -0.984311749944212780, - 0.176249288736167940, -0.984345563417641900, 0.176060539599367960, - -0.984379340699498510, - 0.175871783989325040, -0.984413081788540700, 0.175683021912979580, - -0.984446786683527920, - 0.175494253377271400, -0.984480455383220930, 0.175305478389141370, - -0.984514087886381840, - 0.175116696955530060, -0.984547684191773960, 0.174927909083378160, - -0.984581244298162180, - 0.174739114779627310, -0.984614768204312600, 0.174550314051218490, - -0.984648255908992630, - 0.174361506905093830, -0.984681707410970940, 0.174172693348194960, - -0.984715122709017620, - 0.173983873387463850, -0.984748501801904210, 0.173795047029843270, - -0.984781844688403350, - 0.173606214282275410, -0.984815151367289140, 0.173417375151703520, - -0.984848421837337010, - 0.173228529645070490, -0.984881656097323700, 0.173039677769319390, - -0.984914854146027200, - 0.172850819531394200, -0.984948015982227030, 0.172661954938238270, - -0.984981141604703960, - 0.172473083996796030, -0.985014231012239840, 0.172284206714011350, - -0.985047284203618200, - 0.172095323096829040, -0.985080301177623800, 0.171906433152193700, - -0.985113281933042590, - 0.171717536887049970, -0.985146226468662230, 0.171528634308343500, - -0.985179134783271020, - 0.171339725423019260, -0.985212006875659460, 0.171150810238023340, - -0.985244842744618540, - 0.170961888760301360, -0.985277642388941220, 0.170772960996799230, - -0.985310405807421570, - 0.170584026954463700, -0.985343132998854790, 0.170395086640240920, - -0.985375823962037710, - 0.170206140061078120, -0.985408478695768420, 0.170017187223922090, - -0.985441097198846210, - 0.169828228135719880, -0.985473679470071810, 0.169639262803419400, - -0.985506225508247290, - 0.169450291233967930, -0.985538735312176060, 0.169261313434313890, - -0.985571208880662740, - 0.169072329411405180, -0.985603646212513400, 0.168883339172190010, - -0.985636047306535420, - 0.168694342723617440, -0.985668412161537550, 0.168505340072635900, - -0.985700740776329850, - 0.168316331226194910, -0.985733033149723490, 0.168127316191243350, - -0.985765289280531310, - 0.167938294974731230, -0.985797509167567370, 0.167749267583608030, - -0.985829692809647050, - 0.167560234024823590, -0.985861840205586980, 0.167371194305328540, - -0.985893951354205210, - 0.167182148432072880, -0.985926026254321130, 0.166993096412007770, - -0.985958064904755460, - 0.166804038252083870, -0.985990067304330030, 0.166614973959252090, - -0.986022033451868560, - 0.166425903540464220, -0.986053963346195440, 0.166236827002671390, - -0.986085856986136820, - 0.166047744352825850, -0.986117714370520090, 0.165858655597879430, - -0.986149535498173860, - 0.165669560744784140, -0.986181320367928270, 0.165480459800492890, - -0.986213068978614490, - 0.165291352771957970, -0.986244781329065460, 0.165102239666132720, - -0.986276457418114980, - 0.164913120489970090, -0.986308097244598670, 0.164723995250423190, - -0.986339700807353000, - 0.164534863954446110, -0.986371268105216030, 0.164345726608992190, - -0.986402799137027220, - 0.164156583221015890, -0.986434293901627070, 0.163967433797471110, - -0.986465752397857940, - 0.163778278345312690, -0.986497174624562880, 0.163589116871495160, - -0.986528560580586690, - 0.163399949382973230, -0.986559910264775410, 0.163210775886702460, - -0.986591223675976400, - 0.163021596389637810, -0.986622500813038480, 0.162832410898735260, - -0.986653741674811350, - 0.162643219420950450, -0.986684946260146690, 0.162454021963239190, - -0.986716114567897100, - 0.162264818532558110, -0.986747246596916480, 0.162075609135863330, - -0.986778342346060430, - 0.161886393780111910, -0.986809401814185420, 0.161697172472260540, - -0.986840425000149680, - 0.161507945219266150, -0.986871411902812470, 0.161318712028086540, - -0.986902362521034470, - 0.161129472905678780, -0.986933276853677710, 0.160940227859001140, - -0.986964154899605650, - 0.160750976895011390, -0.986994996657682870, 0.160561720020667510, - -0.987025802126775600, - 0.160372457242928400, -0.987056571305750970, 0.160183188568752240, - -0.987087304193477900, - 0.159993914005098350, -0.987118000788826280, 0.159804633558925380, - -0.987148661090667570, - 0.159615347237193090, -0.987179285097874340, 0.159426055046860750, - -0.987209872809320820, - 0.159236756994887850, -0.987240424223882250, 0.159047453088234840, - -0.987270939340435420, - 0.158858143333861390, -0.987301418157858430, 0.158668827738728370, - -0.987331860675030430, - 0.158479506309796100, -0.987362266890832400, 0.158290179054025180, - -0.987392636804146240, - 0.158100845978377090, -0.987422970413855410, 0.157911507089812640, - -0.987453267718844560, - 0.157722162395293690, -0.987483528717999710, 0.157532811901781670, - -0.987513753410208420, - 0.157343455616238280, -0.987543941794359230, 0.157154093545626010, - -0.987574093869342360, - 0.156964725696906750, -0.987604209634049160, 0.156775352077043430, - -0.987634289087372160, - 0.156585972692998590, -0.987664332228205710, 0.156396587551734940, - -0.987694339055445130, - 0.156207196660216040, -0.987724309567986960, 0.156017800025404830, - -0.987754243764729530, - 0.155828397654265320, -0.987784141644572180, 0.155638989553760850, - -0.987814003206415550, - 0.155449575730855880, -0.987843828449161740, 0.155260156192514380, - -0.987873617371714200, - 0.155070730945700510, -0.987903369972977790, 0.154881299997379400, - -0.987933086251858380, - 0.154691863354515400, -0.987962766207263420, 0.154502421024073990, - -0.987992409838101880, - 0.154312973013020240, -0.988022017143283530, 0.154123519328319360, - -0.988051588121720110, - 0.153934059976937460, -0.988081122772324070, 0.153744594965840000, - -0.988110621094009820, - 0.153555124301993500, -0.988140083085692570, 0.153365647992364020, - -0.988169508746289060, - 0.153176166043917870, -0.988198898074717610, 0.152986678463622160, - -0.988228251069897420, - 0.152797185258443410, -0.988257567730749460, 0.152607686435349140, - -0.988286848056195710, - 0.152418182001306500, -0.988316092045159690, 0.152228671963282770, - -0.988345299696566150, - 0.152039156328246160, -0.988374471009341280, 0.151849635103164180, - -0.988403605982412390, - 0.151660108295005400, -0.988432704614708340, 0.151470575910737760, - -0.988461766905159300, - 0.151281037957330250, -0.988490792852696590, 0.151091494441751430, - -0.988519782456253270, - 0.150901945370970040, -0.988548735714763200, 0.150712390751955720, - -0.988577652627162020, - 0.150522830591677370, -0.988606533192386450, 0.150333264897105050, - -0.988635377409374790, - 0.150143693675208330, -0.988664185277066230, 0.149954116932956990, - -0.988692956794401940, - 0.149764534677321620, -0.988721691960323780, 0.149574946915272210, - -0.988750390773775360, - 0.149385353653779810, -0.988779053233701520, 0.149195754899814960, - -0.988807679339048340, - 0.149006150660348470, -0.988836269088763540, 0.148816540942352030, - -0.988864822481795640, - 0.148626925752796540, -0.988893339517095130, 0.148437305098654050, - -0.988921820193613190, - 0.148247678986896200, -0.988950264510302990, 0.148058047424494740, - -0.988978672466118480, - 0.147868410418422360, -0.989007044060015270, 0.147678767975650970, - -0.989035379290950310, - 0.147489120103153680, -0.989063678157881540, 0.147299466807902820, - -0.989091940659768800, - 0.147109808096871850, -0.989120166795572690, 0.146920143977033760, - -0.989148356564255590, - 0.146730474455361750, -0.989176509964781010, 0.146540799538829870, - -0.989204626996113780, - 0.146351119234411440, -0.989232707657220050, 0.146161433549080950, - -0.989260751947067640, - 0.145971742489812370, -0.989288759864625170, 0.145782046063579860, - -0.989316731408863000, - 0.145592344277358450, -0.989344666578752640, 0.145402637138122540, - -0.989372565373267010, - 0.145212924652847520, -0.989400427791380380, 0.145023206828508360, - -0.989428253832068230, - 0.144833483672080240, -0.989456043494307710, 0.144643755190539150, - -0.989483796777076760, - 0.144454021390860440, -0.989511513679355190, 0.144264282280020530, - -0.989539194200123930, - 0.144074537864995330, -0.989566838338365120, 0.143884788152761010, - -0.989594446093062460, - 0.143695033150294580, -0.989622017463200780, 0.143505272864572290, - -0.989649552447766530, - 0.143315507302571590, -0.989677051045747210, 0.143125736471269140, - -0.989704513256131850, - 0.142935960377642700, -0.989731939077910570, 0.142746179028669620, - -0.989759328510075200, - 0.142556392431327340, -0.989786681551618640, 0.142366600592594260, - -0.989813998201535260, - 0.142176803519448000, -0.989841278458820530, 0.141987001218867340, - -0.989868522322471580, - 0.141797193697830530, -0.989895729791486660, 0.141607380963316020, - -0.989922900864865450, - 0.141417563022303130, -0.989950035541608990, 0.141227739881770480, - -0.989977133820719610, - 0.141037911548697770, -0.990004195701200910, 0.140848078030064220, - -0.990031221182058000, - 0.140658239332849240, -0.990058210262297120, 0.140468395464033110, - -0.990085162940925970, - 0.140278546430595420, -0.990112079216953770, 0.140088692239516780, - -0.990138959089390650, - 0.139898832897777380, -0.990165802557248400, 0.139708968412357580, - -0.990192609619540030, - 0.139519098790238600, -0.990219380275280000, 0.139329224038400980, - -0.990246114523483990, - 0.139139344163826280, -0.990272812363169110, 0.138949459173495440, - -0.990299473793353590, - 0.138759569074390380, -0.990326098813057330, 0.138569673873492640, - -0.990352687421301340, - 0.138379773577783890, -0.990379239617108160, 0.138189868194246640, - -0.990405755399501260, - 0.137999957729862760, -0.990432234767505970, 0.137810042191615130, - -0.990458677720148620, - 0.137620121586486180, -0.990485084256456980, 0.137430195921458550, - -0.990511454375460290, - 0.137240265203515700, -0.990537788076188750, 0.137050329439640380, - -0.990564085357674370, - 0.136860388636816430, -0.990590346218950150, 0.136670442802027230, - -0.990616570659050620, - 0.136480491942256310, -0.990642758677011570, 0.136290536064488070, - -0.990668910271869980, - 0.136100575175706200, -0.990695025442664630, 0.135910609282895440, - -0.990721104188435180, - 0.135720638393040080, -0.990747146508222710, 0.135530662513124620, - -0.990773152401069780, - 0.135340681650134330, -0.990799121866020370, 0.135150695811053850, - -0.990825054902119470, - 0.134960705002868830, -0.990850951508413620, 0.134770709232564290, - -0.990876811683950810, - 0.134580708507126220, -0.990902635427780010, 0.134390702833540240, - -0.990928422738951990, - 0.134200692218792020, -0.990954173616518500, 0.134010676669868210, - -0.990979888059532740, - 0.133820656193754690, -0.991005566067049370, 0.133630630797438390, - -0.991031207638124130, - 0.133440600487905820, -0.991056812771814340, 0.133250565272143570, - -0.991082381467178640, - 0.133060525157139180, -0.991107913723276780, 0.132870480149879400, - -0.991133409539170170, - 0.132680430257352130, -0.991158868913921350, 0.132490375486544710, - -0.991184291846594180, - 0.132300315844444680, -0.991209678336254060, 0.132110251338040470, - -0.991235028381967420, - 0.131920181974319760, -0.991260341982802440, 0.131730107760271280, - -0.991285619137828200, - 0.131540028702883280, -0.991310859846115440, 0.131349944809144220, - -0.991336064106736140, - 0.131159856086043410, -0.991361231918763460, 0.130969762540569380, - -0.991386363281272280, - 0.130779664179711790, -0.991411458193338540, 0.130589561010459600, - -0.991436516654039420, - 0.130399453039802740, -0.991461538662453790, 0.130209340274730770, - -0.991486524217661480, - 0.130019222722233350, -0.991511473318743900, 0.129829100389301010, - -0.991536385964783880, - 0.129638973282923540, -0.991561262154865290, 0.129448841410091830, - -0.991586101888073500, - 0.129258704777796270, -0.991610905163495370, 0.129068563393027410, - -0.991635671980218740, - 0.128878417262776660, -0.991660402337333210, 0.128688266394034690, - -0.991685096233929530, - 0.128498110793793220, -0.991709753669099530, 0.128307950469043590, - -0.991734374641936810, - 0.128117785426777150, -0.991758959151536110, 0.127927615673986190, - -0.991783507196993490, - 0.127737441217662280, -0.991808018777406430, 0.127547262064798050, - -0.991832493891873780, - 0.127357078222385570, -0.991856932539495360, 0.127166889697417180, - -0.991881334719373010, - 0.126976696496885980, -0.991905700430609330, 0.126786498627784430, - -0.991930029672308480, - 0.126596296097105960, -0.991954322443575950, 0.126406088911843320, - -0.991978578743518580, - 0.126215877078990400, -0.992002798571244520, 0.126025660605540460, - -0.992026981925863360, - 0.125835439498487020, -0.992051128806485720, 0.125645213764824380, - -0.992075239212224070, - 0.125454983411546210, -0.992099313142191800, 0.125264748445647110, - -0.992123350595503720, - 0.125074508874121300, -0.992147351571276090, 0.124884264703963150, - -0.992171316068626520, - 0.124694015942167770, -0.992195244086673920, 0.124503762595729650, - -0.992219135624538450, - 0.124313504671644300, -0.992242990681341700, 0.124123242176906760, - -0.992266809256206580, - 0.123932975118512200, -0.992290591348257370, 0.123742703503456630, - -0.992314336956619640, - 0.123552427338735370, -0.992338046080420420, 0.123362146631344750, - -0.992361718718787870, - 0.123171861388280650, -0.992385354870851670, 0.122981571616539080, - -0.992408954535742850, - 0.122791277323116900, -0.992432517712593550, 0.122600978515010240, - -0.992456044400537700, - 0.122410675199216280, -0.992479534598709970, 0.122220367382731500, - -0.992502988306246950, - 0.122030055072553410, -0.992526405522286100, 0.121839738275679020, - -0.992549786245966570, - 0.121649416999105540, -0.992573130476428810, 0.121459091249830950, - -0.992596438212814290, - 0.121268761034852550, -0.992619709454266140, 0.121078426361168710, - -0.992642944199928820, - 0.120888087235777220, -0.992666142448948020, 0.120697743665676120, - -0.992689304200470750, - 0.120507395657864240, -0.992712429453645460, 0.120317043219339670, - -0.992735518207621850, - 0.120126686357101580, -0.992758570461551140, 0.119936325078148620, - -0.992781586214585570, - 0.119745959389479630, -0.992804565465879140, 0.119555589298094230, - -0.992827508214586760, - 0.119365214810991350, -0.992850414459865100, 0.119174835935170960, - -0.992873284200871730, - 0.118984452677632520, -0.992896117436765980, 0.118794065045375670, - -0.992918914166708300, - 0.118603673045400840, -0.992941674389860470, 0.118413276684707770, - -0.992964398105385610, - 0.118222875970297250, -0.992987085312448390, 0.118032470909169300, - -0.993009736010214580, - 0.117842061508325020, -0.993032350197851410, 0.117651647774765000, - -0.993054927874527320, - 0.117461229715489990, -0.993077469039412300, 0.117270807337501560, - -0.993099973691677570, - 0.117080380647800550, -0.993122441830495580, 0.116889949653388850, - -0.993144873455040430, - 0.116699514361267840, -0.993167268564487230, 0.116509074778439050, - -0.993189627158012620, - 0.116318630911904880, -0.993211949234794500, 0.116128182768666920, - -0.993234234794012290, - 0.115937730355727850, -0.993256483834846440, 0.115747273680089870, - -0.993278696356479030, - 0.115556812748755290, -0.993300872358093280, 0.115366347568727250, - -0.993323011838873950, - 0.115175878147008180, -0.993345114798006910, 0.114985404490601530, - -0.993367181234679600, - 0.114794926606510250, -0.993389211148080650, 0.114604444501737460, - -0.993411204537400060, - 0.114413958183287050, -0.993433161401829360, 0.114223467658162260, - -0.993455081740560960, - 0.114032972933367300, -0.993476965552789190, 0.113842474015905660, - -0.993498812837709360, - 0.113651970912781920, -0.993520623594518090, 0.113461463631000080, - -0.993542397822413600, - 0.113270952177564360, -0.993564135520595300, 0.113080436559479720, - -0.993585836688263950, - 0.112889916783750470, -0.993607501324621610, 0.112699392857381910, - -0.993629129428871720, - 0.112508864787378830, -0.993650721000219120, 0.112318332580746190, - -0.993672276037870010, - 0.112127796244489750, -0.993693794541031680, 0.111937255785614560, - -0.993715276508913230, - 0.111746711211126660, -0.993736721940724600, 0.111556162528031630, - -0.993758130835677430, - 0.111365609743335190, -0.993779503192984580, 0.111175052864043830, - -0.993800839011860120, - 0.110984491897163380, -0.993822138291519660, 0.110793926849700630, - -0.993843401031180180, - 0.110603357728661910, -0.993864627230059750, 0.110412784541053660, - -0.993885816887378090, - 0.110222207293883180, -0.993906970002356060, 0.110031625994157000, - -0.993928086574215830, - 0.109841040648882680, -0.993949166602181130, 0.109650451265067080, - -0.993970210085476920, - 0.109459857849718030, -0.993991217023329380, 0.109269260409842920, - -0.994012187414966220, - 0.109078658952449240, -0.994033121259616400, 0.108888053484545310, - -0.994054018556510210, - 0.108697444013138670, -0.994074879304879370, 0.108506830545237980, - -0.994095703503956930, - 0.108316213087851300, -0.994116491152977070, 0.108125591647986880, - -0.994137242251175720, - 0.107934966232653760, -0.994157956797789730, 0.107744336848860260, - -0.994178634792057590, - 0.107553703503615710, -0.994199276233218910, 0.107363066203928920, - -0.994219881120514850, - 0.107172424956808870, -0.994240449453187900, 0.106981779769265340, - -0.994260981230481790, - 0.106791130648307380, -0.994281476451641550, 0.106600477600945030, - -0.994301935115913580, - 0.106409820634187840, -0.994322357222545810, 0.106219159755045520, - -0.994342742770787270, - 0.106028494970528530, -0.994363091759888570, 0.105837826287646670, - -0.994383404189101430, - 0.105647153713410700, -0.994403680057679100, 0.105456477254830660, - -0.994423919364875950, - 0.105265796918917650, -0.994444122109948040, 0.105075112712682180, - -0.994464288292152390, - 0.104884424643134970, -0.994484417910747600, 0.104693732717287500, - -0.994504510964993590, - 0.104503036942150550, -0.994524567454151740, 0.104312337324735870, - -0.994544587377484300, - 0.104121633872054730, -0.994564570734255420, 0.103930926591118540, - -0.994584517523730340, - 0.103740215488939480, -0.994604427745175660, 0.103549500572529040, - -0.994624301397859400, - 0.103358781848899700, -0.994644138481050710, 0.103168059325063390, - -0.994663938994020280, - 0.102977333008032250, -0.994683702936040250, 0.102786602904819150, - -0.994703430306383860, - 0.102595869022436280, -0.994723121104325700, 0.102405131367896790, - -0.994742775329142010, - 0.102214389948213370, -0.994762392980109930, 0.102023644770398800, - -0.994781974056508260, - 0.101832895841466670, -0.994801518557617110, 0.101642143168429830, - -0.994821026482717860, - 0.101451386758302160, -0.994840497831093180, 0.101260626618096800, - -0.994859932602027320, - 0.101069862754827880, -0.994879330794805620, 0.100879095175509010, - -0.994898692408714870, - 0.100688323887153970, -0.994918017443043200, 0.100497548896777310, - -0.994937305897080070, - 0.100306770211392820, -0.994956557770116380, 0.100115987838015370, - -0.994975773061444140, - 0.099925201783659226, -0.994994951770357020, 0.099734412055338839, - -0.995014093896149700, - 0.099543618660069444, -0.995033199438118630, 0.099352821604865513, - -0.995052268395561160, - 0.099162020896742573, -0.995071300767776170, 0.098971216542715582, - -0.995090296554063890, - 0.098780408549799664, -0.995109255753726110, 0.098589596925010708, - -0.995128178366065490, - 0.098398781675363881, -0.995147064390386470, 0.098207962807875346, - -0.995165913825994620, - 0.098017140329560770, -0.995184726672196820, 0.097826314247435903, - -0.995203502928301510, - 0.097635484568517339, -0.995222242593618240, 0.097444651299820870, - -0.995240945667458130, - 0.097253814448363354, -0.995259612149133390, 0.097062974021160875, - -0.995278242037957670, - 0.096872130025230527, -0.995296835333246090, 0.096681282467588864, - -0.995315392034315070, - 0.096490431355252607, -0.995333912140482280, 0.096299576695239225, - -0.995352395651066810, - 0.096108718494565468, -0.995370842565388990, 0.095917856760249096, - -0.995389252882770690, - 0.095726991499307315, -0.995407626602534900, 0.095536122718757485, - -0.995425963724006160, - 0.095345250425617742, -0.995444264246510340, 0.095154374626905472, - -0.995462528169374420, - 0.094963495329639061, -0.995480755491926940, 0.094772612540836410, - -0.995498946213497770, - 0.094581726267515473, -0.995517100333418110, 0.094390836516695067, - -0.995535217851020390, - 0.094199943295393190, -0.995553298765638470, 0.094009046610628907, - -0.995571343076607770, - 0.093818146469420494, -0.995589350783264600, 0.093627242878787237, - -0.995607321884947050, - 0.093436335845747912, -0.995625256380994310, 0.093245425377321389, - -0.995643154270746900, - 0.093054511480527333, -0.995661015553546910, 0.092863594162384697, - -0.995678840228737540, - 0.092672673429913366, -0.995696628295663520, 0.092481749290132753, - -0.995714379753670610, - 0.092290821750062355, -0.995732094602106430, 0.092099890816722485, - -0.995749772840319400, - 0.091908956497132696, -0.995767414467659820, 0.091718018798313525, - -0.995785019483478750, - 0.091527077727284981, -0.995802587887129160, 0.091336133291067212, - -0.995820119677964910, - 0.091145185496681130, -0.995837614855341610, 0.090954234351146898, - -0.995855073418615790, - 0.090763279861485704, -0.995872495367145730, 0.090572322034718156, - -0.995889880700290720, - 0.090381360877865011, -0.995907229417411720, 0.090190396397947820, - -0.995924541517870690, - 0.089999428601987341, -0.995941817001031350, 0.089808457497005362, - -0.995959055866258320, - 0.089617483090022917, -0.995976258112917790, 0.089426505388062016, - -0.995993423740377360, - 0.089235524398144139, -0.996010552748005870, 0.089044540127290905, - -0.996027645135173610, - 0.088853552582524684, -0.996044700901251970, 0.088662561770867121, - -0.996061720045614000, - 0.088471567699340822, -0.996078702567633980, 0.088280570374967879, - -0.996095648466687300, - 0.088089569804770507, -0.996112557742151130, 0.087898565995771685, - -0.996129430393403740, - 0.087707558954993645, -0.996146266419824620, 0.087516548689459586, - -0.996163065820794950, - 0.087325535206192226, -0.996179828595696870, 0.087134518512214321, - -0.996196554743914220, - 0.086943498614549489, -0.996213244264832040, 0.086752475520220515, - -0.996229897157836500, - 0.086561449236251239, -0.996246513422315520, 0.086370419769664919, - -0.996263093057658030, - 0.086179387127484922, -0.996279636063254650, 0.085988351316735448, - -0.996296142438496850, - 0.085797312344439880, -0.996312612182778000, 0.085606270217622613, - -0.996329045295492380, - 0.085415224943307277, -0.996345441776035900, 0.085224176528518519, - -0.996361801623805720, - 0.085033124980280414, -0.996378124838200210, 0.084842070305617148, - -0.996394411418619290, - 0.084651012511553700, -0.996410661364464100, 0.084459951605114297, - -0.996426874675137240, - 0.084268887593324127, -0.996443051350042630, 0.084077820483207846, - -0.996459191388585410, - 0.083886750281790226, -0.996475294790172160, 0.083695676996096827, - -0.996491361554210920, - 0.083504600633152404, -0.996507391680110820, 0.083313521199982740, - -0.996523385167282450, - 0.083122438703613077, -0.996539342015137940, 0.082931353151068726, - -0.996555262223090540, - 0.082740264549375803, -0.996571145790554840, 0.082549172905559659, - -0.996586992716946950, - 0.082358078226646619, -0.996602803001684130, 0.082166980519662466, - -0.996618576644185070, - 0.081975879791633108, -0.996634313643869900, 0.081784776049585201, - -0.996650014000160070, - 0.081593669300544638, -0.996665677712478160, 0.081402559551538328, - -0.996681304780248300, - 0.081211446809592386, -0.996696895202896060, 0.081020331081733912, - -0.996712448979848010, - 0.080829212374989468, -0.996727966110532490, 0.080638090696385709, - -0.996743446594378860, - 0.080446966052950097, -0.996758890430818000, 0.080255838451709291, - -0.996774297619282050, - 0.080064707899690932, -0.996789668159204560, 0.079873574403922148, - -0.996805002050020320, - 0.079682437971430126, -0.996820299291165670, 0.079491298609242866, - -0.996835559882078170, - 0.079300156324387569, -0.996850783822196610, 0.079109011123892431, - -0.996865971110961310, - 0.078917863014785095, -0.996881121747813850, 0.078726712004093313, - -0.996896235732197210, - 0.078535558098845590, -0.996911313063555740, 0.078344401306069678, - -0.996926353741335090, - 0.078153241632794315, -0.996941357764982160, 0.077962079086047645, - -0.996956325133945280, - 0.077770913672857989, -0.996971255847674320, 0.077579745400254363, - -0.996986149905620180, - 0.077388574275265049, -0.997001007307235290, 0.077197400304919297, - -0.997015828051973310, - 0.077006223496245585, -0.997030612139289450, 0.076815043856273399, - -0.997045359568640040, - 0.076623861392031617, -0.997060070339482960, 0.076432676110549283, - -0.997074744451277310, - 0.076241488018856149, -0.997089381903483400, 0.076050297123981231, - -0.997103982695563330, - 0.075859103432954503, -0.997118546826979980, 0.075667906952805383, - -0.997133074297198110, - 0.075476707690563416, -0.997147565105683480, 0.075285505653258880, - -0.997162019251903290, - 0.075094300847921291, -0.997176436735326190, 0.074903093281581137, - -0.997190817555421940, - 0.074711882961268378, -0.997205161711661850, 0.074520669894013014, - -0.997219469203518670, - 0.074329454086845867, -0.997233740030466160, 0.074138235546796952, - -0.997247974191979860, - 0.073947014280897269, -0.997262171687536170, 0.073755790296177265, - -0.997276332516613180, - 0.073564563599667454, -0.997290456678690210, 0.073373334198399157, - -0.997304544173247990, - 0.073182102099402888, -0.997318594999768600, 0.072990867309710133, - -0.997332609157735470, - 0.072799629836351618, -0.997346586646633230, 0.072608389686359048, - -0.997360527465947940, - 0.072417146866763538, -0.997374431615167030, 0.072225901384596336, - -0.997388299093779460, - 0.072034653246889416, -0.997402129901275300, 0.071843402460674000, - -0.997415924037145960, - 0.071652149032982254, -0.997429681500884180, 0.071460892970845832, - -0.997443402291984360, - 0.071269634281296415, -0.997457086409941910, 0.071078372971366502, - -0.997470733854253670, - 0.070887109048087787, -0.997484344624417930, 0.070695842518492924, - -0.997497918719934210, - 0.070504573389614009, -0.997511456140303450, 0.070313301668483263, - -0.997524956885027960, - 0.070122027362133646, -0.997538420953611230, 0.069930750477597295, - -0.997551848345558430, - 0.069739471021907376, -0.997565239060375750, 0.069548189002096472, - -0.997578593097570800, - 0.069356904425197236, -0.997591910456652630, 0.069165617298243109, - -0.997605191137131640, - 0.068974327628266732, -0.997618435138519550, 0.068783035422301728, - -0.997631642460329320, - 0.068591740687380900, -0.997644813102075420, 0.068400443430538069, - -0.997657947063273710, - 0.068209143658806454, -0.997671044343441000, 0.068017841379219388, - -0.997684104942096030, - 0.067826536598810966, -0.997697128858758500, 0.067635229324614451, - -0.997710116092949570, - 0.067443919563664106, -0.997723066644191640, 0.067252607322993652, - -0.997735980512008620, - 0.067061292609636836, -0.997748857695925690, 0.066869975430628226, - -0.997761698195469560, - 0.066678655793001543, -0.997774502010167820, 0.066487333703791507, - -0.997787269139549960, - 0.066296009170032283, -0.997799999583146470, 0.066104682198758091, - -0.997812693340489280, - 0.065913352797003930, -0.997825350411111640, 0.065722020971803977, - -0.997837970794548280, - 0.065530686730193397, -0.997850554490335110, 0.065339350079206798, - -0.997863101498009500, - 0.065148011025878860, -0.997875611817110150, 0.064956669577245010, - -0.997888085447177110, - 0.064765325740339871, -0.997900522387751620, 0.064573979522199065, - -0.997912922638376610, - 0.064382630929857410, -0.997925286198596000, 0.064191279970350679, - -0.997937613067955250, - 0.063999926650714078, -0.997949903246001190, 0.063808570977982898, - -0.997962156732281950, - 0.063617212959193190, -0.997974373526346990, 0.063425852601380200, - -0.997986553627747020, - 0.063234489911580136, -0.997998697036034390, 0.063043124896828631, - -0.998010803750762450, - 0.062851757564161420, -0.998022873771486240, 0.062660387920614985, - -0.998034907097761770, - 0.062469015973224969, -0.998046903729146840, 0.062277641729028041, - -0.998058863665200250, - 0.062086265195060247, -0.998070786905482340, 0.061894886378357744, - -0.998082673449554590, - 0.061703505285957416, -0.998094523296980010, 0.061512121924895365, - -0.998106336447323050, - 0.061320736302208648, -0.998118112900149180, 0.061129348424933755, - -0.998129852655025520, - 0.060937958300107238, -0.998141555711520520, 0.060746565934766412, - -0.998153222069203650, - 0.060555171335947781, -0.998164851727646240, 0.060363774510688827, - -0.998176444686420530, - 0.060172375466026218, -0.998188000945100300, 0.059980974208997596, - -0.998199520503260660, - 0.059789570746640007, -0.998211003360478190, 0.059598165085990598, - -0.998222449516330550, - 0.059406757234087247, -0.998233858970396850, 0.059215347197967026, - -0.998245231722257880, - 0.059023934984667986, -0.998256567771495180, 0.058832520601227581, - -0.998267867117692110, - 0.058641104054683348, -0.998279129760433200, 0.058449685352073573, - -0.998290355699304350, - 0.058258264500435732, -0.998301544933892890, 0.058066841506808263, - -0.998312697463787260, - 0.057875416378229017, -0.998323813288577560, 0.057683989121735932, - -0.998334892407855000, - 0.057492559744367684, -0.998345934821212370, 0.057301128253162144, - -0.998356940528243420, - 0.057109694655158132, -0.998367909528543820, 0.056918258957393907, - -0.998378841821709990, - 0.056726821166907783, -0.998389737407340160, 0.056535381290738825, - -0.998400596285033640, - 0.056343939335925283, -0.998411418454391300, 0.056152495309506383, - -0.998422203915015020, - 0.055961049218520520, -0.998432952666508440, 0.055769601070007072, - -0.998443664708476340, - 0.055578150871004817, -0.998454340040524800, 0.055386698628552604, - -0.998464978662261250, - 0.055195244349690031, -0.998475580573294770, 0.055003788041455885, - -0.998486145773235360, - 0.054812329710889909, -0.998496674261694640, 0.054620869365031251, - -0.998507166038285490, - 0.054429407010919147, -0.998517621102622210, 0.054237942655593556, - -0.998528039454320230, - 0.054046476306093640, -0.998538421092996730, 0.053855007969459509, - -0.998548766018269920, - 0.053663537652730679, -0.998559074229759310, 0.053472065362946755, - -0.998569345727086110, - 0.053280591107148056, -0.998579580509872500, 0.053089114892374119, - -0.998589778577742230, - 0.052897636725665401, -0.998599939930320370, 0.052706156614061798, - -0.998610064567233340, - 0.052514674564603257, -0.998620152488108870, 0.052323190584330471, - -0.998630203692576050, - 0.052131704680283317, -0.998640218180265270, 0.051940216859502626, - -0.998650195950808280, - 0.051748727129028414, -0.998660137003838490, 0.051557235495901653, - -0.998670041338990070, - 0.051365741967162731, -0.998679908955899090, 0.051174246549852087, - -0.998689739854202620, - 0.050982749251010900, -0.998699534033539280, 0.050791250077679546, - -0.998709291493549030, - 0.050599749036899337, -0.998719012233872940, 0.050408246135710995, - -0.998728696254153720, - 0.050216741381155325, -0.998738343554035230, 0.050025234780273840, - -0.998747954133162860, - 0.049833726340107257, -0.998757527991183340, 0.049642216067697226, - -0.998767065127744380, - 0.049450703970084824, -0.998776565542495610, 0.049259190054311168, - -0.998786029235087640, - 0.049067674327418126, -0.998795456205172410, 0.048876156796446746, - -0.998804846452403420, - 0.048684637468439020, -0.998814199976435390, 0.048493116350436342, - -0.998823516776924380, - 0.048301593449480172, -0.998832796853527990, 0.048110068772612716, - -0.998842040205904840, - 0.047918542326875327, -0.998851246833715180, 0.047727014119310344, - -0.998860416736620520, - 0.047535484156959261, -0.998869549914283560, 0.047343952446864526, - -0.998878646366368690, - 0.047152418996068000, -0.998887706092541290, 0.046960883811611599, - -0.998896729092468410, - 0.046769346900537960, -0.998905715365818290, 0.046577808269888908, - -0.998914664912260440, - 0.046386267926707213, -0.998923577731465780, 0.046194725878035046, - -0.998932453823106690, - 0.046003182130914644, -0.998941293186856870, 0.045811636692388955, - -0.998950095822391250, - 0.045620089569500123, -0.998958861729386080, 0.045428540769291224, - -0.998967590907519300, - 0.045236990298804750, -0.998976283356469820, 0.045045438165083225, - -0.998984939075918010, - 0.044853884375169933, -0.998993558065545680, 0.044662328936107311, - -0.999002140325035980, - 0.044470771854938744, -0.999010685854073380, 0.044279213138707016, - -0.999019194652343460, - 0.044087652794454979, -0.999027666719533690, 0.043896090829226200, - -0.999036102055332330, - 0.043704527250063421, -0.999044500659429290, 0.043512962064010327, - -0.999052862531515930, - 0.043321395278109784, -0.999061187671284600, 0.043129826899405595, - -0.999069476078429330, - 0.042938256934940959, -0.999077727752645360, 0.042746685391759139, - -0.999085942693629270, - 0.042555112276904117, -0.999094120901079070, 0.042363537597419038, - -0.999102262374694130, - 0.042171961360348002, -0.999110367114174890, 0.041980383572734502, - -0.999118435119223490, - 0.041788804241622082, -0.999126466389543390, 0.041597223374055005, - -0.999134460924839150, - 0.041405640977076712, -0.999142418724816910, 0.041214057057731589, - -0.999150339789184110, - 0.041022471623063397, -0.999158224117649430, 0.040830884680115968, - -0.999166071709923000, - 0.040639296235933854, -0.999173882565716380, 0.040447706297560768, - -0.999181656684742350, - 0.040256114872041358, -0.999189394066714920, 0.040064521966419686, - -0.999197094711349880, - 0.039872927587739845, -0.999204758618363890, 0.039681331743046659, - -0.999212385787475290, - 0.039489734439384118, -0.999219976218403530, 0.039298135683797149, - -0.999227529910869610, - 0.039106535483329839, -0.999235046864595850, 0.038914933845027241, - -0.999242527079305830, - 0.038723330775933762, -0.999249970554724420, 0.038531726283093877, - -0.999257377290578060, - 0.038340120373552791, -0.999264747286594420, 0.038148513054354856, - -0.999272080542502610, - 0.037956904332545366, -0.999279377058032710, 0.037765294215169005, - -0.999286636832916740, - 0.037573682709270514, -0.999293859866887790, 0.037382069821895340, - -0.999301046159680070, - 0.037190455560088091, -0.999308195711029470, 0.036998839930894332, - -0.999315308520673070, - 0.036807222941358991, -0.999322384588349540, 0.036615604598527057, - -0.999329423913798420, - 0.036423984909444228, -0.999336426496761240, 0.036232363881155374, - -0.999343392336980220, - 0.036040741520706299, -0.999350321434199440, 0.035849117835142184, - -0.999357213788164000, - 0.035657492831508264, -0.999364069398620550, 0.035465866516850478, - -0.999370888265317060, - 0.035274238898213947, -0.999377670388002850, 0.035082609982644702, - -0.999384415766428560, - 0.034890979777187955, -0.999391124400346050, 0.034699348288889847, - -0.999397796289508640, - 0.034507715524795889, -0.999404431433671300, 0.034316081491951658, - -0.999411029832589780, - 0.034124446197403423, -0.999417591486021720, 0.033932809648196623, - -0.999424116393725640, - 0.033741171851377642, -0.999430604555461730, 0.033549532813992221, - -0.999437055970991530, - 0.033357892543086159, -0.999443470640077770, 0.033166251045705968, - -0.999449848562484530, - 0.032974608328897315, -0.999456189737977340, 0.032782964399706793, - -0.999462494166323160, - 0.032591319265180385, -0.999468761847290050, 0.032399672932364114, - -0.999474992780647780, - 0.032208025408304704, -0.999481186966166950, 0.032016376700048046, - -0.999487344403620080, - 0.031824726814640963, -0.999493465092780590, 0.031633075759129645, - -0.999499549033423640, - 0.031441423540560343, -0.999505596225325310, 0.031249770165979990, - -0.999511606668263440, - 0.031058115642434700, -0.999517580362016990, 0.030866459976971503, - -0.999523517306366350, - 0.030674803176636581, -0.999529417501093140, 0.030483145248477058, - -0.999535280945980540, - 0.030291486199539423, -0.999541107640812940, 0.030099826036870208, - -0.999546897585375960, - 0.029908164767516655, -0.999552650779456990, 0.029716502398525156, - -0.999558367222844300, - 0.029524838936943035, -0.999564046915327740, 0.029333174389816984, - -0.999569689856698580, - 0.029141508764193740, -0.999575296046749220, 0.028949842067120746, - -0.999580865485273700, - 0.028758174305644590, -0.999586398172067070, 0.028566505486812797, - -0.999591894106925950, - 0.028374835617672258, -0.999597353289648380, 0.028183164705269902, - -0.999602775720033530, - 0.027991492756653365, -0.999608161397882110, 0.027799819778869434, - -0.999613510322995950, - 0.027608145778965820, -0.999618822495178640, 0.027416470763989606, - -0.999624097914234570, - 0.027224794740987910, -0.999629336579970110, 0.027033117717008563, - -0.999634538492192300, - 0.026841439699098527, -0.999639703650710200, 0.026649760694305708, - -0.999644832055333610, - 0.026458080709677145, -0.999649923705874240, 0.026266399752260809, - -0.999654978602144690, - 0.026074717829104040, -0.999659996743959220, 0.025883034947254208, - -0.999664978131133310, - 0.025691351113759395, -0.999669922763483760, 0.025499666335666818, - -0.999674830640828740, - 0.025307980620024630, -0.999679701762987930, 0.025116293973880335, - -0.999684536129782140, - 0.024924606404281485, -0.999689333741033640, 0.024732917918276334, - -0.999694094596566000, - 0.024541228522912264, -0.999698818696204250, 0.024349538225237600, - -0.999703506039774650, - 0.024157847032300020, -0.999708156627104880, 0.023966154951147241, - -0.999712770458023870, - 0.023774461988827676, -0.999717347532362190, 0.023582768152388880, - -0.999721887849951310, - 0.023391073448879338, -0.999726391410624470, 0.023199377885346890, - -0.999730858214216030, - 0.023007681468839410, -0.999735288260561680, 0.022815984206405477, - -0.999739681549498660, - 0.022624286105092803, -0.999744038080865430, 0.022432587171950024, - -0.999748357854501780, - 0.022240887414024919, -0.999752640870248840, 0.022049186838366180, - -0.999756887127949080, - 0.021857485452021874, -0.999761096627446610, 0.021665783262040089, - -0.999765269368586450, - 0.021474080275469605, -0.999769405351215280, 0.021282376499358355, - -0.999773504575180990, - 0.021090671940755180, -0.999777567040332940, 0.020898966606708289, - -0.999781592746521670, - 0.020707260504265912, -0.999785581693599210, 0.020515553640476986, - -0.999789533881418780, - 0.020323846022389572, -0.999793449309835270, 0.020132137657052664, - -0.999797327978704690, - 0.019940428551514598, -0.999801169887884260, 0.019748718712823757, - -0.999804975037232870, - 0.019557008148029204, -0.999808743426610520, 0.019365296864179146, - -0.999812475055878780, - 0.019173584868322699, -0.999816169924900410, 0.018981872167508348, - -0.999819828033539420, - 0.018790158768784596, -0.999823449381661570, 0.018598444679200642, - -0.999827033969133420, - 0.018406729905804820, -0.999830581795823400, 0.018215014455646376, - -0.999834092861600960, - 0.018023298335773701, -0.999837567166337090, 0.017831581553236088, - -0.999841004709904000, - 0.017639864115082195, -0.999844405492175240, 0.017448146028360704, - -0.999847769513025900, - 0.017256427300120978, -0.999851096772332190, 0.017064707937411529, - -0.999854387269971890, - 0.016872987947281773, -0.999857641005823860, 0.016681267336780482, - -0.999860857979768540, - 0.016489546112956454, -0.999864038191687680, 0.016297824282859176, - -0.999867181641464380, - 0.016106101853537263, -0.999870288328982950, 0.015914378832040249, - -0.999873358254129260, - 0.015722655225417017, -0.999876391416790410, 0.015530931040716478, - -0.999879387816854930, - 0.015339206284988220, -0.999882347454212560, 0.015147480965280975, - -0.999885270328754520, - 0.014955755088644378, -0.999888156440373320, 0.014764028662127416, - -0.999891005788962950, - 0.014572301692779104, -0.999893818374418490, 0.014380574187649138, - -0.999896594196636680, - 0.014188846153786343, -0.999899333255515390, 0.013997117598240459, - -0.999902035550953920, - 0.013805388528060349, -0.999904701082852900, 0.013613658950295789, - -0.999907329851114300, - 0.013421928871995907, -0.999909921855641540, 0.013230198300209845, - -0.999912477096339240, - 0.013038467241987433, -0.999914995573113470, 0.012846735704377631, - -0.999917477285871770, - 0.012655003694430301, -0.999919922234522750, 0.012463271219194662, - -0.999922330418976490, - 0.012271538285719944, -0.999924701839144500, 0.012079804901056066, - -0.999927036494939640, - 0.011888071072252072, -0.999929334386276070, 0.011696336806357907, - -0.999931595513069200, - 0.011504602110422875, -0.999933819875236000, 0.011312866991496287, - -0.999936007472694620, - 0.011121131456628141, -0.999938158305364590, 0.010929395512867561, - -0.999940272373166960, - 0.010737659167264572, -0.999942349676023910, 0.010545922426868548, - -0.999944390213859060, - 0.010354185298728884, -0.999946393986597460, 0.010162447789895645, - -0.999948360994165400, - 0.009970709907418029, -0.999950291236490480, 0.009778971658346134, - -0.999952184713501780, - 0.009587233049729183, -0.999954041425129780, 0.009395494088617302, - -0.999955861371306100, - 0.009203754782059960, -0.999957644551963900, 0.009012015137106642, - -0.999959390967037450, - 0.008820275160807512, -0.999961100616462820, 0.008628534860211857, - -0.999962773500176930, - 0.008436794242369860, -0.999964409618118280, 0.008245053314331058, - -0.999966008970226920, - 0.008053312083144991, -0.999967571556443780, 0.007861570555861883, - -0.999969097376711580, - 0.007669828739531077, -0.999970586430974140, 0.007478086641202815, - -0.999972038719176730, - 0.007286344267926684, -0.999973454241265940, 0.007094601626752279, - -0.999974832997189810, - 0.006902858724729877, -0.999976174986897610, 0.006711115568908869, - -0.999977480210339940, - 0.006519372166339549, -0.999978748667468830, 0.006327628524071549, - -0.999979980358237650, - 0.006135884649154515, -0.999981175282601110, 0.005944140548638765, - -0.999982333440515350, - 0.005752396229573737, -0.999983454831937730, 0.005560651699009764, - -0.999984539456826970, - 0.005368906963996303, -0.999985587315143200, 0.005177162031583702, - -0.999986598406848000, - 0.004985416908821652, -0.999987572731904080, 0.004793671602759852, - -0.999988510290275690, - 0.004601926120448672, -0.999989411081928400, 0.004410180468937601, - -0.999990275106828920, - 0.004218434655277024, -0.999991102364945590, 0.004026688686516664, - -0.999991892856248010, - 0.003834942569706248, -0.999992646580707190, 0.003643196311896179, - -0.999993363538295150, - 0.003451449920135975, -0.999994043728985820, 0.003259703401476044, - -0.999994687152754080, - 0.003067956762966138, -0.999995293809576190, 0.002876210011656010, - -0.999995863699429940, - 0.002684463154596083, -0.999996396822294350, 0.002492716198835898, - -0.999996893178149880, - 0.002300969151425887, -0.999997352766978210, 0.002109222019415816, - -0.999997775588762350, - 0.001917474809855460, -0.999998161643486980, 0.001725727529795258, - -0.999998510931137790, - 0.001533980186284766, -0.999998823451701880, 0.001342232786374430, - -0.999999099205167830, - 0.001150485337113809, -0.999999338191525530, 0.000958737845553352, - -0.999999540410766110, - 0.000766990318742846, -0.999999705862882230, 0.000575242763732077, - -0.999999834547867670, - 0.000383495187571497, -0.999999926465717890, 0.000191747597310674, - -0.999999981616429330, - -}; - -/** -* \par -* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
-* \par -* C command to generate the table -* \par -*
 for(i = 0; i< N; i++)    
-* {    
-*    cos_factors[i]= 2 * cos((2*i+1)*c/2);    
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -*/ -static const float32_t cos_factors_128[128] = { - 0.999981175282601110f, 0.999830581795823400f, 0.999529417501093140f, - 0.999077727752645360f, - 0.998475580573294770f, 0.997723066644191640f, 0.996820299291165670f, - 0.995767414467659820f, - 0.994564570734255420f, 0.993211949234794500f, 0.991709753669099530f, - 0.990058210262297120f, - 0.988257567730749460f, 0.986308097244598670f, 0.984210092386929030f, - 0.981963869109555240f, - 0.979569765685440520f, 0.977028142657754390f, 0.974339382785575860f, - 0.971503890986251780f, - 0.968522094274417380f, 0.965394441697689400f, 0.962121404269041580f, - 0.958703474895871600f, - 0.955141168305770780f, 0.951435020969008340f, 0.947585591017741090f, - 0.943593458161960390f, - 0.939459223602189920f, 0.935183509938947610f, 0.930766961078983710f, - 0.926210242138311380f, - 0.921514039342042010f, 0.916679059921042700f, 0.911706032005429880f, - 0.906595704514915330f, - 0.901348847046022030f, 0.895966249756185220f, 0.890448723244757880f, - 0.884797098430937790f, - 0.879012226428633530f, 0.873094978418290090f, 0.867046245515692650f, - 0.860866938637767310f, - 0.854557988365400530f, 0.848120344803297230f, 0.841554977436898440f, - 0.834862874986380010f, - 0.828045045257755800f, 0.821102514991104650f, 0.814036329705948410f, - 0.806847553543799330f, - 0.799537269107905010f, 0.792106577300212390f, 0.784556597155575240f, - 0.776888465673232440f, - 0.769103337645579700f, 0.761202385484261780f, 0.753186799043612520f, - 0.745057785441466060f, - 0.736816568877369900f, 0.728464390448225200f, 0.720002507961381650f, - 0.711432195745216430f, - 0.702754744457225300f, 0.693971460889654000f, 0.685083667772700360f, - 0.676092703575316030f, - 0.666999922303637470f, 0.657806693297078640f, 0.648514401022112550f, - 0.639124444863775730f, - 0.629638238914927100f, 0.620057211763289210f, 0.610382806276309480f, - 0.600616479383868970f, - 0.590759701858874280f, 0.580813958095764530f, 0.570780745886967370f, - 0.560661576197336030f, - 0.550457972936604810f, 0.540171472729892970f, 0.529803624686294830f, - 0.519355990165589530f, - 0.508830142543106990f, 0.498227666972781870f, 0.487550160148436050f, - 0.476799230063322250f, - 0.465976495767966130f, 0.455083587126343840f, 0.444122144570429260f, - 0.433093818853152010f, - 0.422000270799799790f, 0.410843171057903910f, 0.399624199845646790f, - 0.388345046698826300f, - 0.377007410216418310f, 0.365612997804773960f, 0.354163525420490510f, - 0.342660717311994380f, - 0.331106305759876430f, 0.319502030816015750f, 0.307849640041534980f, - 0.296150888243623960f, - 0.284407537211271820f, 0.272621355449948980f, 0.260794117915275570f, - 0.248927605745720260f, - 0.237023605994367340f, 0.225083911359792780f, 0.213110319916091360f, - 0.201104634842091960f, - 0.189068664149806280f, 0.177004220412148860f, 0.164913120489970090f, - 0.152797185258443410f, - 0.140658239332849240f, 0.128498110793793220f, 0.116318630911904880f, - 0.104121633872054730f, - 0.091908956497132696f, 0.079682437971430126f, 0.067443919563664106f, - 0.055195244349690031f, - 0.042938256934940959f, 0.030674803176636581f, 0.018406729905804820f, - 0.006135884649154515f -}; - -static const float32_t cos_factors_512[512] = { - 0.999998823451701880f, 0.999989411081928400f, 0.999970586430974140f, - 0.999942349676023910f, - 0.999904701082852900f, 0.999857641005823860f, 0.999801169887884260f, - 0.999735288260561680f, - 0.999659996743959220f, 0.999575296046749220f, 0.999481186966166950f, - 0.999377670388002850f, - 0.999264747286594420f, 0.999142418724816910f, 0.999010685854073380f, - 0.998869549914283560f, - 0.998719012233872940f, 0.998559074229759310f, 0.998389737407340160f, - 0.998211003360478190f, - 0.998022873771486240f, 0.997825350411111640f, 0.997618435138519550f, - 0.997402129901275300f, - 0.997176436735326190f, 0.996941357764982160f, 0.996696895202896060f, - 0.996443051350042630f, - 0.996179828595696980f, 0.995907229417411720f, 0.995625256380994310f, - 0.995333912140482280f, - 0.995033199438118630f, 0.994723121104325700f, 0.994403680057679100f, - 0.994074879304879370f, - 0.993736721940724600f, 0.993389211148080650f, 0.993032350197851410f, - 0.992666142448948020f, - 0.992290591348257370f, 0.991905700430609330f, 0.991511473318743900f, - 0.991107913723276890f, - 0.990695025442664630f, 0.990272812363169110f, 0.989841278458820530f, - 0.989400427791380380f, - 0.988950264510302990f, 0.988490792852696590f, 0.988022017143283530f, - 0.987543941794359230f, - 0.987056571305750970f, 0.986559910264775410f, 0.986053963346195440f, - 0.985538735312176060f, - 0.985014231012239840f, 0.984480455383220930f, 0.983937413449218920f, - 0.983385110321551180f, - 0.982823551198705240f, 0.982252741366289370f, 0.981672686196983110f, - 0.981083391150486710f, - 0.980484861773469380f, 0.979877103699517640f, 0.979260122649082020f, - 0.978633924429423210f, - 0.977998514934557140f, 0.977353900145199960f, 0.976700086128711840f, - 0.976037079039039020f, - 0.975364885116656980f, 0.974683510688510670f, 0.973992962167955830f, - 0.973293246054698250f, - 0.972584368934732210f, 0.971866337480279400f, 0.971139158449725090f, - 0.970402838687555500f, - 0.969657385124292450f, 0.968902804776428870f, 0.968139104746362440f, - 0.967366292222328510f, - 0.966584374478333120f, 0.965793358874083680f, 0.964993252854920320f, - 0.964184063951745830f, - 0.963365799780954050f, 0.962538468044359160f, 0.961702076529122540f, - 0.960856633107679660f, - 0.960002145737665960f, 0.959138622461841890f, 0.958266071408017670f, - 0.957384500788975860f, - 0.956493918902395100f, 0.955594334130771110f, 0.954685754941338340f, - 0.953768189885990330f, - 0.952841647601198720f, 0.951906136807932350f, 0.950961666311575080f, - 0.950008245001843000f, - 0.949045881852700560f, 0.948074585922276230f, 0.947094366352777220f, - 0.946105232370403450f, - 0.945107193285260610f, 0.944100258491272660f, 0.943084437466093490f, - 0.942059739771017310f, - 0.941026175050889260f, 0.939983753034014050f, 0.938932483532064600f, - 0.937872376439989890f, - 0.936803441735921560f, 0.935725689481080370f, 0.934639129819680780f, - 0.933543772978836170f, - 0.932439629268462360f, 0.931326709081180430f, 0.930205022892219070f, - 0.929074581259315860f, - 0.927935394822617890f, 0.926787474304581750f, 0.925630830509872720f, - 0.924465474325262600f, - 0.923291416719527640f, 0.922108668743345180f, 0.920917241529189520f, - 0.919717146291227360f, - 0.918508394325212250f, 0.917290997008377910f, 0.916064965799331720f, - 0.914830312237946200f, - 0.913587047945250810f, 0.912335184623322750f, 0.911074734055176360f, - 0.909805708104652220f, - 0.908528118716306120f, 0.907241977915295820f, 0.905947297807268460f, - 0.904644090578246240f, - 0.903332368494511820f, 0.902012143902493180f, 0.900683429228646970f, - 0.899346236979341570f, - 0.898000579740739880f, 0.896646470178680150f, 0.895283921038557580f, - 0.893912945145203250f, - 0.892533555402764580f, 0.891145764794583180f, 0.889749586383072780f, - 0.888345033309596350f, - 0.886932118794342190f, 0.885510856136199950f, 0.884081258712634990f, - 0.882643339979562790f, - 0.881197113471222090f, 0.879742592800047410f, 0.878279791656541580f, - 0.876808723809145650f, - 0.875329403104110890f, 0.873841843465366860f, 0.872346058894391540f, - 0.870842063470078980f, - 0.869329871348606840f, 0.867809496763303320f, 0.866280954024512990f, - 0.864744257519462380f, - 0.863199421712124160f, 0.861646461143081300f, 0.860085390429390140f, - 0.858516224264442740f, - 0.856938977417828760f, 0.855353664735196030f, 0.853760301138111410f, - 0.852158901623919830f, - 0.850549481265603480f, 0.848932055211639610f, 0.847306638685858320f, - 0.845673246987299070f, - 0.844031895490066410f, 0.842382599643185850f, 0.840725374970458070f, - 0.839060237070312740f, - 0.837387201615661940f, 0.835706284353752600f, 0.834017501106018130f, - 0.832320867767929680f, - 0.830616400308846310f, 0.828904114771864870f, 0.827184027273669130f, - 0.825456154004377550f, - 0.823720511227391430f, 0.821977115279241550f, 0.820225982569434690f, - 0.818467129580298660f, - 0.816700572866827850f, 0.814926329056526620f, 0.813144414849253590f, - 0.811354847017063730f, - 0.809557642404051260f, 0.807752817926190360f, 0.805940390571176280f, - 0.804120377398265810f, - 0.802292795538115720f, 0.800457662192622820f, 0.798614994634760820f, - 0.796764810208418830f, - 0.794907126328237010f, 0.793041960479443640f, 0.791169330217690200f, - 0.789289253168885650f, - 0.787401747029031430f, 0.785506829564053930f, 0.783604518609638200f, - 0.781694832071059390f, - 0.779777787923014550f, 0.777853404209453150f, 0.775921699043407690f, - 0.773982690606822900f, - 0.772036397150384520f, 0.770082836993347900f, 0.768122028523365420f, - 0.766153990196312920f, - 0.764178740536116670f, 0.762196298134578900f, 0.760206681651202420f, - 0.758209909813015280f, - 0.756206001414394540f, 0.754194975316889170f, 0.752176850449042810f, - 0.750151645806215070f, - 0.748119380450403600f, 0.746080073510063780f, 0.744033744179929290f, - 0.741980411720831070f, - 0.739920095459516200f, 0.737852814788465980f, 0.735778589165713590f, - 0.733697438114660370f, - 0.731609381223892630f, 0.729514438146997010f, 0.727412628602375770f, - 0.725303972373060770f, - 0.723188489306527460f, 0.721066199314508110f, 0.718937122372804490f, - 0.716801278521099540f, - 0.714658687862769090f, 0.712509370564692320f, 0.710353346857062420f, - 0.708190637033195400f, - 0.706021261449339740f, 0.703845240524484940f, 0.701662594740168570f, - 0.699473344640283770f, - 0.697277510830886630f, 0.695075113980000880f, 0.692866174817424740f, - 0.690650714134534720f, - 0.688428752784090550f, 0.686200311680038700f, 0.683965411797315510f, - 0.681724074171649820f, - 0.679476319899365080f, 0.677222170137180450f, 0.674961646102012040f, - 0.672694769070772970f, - 0.670421560380173090f, 0.668142041426518560f, 0.665856233665509720f, - 0.663564158612039880f, - 0.661265837839992270f, 0.658961292982037320f, 0.656650545729429050f, - 0.654333617831800550f, - 0.652010531096959500f, 0.649681307390683190f, 0.647345968636512060f, - 0.645004536815544040f, - 0.642657033966226860f, 0.640303482184151670f, 0.637943903621844170f, - 0.635578320488556230f, - 0.633206755050057190f, 0.630829229628424470f, 0.628445766601832710f, - 0.626056388404343520f, - 0.623661117525694640f, 0.621259976511087660f, 0.618852987960976320f, - 0.616440174530853650f, - 0.614021558931038490f, 0.611597163926462020f, 0.609167012336453210f, - 0.606731127034524480f, - 0.604289530948156070f, 0.601842247058580030f, 0.599389298400564540f, - 0.596930708062196500f, - 0.594466499184664540f, 0.591996694962040990f, 0.589521318641063940f, - 0.587040393520918080f, - 0.584553942953015330f, 0.582061990340775550f, 0.579564559139405740f, - 0.577061672855679550f, - 0.574553355047715760f, 0.572039629324757050f, 0.569520519346947250f, - 0.566996048825108680f, - 0.564466241520519500f, 0.561931121244689470f, 0.559390711859136140f, - 0.556845037275160100f, - 0.554294121453620110f, 0.551737988404707450f, 0.549176662187719770f, - 0.546610166910834860f, - 0.544038526730883930f, 0.541461765853123560f, 0.538879908531008420f, - 0.536292979065963180f, - 0.533701001807152960f, 0.531104001151255000f, 0.528502001542228480f, - 0.525895027471084740f, - 0.523283103475656430f, 0.520666254140367270f, 0.518044504095999340f, - 0.515417878019463150f, - 0.512786400633563070f, 0.510150096706766700f, 0.507508991052970870f, - 0.504863108531267480f, - 0.502212474045710900f, 0.499557112545081890f, 0.496897049022654640f, - 0.494232308515959730f, - 0.491562916106550060f, 0.488888896919763230f, 0.486210276124486530f, - 0.483527078932918740f, - 0.480839330600333900f, 0.478147056424843120f, 0.475450281747155870f, - 0.472749031950342900f, - 0.470043332459595620f, 0.467333208741988530f, 0.464618686306237820f, - 0.461899790702462840f, - 0.459176547521944150f, 0.456448982396883860f, 0.453717121000163930f, - 0.450980989045103810f, - 0.448240612285220000f, 0.445496016513981740f, 0.442747227564570130f, - 0.439994271309633260f, - 0.437237173661044200f, 0.434475960569655710f, 0.431710658025057370f, - 0.428941292055329550f, - 0.426167888726799620f, 0.423390474143796100f, 0.420609074448402510f, - 0.417823715820212380f, - 0.415034424476081630f, 0.412241226669883000f, 0.409444148692257590f, - 0.406643216870369140f, - 0.403838457567654130f, 0.401029897183575790f, 0.398217562153373620f, - 0.395401478947816300f, - 0.392581674072951530f, 0.389758174069856410f, 0.386931005514388690f, - 0.384100195016935040f, - 0.381265769222162490f, 0.378427754808765620f, 0.375586178489217330f, - 0.372741067009515810f, - 0.369892447148934270f, 0.367040345719767240f, 0.364184789567079840f, - 0.361325805568454340f, - 0.358463420633736540f, 0.355597661704783960f, 0.352728555755210730f, - 0.349856129790135030f, - 0.346980410845923680f, 0.344101425989938980f, 0.341219202320282410f, - 0.338333766965541290f, - 0.335445147084531660f, 0.332553369866044220f, 0.329658462528587550f, - 0.326760452320131790f, - 0.323859366517852960f, 0.320955232427875210f, 0.318048077385015060f, - 0.315137928752522440f, - 0.312224813921825050f, 0.309308760312268780f, 0.306389795370861080f, - 0.303467946572011370f, - 0.300543241417273400f, 0.297615707435086310f, 0.294685372180514330f, - 0.291752263234989370f, - 0.288816408206049480f, 0.285877834727080730f, 0.282936570457055390f, - 0.279992643080273380f, - 0.277046080306099950f, 0.274096909868706330f, 0.271145159526808070f, - 0.268190857063403180f, - 0.265234030285511900f, 0.262274707023913590f, 0.259312915132886350f, - 0.256348682489942910f, - 0.253382036995570270f, 0.250413006572965280f, 0.247441619167773440f, - 0.244467902747824210f, - 0.241491885302869300f, 0.238513594844318500f, 0.235533059404975460f, - 0.232550307038775330f, - 0.229565365820518870f, 0.226578263845610110f, 0.223589029229790020f, - 0.220597690108873650f, - 0.217604274638483670f, 0.214608810993786920f, 0.211611327369227610f, - 0.208611851978263460f, - 0.205610413053099320f, 0.202607038844421110f, 0.199601757621131050f, - 0.196594597670080220f, - 0.193585587295803750f, 0.190574754820252800f, 0.187562128582529740f, - 0.184547736938619640f, - 0.181531608261125130f, 0.178513770938997590f, 0.175494253377271400f, - 0.172473083996796030f, - 0.169450291233967930f, 0.166425903540464220f, 0.163399949382973230f, - 0.160372457242928400f, - 0.157343455616238280f, 0.154312973013020240f, 0.151281037957330250f, - 0.148247678986896200f, - 0.145212924652847520f, 0.142176803519448000f, 0.139139344163826280f, - 0.136100575175706200f, - 0.133060525157139180f, 0.130019222722233350f, 0.126976696496885980f, - 0.123932975118512200f, - 0.120888087235777220f, 0.117842061508325020f, 0.114794926606510250f, - 0.111746711211126660f, - 0.108697444013138670f, 0.105647153713410700f, 0.102595869022436280f, - 0.099543618660069444f, - 0.096490431355252607f, 0.093436335845747912f, 0.090381360877865011f, - 0.087325535206192226f, - 0.084268887593324127f, 0.081211446809592386f, 0.078153241632794315f, - 0.075094300847921291f, - 0.072034653246889416f, 0.068974327628266732f, 0.065913352797003930f, - 0.062851757564161420f, - 0.059789570746640007f, 0.056726821166907783f, 0.053663537652730679f, - 0.050599749036899337f, - 0.047535484156959261f, 0.044470771854938744f, 0.041405640977076712f, - 0.038340120373552791f, - 0.035274238898213947f, 0.032208025408304704f, 0.029141508764193740f, - 0.026074717829104040f, - 0.023007681468839410f, 0.019940428551514598f, 0.016872987947281773f, - 0.013805388528060349f, - 0.010737659167264572f, 0.007669828739531077f, 0.004601926120448672f, - 0.001533980186284766f -}; - -static const float32_t cos_factors_2048[2048] = { - 0.999999926465717890f, 0.999999338191525530f, 0.999998161643486980f, - 0.999996396822294350f, - 0.999994043728985820f, 0.999991102364945590f, 0.999987572731904080f, - 0.999983454831937730f, - 0.999978748667468830f, 0.999973454241265940f, 0.999967571556443780f, - 0.999961100616462820f, - 0.999954041425129780f, 0.999946393986597460f, 0.999938158305364590f, - 0.999929334386276070f, - 0.999919922234522750f, 0.999909921855641540f, 0.999899333255515390f, - 0.999888156440373320f, - 0.999876391416790410f, 0.999864038191687680f, 0.999851096772332190f, - 0.999837567166337090f, - 0.999823449381661570f, 0.999808743426610520f, 0.999793449309835270f, - 0.999777567040332940f, - 0.999761096627446610f, 0.999744038080865430f, 0.999726391410624470f, - 0.999708156627104880f, - 0.999689333741033640f, 0.999669922763483760f, 0.999649923705874240f, - 0.999629336579970110f, - 0.999608161397882110f, 0.999586398172067070f, 0.999564046915327740f, - 0.999541107640812940f, - 0.999517580362016990f, 0.999493465092780590f, 0.999468761847290050f, - 0.999443470640077770f, - 0.999417591486021720f, 0.999391124400346050f, 0.999364069398620550f, - 0.999336426496761240f, - 0.999308195711029470f, 0.999279377058032710f, 0.999249970554724420f, - 0.999219976218403530f, - 0.999189394066714920f, 0.999158224117649430f, 0.999126466389543390f, - 0.999094120901079070f, - 0.999061187671284600f, 0.999027666719533690f, 0.998993558065545680f, - 0.998958861729386080f, - 0.998923577731465780f, 0.998887706092541290f, 0.998851246833715180f, - 0.998814199976435390f, - 0.998776565542495610f, 0.998738343554035230f, 0.998699534033539280f, - 0.998660137003838490f, - 0.998620152488108870f, 0.998579580509872500f, 0.998538421092996730f, - 0.998496674261694640f, - 0.998454340040524800f, 0.998411418454391300f, 0.998367909528543820f, - 0.998323813288577560f, - 0.998279129760433200f, 0.998233858970396850f, 0.998188000945100300f, - 0.998141555711520520f, - 0.998094523296980010f, 0.998046903729146840f, 0.997998697036034390f, - 0.997949903246001190f, - 0.997900522387751620f, 0.997850554490335110f, 0.997799999583146470f, - 0.997748857695925690f, - 0.997697128858758500f, 0.997644813102075420f, 0.997591910456652630f, - 0.997538420953611340f, - 0.997484344624417930f, 0.997429681500884180f, 0.997374431615167150f, - 0.997318594999768600f, - 0.997262171687536170f, 0.997205161711661850f, 0.997147565105683480f, - 0.997089381903483400f, - 0.997030612139289450f, 0.996971255847674320f, 0.996911313063555740f, - 0.996850783822196610f, - 0.996789668159204560f, 0.996727966110532490f, 0.996665677712478160f, - 0.996602803001684130f, - 0.996539342015137940f, 0.996475294790172160f, 0.996410661364464100f, - 0.996345441776035900f, - 0.996279636063254650f, 0.996213244264832040f, 0.996146266419824620f, - 0.996078702567633980f, - 0.996010552748005870f, 0.995941817001031350f, 0.995872495367145730f, - 0.995802587887129160f, - 0.995732094602106430f, 0.995661015553546910f, 0.995589350783264600f, - 0.995517100333418110f, - 0.995444264246510340f, 0.995370842565388990f, 0.995296835333246090f, - 0.995222242593618360f, - 0.995147064390386470f, 0.995071300767776170f, 0.994994951770357020f, - 0.994918017443043200f, - 0.994840497831093180f, 0.994762392980109930f, 0.994683702936040250f, - 0.994604427745175660f, - 0.994524567454151740f, 0.994444122109948040f, 0.994363091759888570f, - 0.994281476451641550f, - 0.994199276233218910f, 0.994116491152977070f, 0.994033121259616400f, - 0.993949166602181130f, - 0.993864627230059750f, 0.993779503192984580f, 0.993693794541031790f, - 0.993607501324621610f, - 0.993520623594518090f, 0.993433161401829360f, 0.993345114798006910f, - 0.993256483834846440f, - 0.993167268564487230f, 0.993077469039412300f, 0.992987085312448390f, - 0.992896117436765980f, - 0.992804565465879140f, 0.992712429453645460f, 0.992619709454266140f, - 0.992526405522286100f, - 0.992432517712593660f, 0.992338046080420420f, 0.992242990681341700f, - 0.992147351571276090f, - 0.992051128806485720f, 0.991954322443575950f, 0.991856932539495470f, - 0.991758959151536110f, - 0.991660402337333210f, 0.991561262154865290f, 0.991461538662453790f, - 0.991361231918763460f, - 0.991260341982802440f, 0.991158868913921350f, 0.991056812771814340f, - 0.990954173616518500f, - 0.990850951508413620f, 0.990747146508222710f, 0.990642758677011570f, - 0.990537788076188750f, - 0.990432234767505970f, 0.990326098813057330f, 0.990219380275280000f, - 0.990112079216953770f, - 0.990004195701200910f, 0.989895729791486660f, 0.989786681551618640f, - 0.989677051045747210f, - 0.989566838338365120f, 0.989456043494307710f, 0.989344666578752640f, - 0.989232707657220050f, - 0.989120166795572690f, 0.989007044060015270f, 0.988893339517095130f, - 0.988779053233701520f, - 0.988664185277066230f, 0.988548735714763200f, 0.988432704614708340f, - 0.988316092045159690f, - 0.988198898074717610f, 0.988081122772324070f, 0.987962766207263420f, - 0.987843828449161740f, - 0.987724309567986960f, 0.987604209634049160f, 0.987483528717999710f, - 0.987362266890832400f, - 0.987240424223882250f, 0.987118000788826280f, 0.986994996657682980f, - 0.986871411902812470f, - 0.986747246596916590f, 0.986622500813038480f, 0.986497174624562880f, - 0.986371268105216030f, - 0.986244781329065460f, 0.986117714370520090f, 0.985990067304330140f, - 0.985861840205586980f, - 0.985733033149723490f, 0.985603646212513400f, 0.985473679470071810f, - 0.985343132998854790f, - 0.985212006875659350f, 0.985080301177623800f, 0.984948015982227030f, - 0.984815151367289140f, - 0.984681707410970940f, 0.984547684191773960f, 0.984413081788540700f, - 0.984277900280454370f, - 0.984142139747038570f, 0.984005800268157870f, 0.983868881924017220f, - 0.983731384795162090f, - 0.983593308962478650f, 0.983454654507193270f, 0.983315421510872810f, - 0.983175610055424420f, - 0.983035220223095640f, 0.982894252096474070f, 0.982752705758487830f, - 0.982610581292404750f, - 0.982467878781833170f, 0.982324598310721280f, 0.982180739963357090f, - 0.982036303824369020f, - 0.981891289978725100f, 0.981745698511732990f, 0.981599529509040720f, - 0.981452783056635520f, - 0.981305459240844670f, 0.981157558148334830f, 0.981009079866112630f, - 0.980860024481523870f, - 0.980710392082253970f, 0.980560182756327840f, 0.980409396592109910f, - 0.980258033678303550f, - 0.980106094103951770f, 0.979953577958436740f, 0.979800485331479790f, - 0.979646816313141210f, - 0.979492570993820810f, 0.979337749464256780f, 0.979182351815526930f, - 0.979026378139047580f, - 0.978869828526574120f, 0.978712703070200420f, 0.978555001862359550f, - 0.978396724995823090f, - 0.978237872563701090f, 0.978078444659442380f, 0.977918441376834370f, - 0.977757862810002760f, - 0.977596709053411890f, 0.977434980201864260f, 0.977272676350500860f, - 0.977109797594800880f, - 0.976946344030581670f, 0.976782315753998650f, 0.976617712861545640f, - 0.976452535450054060f, - 0.976286783616693630f, 0.976120457458971910f, 0.975953557074734300f, - 0.975786082562163930f, - 0.975618034019781750f, 0.975449411546446380f, 0.975280215241354220f, - 0.975110445204038890f, - 0.974940101534371830f, 0.974769184332561770f, 0.974597693699155050f, - 0.974425629735034990f, - 0.974252992541422500f, 0.974079782219875680f, 0.973905998872289570f, - 0.973731642600896400f, - 0.973556713508265560f, 0.973381211697303290f, 0.973205137271252800f, - 0.973028490333694210f, - 0.972851270988544180f, 0.972673479340056430f, 0.972495115492821190f, - 0.972316179551765300f, - 0.972136671622152230f, 0.971956591809581720f, 0.971775940219990140f, - 0.971594716959650160f, - 0.971412922135170940f, 0.971230555853497380f, 0.971047618221911100f, - 0.970864109348029470f, - 0.970680029339806130f, 0.970495378305530560f, 0.970310156353828110f, - 0.970124363593660280f, - 0.969938000134323960f, 0.969751066085452140f, 0.969563561557013180f, - 0.969375486659311280f, - 0.969186841502985950f, 0.968997626199012420f, 0.968807840858700970f, - 0.968617485593697540f, - 0.968426560515983190f, 0.968235065737874320f, 0.968043001372022260f, - 0.967850367531413620f, - 0.967657164329369880f, 0.967463391879547550f, 0.967269050295937790f, - 0.967074139692867040f, - 0.966878660184995910f, 0.966682611887320080f, 0.966485994915169840f, - 0.966288809384209690f, - 0.966091055410438830f, 0.965892733110190860f, 0.965693842600133690f, - 0.965494383997269500f, - 0.965294357418934660f, 0.965093762982799590f, 0.964892600806868890f, - 0.964690871009481030f, - 0.964488573709308410f, 0.964285709025357480f, 0.964082277076968140f, - 0.963878277983814200f, - 0.963673711865903230f, 0.963468578843575950f, 0.963262879037507070f, - 0.963056612568704340f, - 0.962849779558509030f, 0.962642380128595710f, 0.962434414400972100f, - 0.962225882497979020f, - 0.962016784542290560f, 0.961807120656913540f, 0.961596890965187860f, - 0.961386095590786250f, - 0.961174734657714080f, 0.960962808290309780f, 0.960750316613243950f, - 0.960537259751520050f, - 0.960323637830473920f, 0.960109450975773940f, 0.959894699313420530f, - 0.959679382969746750f, - 0.959463502071417510f, 0.959247056745430090f, 0.959030047119113660f, - 0.958812473320129310f, - 0.958594335476470220f, 0.958375633716461170f, 0.958156368168758820f, - 0.957936538962351420f, - 0.957716146226558870f, 0.957495190091032570f, 0.957273670685755200f, - 0.957051588141040970f, - 0.956828942587535370f, 0.956605734156215080f, 0.956381962978387730f, - 0.956157629185692140f, - 0.955932732910098280f, 0.955707274283906560f, 0.955481253439748770f, - 0.955254670510586990f, - 0.955027525629714160f, 0.954799818930753720f, 0.954571550547659630f, - 0.954342720614716480f, - 0.954113329266538800f, 0.953883376638071770f, 0.953652862864590500f, - 0.953421788081700310f, - 0.953190152425336670f, 0.952957956031764700f, 0.952725199037579570f, - 0.952491881579706320f, - 0.952258003795399600f, 0.952023565822243570f, 0.951788567798152130f, - 0.951553009861368590f, - 0.951316892150465550f, 0.951080214804345010f, 0.950842977962238160f, - 0.950605181763705340f, - 0.950366826348635780f, 0.950127911857248100f, 0.949888438430089300f, - 0.949648406208035480f, - 0.949407815332291570f, 0.949166665944390700f, 0.948924958186195160f, - 0.948682692199895090f, - 0.948439868128009620f, 0.948196486113385580f, 0.947952546299198670f, - 0.947708048828952100f, - 0.947462993846477700f, 0.947217381495934820f, 0.946971211921810880f, - 0.946724485268921170f, - 0.946477201682408680f, 0.946229361307743820f, 0.945980964290724760f, - 0.945732010777477150f, - 0.945482500914453740f, 0.945232434848435000f, 0.944981812726528150f, - 0.944730634696167800f, - 0.944478900905115550f, 0.944226611501459810f, 0.943973766633615980f, - 0.943720366450326200f, - 0.943466411100659320f, 0.943211900734010620f, 0.942956835500102120f, - 0.942701215548981900f, - 0.942445041031024890f, 0.942188312096931770f, 0.941931028897729620f, - 0.941673191584771360f, - 0.941414800309736340f, 0.941155855224629190f, 0.940896356481780830f, - 0.940636304233847590f, - 0.940375698633811540f, 0.940114539834980280f, 0.939852827990986680f, - 0.939590563255789270f, - 0.939327745783671400f, 0.939064375729241950f, 0.938800453247434770f, - 0.938535978493508560f, - 0.938270951623047190f, 0.938005372791958840f, 0.937739242156476970f, - 0.937472559873159250f, - 0.937205326098887960f, 0.936937540990869900f, 0.936669204706636170f, - 0.936400317404042060f, - 0.936130879241267030f, 0.935860890376814640f, 0.935590350969512370f, - 0.935319261178511610f, - 0.935047621163287430f, 0.934775431083638700f, 0.934502691099687870f, - 0.934229401371880820f, - 0.933955562060986730f, 0.933681173328098410f, 0.933406235334631520f, - 0.933130748242325230f, - 0.932854712213241120f, 0.932578127409764420f, 0.932300993994602760f, - 0.932023312130786490f, - 0.931745081981668720f, 0.931466303710925090f, 0.931186977482553750f, - 0.930907103460875130f, - 0.930626681810531760f, 0.930345712696488470f, 0.930064196284032360f, - 0.929782132738772190f, - 0.929499522226638560f, 0.929216364913884040f, 0.928932660967082820f, - 0.928648410553130520f, - 0.928363613839244370f, 0.928078270992963140f, 0.927792382182146320f, - 0.927505947574975180f, - 0.927218967339951790f, 0.926931441645899130f, 0.926643370661961230f, - 0.926354754557602860f, - 0.926065593502609310f, 0.925775887667086740f, 0.925485637221461490f, - 0.925194842336480530f, - 0.924903503183210910f, 0.924611619933039970f, 0.924319192757675160f, - 0.924026221829143850f, - 0.923732707319793290f, 0.923438649402290370f, 0.923144048249621930f, - 0.922848904035094120f, - 0.922553216932332830f, 0.922256987115283030f, 0.921960214758209220f, - 0.921662900035694730f, - 0.921365043122642340f, 0.921066644194273640f, 0.920767703426128790f, - 0.920468220994067110f, - 0.920168197074266340f, 0.919867631843222950f, 0.919566525477751530f, - 0.919264878154985370f, - 0.918962690052375630f, 0.918659961347691900f, 0.918356692219021720f, - 0.918052882844770380f, - 0.917748533403661250f, 0.917443644074735220f, 0.917138215037350710f, - 0.916832246471183890f, - 0.916525738556228210f, 0.916218691472794220f, 0.915911105401509880f, - 0.915602980523320230f, - 0.915294317019487050f, 0.914985115071589310f, 0.914675374861522390f, - 0.914365096571498560f, - 0.914054280384046570f, 0.913742926482011390f, 0.913431035048554720f, - 0.913118606267154240f, - 0.912805640321603500f, 0.912492137396012650f, 0.912178097674807180f, - 0.911863521342728520f, - 0.911548408584833990f, 0.911232759586496190f, 0.910916574533403360f, - 0.910599853611558930f, - 0.910282597007281760f, 0.909964804907205660f, 0.909646477498279540f, - 0.909327614967767260f, - 0.909008217503247450f, 0.908688285292613360f, 0.908367818524072890f, - 0.908046817386148340f, - 0.907725282067676440f, 0.907403212757808110f, 0.907080609646008450f, - 0.906757472922056550f, - 0.906433802776045460f, 0.906109599398381980f, 0.905784862979786550f, - 0.905459593711293250f, - 0.905133791784249690f, 0.904807457390316540f, 0.904480590721468250f, - 0.904153191969991780f, - 0.903825261328487510f, 0.903496798989868450f, 0.903167805147360720f, - 0.902838279994502830f, - 0.902508223725145940f, 0.902177636533453620f, 0.901846518613901750f, - 0.901514870161278740f, - 0.901182691370684520f, 0.900849982437531450f, 0.900516743557543520f, - 0.900182974926756810f, - 0.899848676741518580f, 0.899513849198487980f, 0.899178492494635330f, - 0.898842606827242370f, - 0.898506192393901950f, 0.898169249392518080f, 0.897831778021305650f, - 0.897493778478790310f, - 0.897155250963808550f, 0.896816195675507300f, 0.896476612813344120f, - 0.896136502577086770f, - 0.895795865166813530f, 0.895454700782912450f, 0.895113009626081760f, - 0.894770791897329550f, - 0.894428047797973800f, 0.894084777529641990f, 0.893740981294271040f, - 0.893396659294107720f, - 0.893051811731707450f, 0.892706438809935390f, 0.892360540731965360f, - 0.892014117701280470f, - 0.891667169921672280f, 0.891319697597241390f, 0.890971700932396860f, - 0.890623180131855930f, - 0.890274135400644600f, 0.889924566944096720f, 0.889574474967854580f, - 0.889223859677868210f, - 0.888872721280395630f, 0.888521059982002260f, 0.888168875989561730f, - 0.887816169510254440f, - 0.887462940751568840f, 0.887109189921300170f, 0.886754917227550840f, - 0.886400122878730600f, - 0.886044807083555600f, 0.885688970051048960f, 0.885332611990540590f, - 0.884975733111666660f, - 0.884618333624369920f, 0.884260413738899190f, 0.883901973665809470f, - 0.883543013615961880f, - 0.883183533800523390f, 0.882823534430966620f, 0.882463015719070150f, - 0.882101977876917580f, - 0.881740421116898320f, 0.881378345651706920f, 0.881015751694342870f, - 0.880652639458111010f, - 0.880289009156621010f, 0.879924861003786860f, 0.879560195213827890f, - 0.879195012001267480f, - 0.878829311580933360f, 0.878463094167957870f, 0.878096359977777130f, - 0.877729109226131570f, - 0.877361342129065140f, 0.876993058902925890f, 0.876624259764365310f, - 0.876254944930338510f, - 0.875885114618103810f, 0.875514769045222850f, 0.875143908429560360f, - 0.874772532989284150f, - 0.874400642942864790f, 0.874028238509075740f, 0.873655319906992630f, - 0.873281887355994210f, - 0.872907941075761080f, 0.872533481286276170f, 0.872158508207824480f, - 0.871783022060993120f, - 0.871407023066670950f, 0.871030511446048260f, 0.870653487420617430f, - 0.870275951212171940f, - 0.869897903042806340f, 0.869519343134916860f, 0.869140271711200560f, - 0.868760688994655310f, - 0.868380595208579800f, 0.867999990576573510f, 0.867618875322536230f, - 0.867237249670668400f, - 0.866855113845470430f, 0.866472468071743050f, 0.866089312574586770f, - 0.865705647579402380f, - 0.865321473311889800f, 0.864936789998049020f, 0.864551597864179340f, - 0.864165897136879300f, - 0.863779688043046720f, 0.863392970809878420f, 0.863005745664870320f, - 0.862618012835816740f, - 0.862229772550811240f, 0.861841025038245330f, 0.861451770526809320f, - 0.861062009245491480f, - 0.860671741423578380f, 0.860280967290654510f, 0.859889687076602290f, - 0.859497901011601730f, - 0.859105609326130450f, 0.858712812250963520f, 0.858319510017173440f, - 0.857925702856129790f, - 0.857531390999499150f, 0.857136574679244980f, 0.856741254127627470f, - 0.856345429577203610f, - 0.855949101260826910f, 0.855552269411646860f, 0.855154934263109620f, - 0.854757096048957220f, - 0.854358755003227440f, 0.853959911360254180f, 0.853560565354666840f, - 0.853160717221390420f, - 0.852760367195645300f, 0.852359515512947090f, 0.851958162409106380f, - 0.851556308120228980f, - 0.851153952882715340f, 0.850751096933260790f, 0.850347740508854980f, - 0.849943883846782210f, - 0.849539527184620890f, 0.849134670760243630f, 0.848729314811817130f, - 0.848323459577801640f, - 0.847917105296951410f, 0.847510252208314330f, 0.847102900551231500f, - 0.846695050565337450f, - 0.846286702490559710f, 0.845877856567119000f, 0.845468513035528830f, - 0.845058672136595470f, - 0.844648334111417820f, 0.844237499201387020f, 0.843826167648186740f, - 0.843414339693792760f, - 0.843002015580472940f, 0.842589195550786710f, 0.842175879847585570f, - 0.841762068714012490f, - 0.841347762393501950f, 0.840932961129779780f, 0.840517665166862550f, - 0.840101874749058400f, - 0.839685590120966110f, 0.839268811527475230f, 0.838851539213765760f, - 0.838433773425308340f, - 0.838015514407863820f, 0.837596762407483040f, 0.837177517670507300f, - 0.836757780443567190f, - 0.836337550973583530f, 0.835916829507766360f, 0.835495616293615350f, - 0.835073911578919410f, - 0.834651715611756440f, 0.834229028640493420f, 0.833805850913786340f, - 0.833382182680579730f, - 0.832958024190106670f, 0.832533375691888680f, 0.832108237435735590f, - 0.831682609671745120f, - 0.831256492650303210f, 0.830829886622083570f, 0.830402791838047550f, - 0.829975208549443950f, - 0.829547137007808910f, 0.829118577464965980f, 0.828689530173025820f, - 0.828259995384385660f, - 0.827829973351729920f, 0.827399464328029470f, 0.826968468566541600f, - 0.826536986320809960f, - 0.826105017844664610f, 0.825672563392221390f, 0.825239623217882250f, - 0.824806197576334330f, - 0.824372286722551250f, 0.823937890911791370f, 0.823503010399598500f, - 0.823067645441801670f, - 0.822631796294514990f, 0.822195463214137170f, 0.821758646457351750f, - 0.821321346281126740f, - 0.820883562942714580f, 0.820445296699652050f, 0.820006547809759680f, - 0.819567316531142230f, - 0.819127603122188240f, 0.818687407841569680f, 0.818246730948242070f, - 0.817805572701444270f, - 0.817363933360698460f, 0.816921813185809480f, 0.816479212436865390f, - 0.816036131374236810f, - 0.815592570258576790f, 0.815148529350820830f, 0.814704008912187080f, - 0.814259009204175270f, - 0.813813530488567190f, 0.813367573027426570f, 0.812921137083098770f, - 0.812474222918210480f, - 0.812026830795669730f, 0.811578960978665890f, 0.811130613730669190f, - 0.810681789315430780f, - 0.810232487996982330f, 0.809782710039636530f, 0.809332455707985950f, - 0.808881725266903610f, - 0.808430518981542720f, 0.807978837117336310f, 0.807526679939997160f, - 0.807074047715517610f, - 0.806620940710169650f, 0.806167359190504420f, 0.805713303423352230f, - 0.805258773675822210f, - 0.804803770215302920f, 0.804348293309460780f, 0.803892343226241260f, - 0.803435920233868120f, - 0.802979024600843250f, 0.802521656595946430f, 0.802063816488235440f, - 0.801605504547046150f, - 0.801146721041991360f, 0.800687466242961610f, 0.800227740420124790f, - 0.799767543843925680f, - 0.799306876785086160f, 0.798845739514604580f, 0.798384132303756380f, - 0.797922055424093000f, - 0.797459509147442460f, 0.796996493745908750f, 0.796533009491872000f, - 0.796069056657987990f, - 0.795604635517188070f, 0.795139746342679590f, 0.794674389407944550f, - 0.794208564986740640f, - 0.793742273353100210f, 0.793275514781330630f, 0.792808289546014120f, - 0.792340597922007170f, - 0.791872440184440470f, 0.791403816608719500f, 0.790934727470523290f, - 0.790465173045804880f, - 0.789995153610791090f, 0.789524669441982190f, 0.789053720816151880f, - 0.788582308010347120f, - 0.788110431301888070f, 0.787638090968367450f, 0.787165287287651010f, - 0.786692020537876790f, - 0.786218290997455660f, 0.785744098945070360f, 0.785269444659675850f, - 0.784794328420499230f, - 0.784318750507038920f, 0.783842711199065230f, 0.783366210776619720f, - 0.782889249520015480f, - 0.782411827709836530f, 0.781933945626937630f, 0.781455603552444590f, - 0.780976801767753750f, - 0.780497540554531910f, 0.780017820194715990f, 0.779537640970513260f, - 0.779057003164400630f, - 0.778575907059125050f, 0.778094352937702790f, 0.777612341083420030f, - 0.777129871779831620f, - 0.776646945310762060f, 0.776163561960304340f, 0.775679722012820650f, - 0.775195425752941420f, - 0.774710673465565550f, 0.774225465435860680f, 0.773739801949261840f, - 0.773253683291472590f, - 0.772767109748463850f, 0.772280081606474320f, 0.771792599152010150f, - 0.771304662671844830f, - 0.770816272453018540f, 0.770327428782838890f, 0.769838131948879840f, - 0.769348382238982280f, - 0.768858179941253270f, 0.768367525344066270f, 0.767876418736060610f, - 0.767384860406141730f, - 0.766892850643480670f, 0.766400389737514230f, 0.765907477977944340f, - 0.765414115654738270f, - 0.764920303058128410f, 0.764426040478612070f, 0.763931328206951090f, - 0.763436166534172010f, - 0.762940555751565720f, 0.762444496150687210f, 0.761947988023355390f, - 0.761451031661653620f, - 0.760953627357928150f, 0.760455775404789260f, 0.759957476095110330f, - 0.759458729722028210f, - 0.758959536578942440f, 0.758459896959515430f, 0.757959811157672300f, - 0.757459279467600720f, - 0.756958302183750490f, 0.756456879600833740f, 0.755955012013824420f, - 0.755452699717958250f, - 0.754949943008732640f, 0.754446742181906440f, 0.753943097533499640f, - 0.753439009359793580f, - 0.752934477957330150f, 0.752429503622912390f, 0.751924086653603550f, - 0.751418227346727470f, - 0.750911925999867890f, 0.750405182910869330f, 0.749897998377835330f, - 0.749390372699129560f, - 0.748882306173375150f, 0.748373799099454560f, 0.747864851776509410f, - 0.747355464503940190f, - 0.746845637581406540f, 0.746335371308826320f, 0.745824665986376090f, - 0.745313521914490520f, - 0.744801939393862630f, 0.744289918725443260f, 0.743777460210440890f, - 0.743264564150321600f, - 0.742751230846809050f, 0.742237460601884000f, 0.741723253717784140f, - 0.741208610497004260f, - 0.740693531242295760f, 0.740178016256666240f, 0.739662065843380010f, - 0.739145680305957510f, - 0.738628859948174840f, 0.738111605074064260f, 0.737593915987913570f, - 0.737075792994265730f, - 0.736557236397919150f, 0.736038246503927350f, 0.735518823617598900f, - 0.734998968044496710f, - 0.734478680090438370f, 0.733957960061495940f, 0.733436808263995710f, - 0.732915225004517780f, - 0.732393210589896040f, 0.731870765327218290f, 0.731347889523825570f, - 0.730824583487312160f, - 0.730300847525525490f, 0.729776681946566090f, 0.729252087058786970f, - 0.728727063170793830f, - 0.728201610591444610f, 0.727675729629849610f, 0.727149420595371020f, - 0.726622683797622850f, - 0.726095519546471000f, 0.725567928152032300f, 0.725039909924675370f, - 0.724511465175019630f, - 0.723982594213935520f, 0.723453297352544380f, 0.722923574902217700f, - 0.722393427174577550f, - 0.721862854481496340f, 0.721331857135096290f, 0.720800435447749190f, - 0.720268589732077190f, - 0.719736320300951030f, 0.719203627467491220f, 0.718670511545067230f, - 0.718136972847297490f, - 0.717603011688049080f, 0.717068628381437480f, 0.716533823241826680f, - 0.715998596583828690f, - 0.715462948722303760f, 0.714926879972359490f, 0.714390390649351390f, - 0.713853481068882470f, - 0.713316151546802610f, 0.712778402399208980f, 0.712240233942445510f, - 0.711701646493102970f, - 0.711162640368018350f, 0.710623215884275020f, 0.710083373359202800f, - 0.709543113110376770f, - 0.709002435455618250f, 0.708461340712994160f, 0.707919829200816310f, - 0.707377901237642100f, - 0.706835557142273860f, 0.706292797233758480f, 0.705749621831387790f, - 0.705206031254697830f, - 0.704662025823468930f, 0.704117605857725430f, 0.703572771677735580f, - 0.703027523604011220f, - 0.702481861957308000f, 0.701935787058624360f, 0.701389299229202230f, - 0.700842398790526230f, - 0.700295086064323780f, 0.699747361372564990f, 0.699199225037462120f, - 0.698650677381469580f, - 0.698101718727283880f, 0.697552349397843270f, 0.697002569716327460f, - 0.696452380006157830f, - 0.695901780590996830f, 0.695350771794747800f, 0.694799353941554900f, - 0.694247527355803310f, - 0.693695292362118350f, 0.693142649285365510f, 0.692589598450650380f, - 0.692036140183318830f, - 0.691482274808955850f, 0.690928002653386280f, 0.690373324042674040f, - 0.689818239303122470f, - 0.689262748761273470f, 0.688706852743907750f, 0.688150551578044830f, - 0.687593845590942170f, - 0.687036735110095660f, 0.686479220463238950f, 0.685921301978343670f, - 0.685362979983618730f, - 0.684804254807510620f, 0.684245126778703080f, 0.683685596226116690f, - 0.683125663478908800f, - 0.682565328866473250f, 0.682004592718440830f, 0.681443455364677990f, - 0.680881917135287340f, - 0.680319978360607200f, 0.679757639371212030f, 0.679194900497911200f, - 0.678631762071749470f, - 0.678068224424006600f, 0.677504287886197430f, 0.676939952790071240f, - 0.676375219467611700f, - 0.675810088251037060f, 0.675244559472799270f, 0.674678633465584540f, - 0.674112310562312360f, - 0.673545591096136100f, 0.672978475400442090f, 0.672410963808849900f, - 0.671843056655211930f, - 0.671274754273613490f, 0.670706056998372160f, 0.670136965164037760f, - 0.669567479105392490f, - 0.668997599157450270f, 0.668427325655456820f, 0.667856658934889440f, - 0.667285599331456480f, - 0.666714147181097670f, 0.666142302819983540f, 0.665570066584515560f, - 0.664997438811325340f, - 0.664424419837275180f, 0.663851009999457340f, 0.663277209635194100f, - 0.662703019082037440f, - 0.662128438677768720f, 0.661553468760399000f, 0.660978109668168060f, - 0.660402361739545030f, - 0.659826225313227430f, 0.659249700728141490f, 0.658672788323441890f, - 0.658095488438511290f, - 0.657517801412960120f, 0.656939727586627110f, 0.656361267299578000f, - 0.655782420892106030f, - 0.655203188704731930f, 0.654623571078202680f, 0.654043568353492640f, - 0.653463180871802330f, - 0.652882408974558960f, 0.652301253003415460f, 0.651719713300251020f, - 0.651137790207170330f, - 0.650555484066503990f, 0.649972795220807530f, 0.649389724012861770f, - 0.648806270785672550f, - 0.648222435882470420f, 0.647638219646710420f, 0.647053622422071650f, - 0.646468644552457890f, - 0.645883286381996440f, 0.645297548255038380f, 0.644711430516158420f, - 0.644124933510154540f, - 0.643538057582047850f, 0.642950803077082080f, 0.642363170340724320f, - 0.641775159718663500f, - 0.641186771556811250f, 0.640598006201301030f, 0.640008863998488440f, - 0.639419345294950700f, - 0.638829450437486400f, 0.638239179773115390f, 0.637648533649078810f, - 0.637057512412838590f, - 0.636466116412077180f, 0.635874345994697720f, 0.635282201508823530f, - 0.634689683302797850f, - 0.634096791725183740f, 0.633503527124764320f, 0.632909889850541860f, - 0.632315880251737680f, - 0.631721498677792370f, 0.631126745478365340f, 0.630531621003334600f, - 0.629936125602796550f, - 0.629340259627065750f, 0.628744023426674790f, 0.628147417352374120f, - 0.627550441755131530f, - 0.626953096986132770f, 0.626355383396779990f, 0.625757301338692900f, - 0.625158851163707730f, - 0.624560033223877320f, 0.623960847871470770f, 0.623361295458973340f, - 0.622761376339086460f, - 0.622161090864726930f, 0.621560439389027270f, 0.620959422265335180f, - 0.620358039847213830f, - 0.619756292488440660f, 0.619154180543008410f, 0.618551704365123860f, - 0.617948864309208260f, - 0.617345660729896940f, 0.616742093982038830f, 0.616138164420696910f, - 0.615533872401147430f, - 0.614929218278879590f, 0.614324202409595950f, 0.613718825149211830f, - 0.613113086853854910f, - 0.612506987879865570f, 0.611900528583796070f, 0.611293709322411010f, - 0.610686530452686280f, - 0.610078992331809620f, 0.609471095317180240f, 0.608862839766408200f, - 0.608254226037314490f, - 0.607645254487930830f, 0.607035925476499760f, 0.606426239361473550f, - 0.605816196501515080f, - 0.605205797255496500f, 0.604595041982500360f, 0.603983931041818020f, - 0.603372464792950370f, - 0.602760643595607220f, 0.602148467809707320f, 0.601535937795377730f, - 0.600923053912954090f, - 0.600309816522980430f, 0.599696225986208310f, 0.599082282663597310f, - 0.598467986916314310f, - 0.597853339105733910f, 0.597238339593437530f, 0.596622988741213330f, - 0.596007286911056530f, - 0.595391234465168730f, 0.594774831765957580f, 0.594158079176036800f, - 0.593540977058226390f, - 0.592923525775551410f, 0.592305725691242400f, 0.591687577168735550f, - 0.591069080571671510f, - 0.590450236263895920f, 0.589831044609458900f, 0.589211505972615070f, - 0.588591620717822890f, - 0.587971389209745120f, 0.587350811813247660f, 0.586729888893400500f, - 0.586108620815476430f, - 0.585487007944951450f, 0.584865050647504490f, 0.584242749289016980f, - 0.583620104235572760f, - 0.582997115853457700f, 0.582373784509160220f, 0.581750110569369760f, - 0.581126094400977620f, - 0.580501736371076600f, 0.579877036846960350f, 0.579251996196123550f, - 0.578626614786261430f, - 0.578000892985269910f, 0.577374831161244880f, 0.576748429682482520f, - 0.576121688917478390f, - 0.575494609234928230f, 0.574867191003726740f, 0.574239434592967890f, - 0.573611340371944610f, - 0.572982908710148680f, 0.572354139977270030f, 0.571725034543197120f, - 0.571095592778016690f, - 0.570465815052012990f, 0.569835701735668110f, 0.569205253199661200f, - 0.568574469814869250f, - 0.567943351952365670f, 0.567311899983420800f, 0.566680114279501710f, - 0.566047995212271560f, - 0.565415543153589770f, 0.564782758475511400f, 0.564149641550287680f, - 0.563516192750364910f, - 0.562882412448384550f, 0.562248301017183150f, 0.561613858829792420f, - 0.560979086259438260f, - 0.560343983679540860f, 0.559708551463714790f, 0.559072789985768480f, - 0.558436699619704100f, - 0.557800280739717100f, 0.557163533720196340f, 0.556526458935723720f, - 0.555889056761073920f, - 0.555251327571214090f, 0.554613271741304040f, 0.553974889646695610f, - 0.553336181662932410f, - 0.552697148165749770f, 0.552057789531074980f, 0.551418106135026060f, - 0.550778098353912230f, - 0.550137766564233630f, 0.549497111142680960f, 0.548856132466135290f, - 0.548214830911667780f, - 0.547573206856539870f, 0.546931260678202190f, 0.546288992754295210f, - 0.545646403462648590f, - 0.545003493181281160f, 0.544360262288400400f, 0.543716711162402390f, - 0.543072840181871850f, - 0.542428649725581360f, 0.541784140172491660f, 0.541139311901750910f, - 0.540494165292695230f, - 0.539848700724847700f, 0.539202918577918240f, 0.538556819231804210f, - 0.537910403066588990f, - 0.537263670462542530f, 0.536616621800121150f, 0.535969257459966710f, - 0.535321577822907010f, - 0.534673583269955510f, 0.534025274182310380f, 0.533376650941355560f, - 0.532727713928658810f, - 0.532078463525973540f, 0.531428900115236910f, 0.530779024078570250f, - 0.530128835798278850f, - 0.529478335656852090f, 0.528827524036961980f, 0.528176401321464370f, - 0.527524967893398200f, - 0.526873224135984700f, 0.526221170432628170f, 0.525568807166914680f, - 0.524916134722612890f, - 0.524263153483673470f, 0.523609863834228030f, 0.522956266158590140f, - 0.522302360841254700f, - 0.521648148266897090f, 0.520993628820373810f, 0.520338802886721960f, - 0.519683670851158520f, - 0.519028233099080970f, 0.518372490016066220f, 0.517716441987871150f, - 0.517060089400432130f, - 0.516403432639863990f, 0.515746472092461380f, 0.515089208144697270f, - 0.514431641183222930f, - 0.513773771594868030f, 0.513115599766640560f, 0.512457126085725800f, - 0.511798350939487000f, - 0.511139274715464390f, 0.510479897801375700f, 0.509820220585115560f, - 0.509160243454754750f, - 0.508499966798540810f, 0.507839391004897940f, 0.507178516462425290f, - 0.506517343559898530f, - 0.505855872686268860f, 0.505194104230662240f, 0.504532038582380380f, - 0.503869676130898950f, - 0.503207017265869030f, 0.502544062377115800f, 0.501880811854638400f, - 0.501217266088609950f, - 0.500553425469377640f, 0.499889290387461380f, 0.499224861233555030f, - 0.498560138398525200f, - 0.497895122273410930f, 0.497229813249424340f, 0.496564211717949340f, - 0.495898318070542240f, - 0.495232132698931350f, 0.494565655995016010f, 0.493898888350867430f, - 0.493231830158728070f, - 0.492564481811010650f, 0.491896843700299240f, 0.491228916219348330f, - 0.490560699761082080f, - 0.489892194718595300f, 0.489223401485152030f, 0.488554320454186230f, - 0.487884952019301210f, - 0.487215296574268820f, 0.486545354513030270f, 0.485875126229695420f, - 0.485204612118541880f, - 0.484533812574016120f, 0.483862727990732320f, 0.483191358763471910f, - 0.482519705287184520f, - 0.481847767956986080f, 0.481175547168160360f, 0.480503043316157670f, - 0.479830256796594250f, - 0.479157188005253310f, 0.478483837338084080f, 0.477810205191201040f, - 0.477136291960884750f, - 0.476462098043581310f, 0.475787623835901120f, 0.475112869734620470f, - 0.474437836136679340f, - 0.473762523439182850f, 0.473086932039400220f, 0.472411062334764100f, - 0.471734914722871430f, - 0.471058489601482610f, 0.470381787368520710f, 0.469704808422072460f, - 0.469027553160387240f, - 0.468350021981876530f, 0.467672215285114710f, 0.466994133468838110f, - 0.466315776931944480f, - 0.465637146073493770f, 0.464958241292706740f, 0.464279062988965760f, - 0.463599611561814120f, - 0.462919887410955130f, 0.462239890936253280f, 0.461559622537733190f, - 0.460879082615578690f, - 0.460198271570134270f, 0.459517189801903590f, 0.458835837711549120f, - 0.458154215699893230f, - 0.457472324167916110f, 0.456790163516757220f, 0.456107734147714220f, - 0.455425036462242420f, - 0.454742070861955450f, 0.454058837748624540f, 0.453375337524177750f, - 0.452691570590700860f, - 0.452007537350436530f, 0.451323238205783520f, 0.450638673559297760f, - 0.449953843813690580f, - 0.449268749371829920f, 0.448583390636739300f, 0.447897768011597360f, - 0.447211881899738260f, - 0.446525732704651400f, 0.445839320829980350f, 0.445152646679523590f, - 0.444465710657234110f, - 0.443778513167218280f, 0.443091054613736990f, 0.442403335401204130f, - 0.441715355934187310f, - 0.441027116617407340f, 0.440338617855737300f, 0.439649860054203420f, - 0.438960843617984430f, - 0.438271568952410480f, 0.437582036462964340f, 0.436892246555280470f, - 0.436202199635143950f, - 0.435511896108492170f, 0.434821336381412350f, 0.434130520860143310f, - 0.433439449951074200f, - 0.432748124060743760f, 0.432056543595841450f, 0.431364708963206440f, - 0.430672620569826860f, - 0.429980278822840570f, 0.429287684129534720f, 0.428594836897344400f, - 0.427901737533854240f, - 0.427208386446796370f, 0.426514784044051520f, 0.425820930733648350f, - 0.425126826923762410f, - 0.424432473022717420f, 0.423737869438983950f, 0.423043016581179100f, - 0.422347914858067000f, - 0.421652564678558380f, 0.420956966451709440f, 0.420261120586723050f, - 0.419565027492946940f, - 0.418868687579875110f, 0.418172101257146430f, 0.417475268934544340f, - 0.416778191021997590f, - 0.416080867929579320f, 0.415383300067506290f, 0.414685487846140010f, - 0.413987431675985510f, - 0.413289131967690960f, 0.412590589132048380f, 0.411891803579992220f, - 0.411192775722600160f, - 0.410493505971092520f, 0.409793994736831200f, 0.409094242431320920f, - 0.408394249466208110f, - 0.407694016253280170f, 0.406993543204466460f, 0.406292830731837470f, - 0.405591879247603870f, - 0.404890689164117750f, 0.404189260893870750f, 0.403487594849495310f, - 0.402785691443763640f, - 0.402083551089587040f, 0.401381174200016790f, 0.400678561188243350f, - 0.399975712467595390f, - 0.399272628451540930f, 0.398569309553686360f, 0.397865756187775750f, - 0.397161968767691720f, - 0.396457947707453960f, 0.395753693421220080f, 0.395049206323284880f, - 0.394344486828079650f, - 0.393639535350172880f, 0.392934352304269600f, 0.392228938105210370f, - 0.391523293167972350f, - 0.390817417907668610f, 0.390111312739546910f, 0.389404978078991100f, - 0.388698414341519250f, - 0.387991621942784910f, 0.387284601298575890f, 0.386577352824813980f, - 0.385869876937555310f, - 0.385162174052989970f, 0.384454244587440870f, 0.383746088957365010f, - 0.383037707579352130f, - 0.382329100870124510f, 0.381620269246537520f, 0.380911213125578130f, - 0.380201932924366050f, - 0.379492429060152740f, 0.378782701950320600f, 0.378072752012383990f, - 0.377362579663988450f, - 0.376652185322909620f, 0.375941569407054420f, 0.375230732334460030f, - 0.374519674523293210f, - 0.373808396391851370f, 0.373096898358560690f, 0.372385180841977360f, - 0.371673244260786630f, - 0.370961089033802040f, 0.370248715579966360f, 0.369536124318350760f, - 0.368823315668153960f, - 0.368110290048703050f, 0.367397047879452820f, 0.366683589579984930f, - 0.365969915570008910f, - 0.365256026269360380f, 0.364541922098002180f, 0.363827603476023610f, - 0.363113070823639530f, - 0.362398324561191310f, 0.361683365109145950f, 0.360968192888095290f, - 0.360252808318756830f, - 0.359537211821973180f, 0.358821403818710860f, 0.358105384730061760f, - 0.357389154977241000f, - 0.356672714981588260f, 0.355956065164567010f, 0.355239205947763370f, - 0.354522137752887430f, - 0.353804861001772160f, 0.353087376116372530f, 0.352369683518766630f, - 0.351651783631154680f, - 0.350933676875858360f, 0.350215363675321740f, 0.349496844452109600f, - 0.348778119628908420f, - 0.348059189628525780f, 0.347340054873889190f, 0.346620715788047320f, - 0.345901172794169100f, - 0.345181426315542610f, 0.344461476775576480f, 0.343741324597798600f, - 0.343020970205855540f, - 0.342300414023513690f, 0.341579656474657210f, 0.340858697983289440f, - 0.340137538973531880f, - 0.339416179869623410f, 0.338694621095921190f, 0.337972863076899830f, - 0.337250906237150650f, - 0.336528751001382350f, 0.335806397794420560f, 0.335083847041206580f, - 0.334361099166798900f, - 0.333638154596370920f, 0.332915013755212650f, 0.332191677068729320f, - 0.331468144962440920f, - 0.330744417861982890f, 0.330020496193105530f, 0.329296380381672800f, - 0.328572070853663690f, - 0.327847568035170960f, 0.327122872352400510f, 0.326397984231672660f, - 0.325672904099419900f, - 0.324947632382188430f, 0.324222169506637130f, 0.323496515899536760f, - 0.322770671987770710f, - 0.322044638198334620f, 0.321318414958334910f, 0.320592002694990330f, - 0.319865401835630610f, - 0.319138612807695900f, 0.318411636038737960f, 0.317684471956418020f, - 0.316957120988508150f, - 0.316229583562890490f, 0.315501860107556040f, 0.314773951050606070f, - 0.314045856820250820f, - 0.313317577844809070f, 0.312589114552708660f, 0.311860467372486130f, - 0.311131636732785270f, - 0.310402623062358880f, 0.309673426790066490f, 0.308944048344875710f, - 0.308214488155861220f, - 0.307484746652204160f, 0.306754824263192780f, 0.306024721418221900f, - 0.305294438546791720f, - 0.304563976078509050f, 0.303833334443086470f, 0.303102514070341060f, - 0.302371515390196130f, - 0.301640338832678880f, 0.300908984827921890f, 0.300177453806162120f, - 0.299445746197739950f, - 0.298713862433100390f, 0.297981802942791920f, 0.297249568157465890f, - 0.296517158507877410f, - 0.295784574424884370f, 0.295051816339446720f, 0.294318884682627570f, - 0.293585779885591310f, - 0.292852502379604810f, 0.292119052596036540f, 0.291385430966355720f, - 0.290651637922133220f, - 0.289917673895040860f, 0.289183539316850310f, 0.288449234619434170f, - 0.287714760234765280f, - 0.286980116594915570f, 0.286245304132057120f, 0.285510323278461380f, - 0.284775174466498300f, - 0.284039858128637360f, 0.283304374697445790f, 0.282568724605589740f, - 0.281832908285833460f, - 0.281096926171038320f, 0.280360778694163810f, 0.279624466288266700f, - 0.278887989386500280f, - 0.278151348422115090f, 0.277414543828458200f, 0.276677576038972420f, - 0.275940445487197320f, - 0.275203152606767370f, 0.274465697831413220f, 0.273728081594960650f, - 0.272990304331329980f, - 0.272252366474536660f, 0.271514268458690810f, 0.270776010717996010f, - 0.270037593686750510f, - 0.269299017799346230f, 0.268560283490267890f, 0.267821391194094320f, - 0.267082341345496350f, - 0.266343134379238180f, 0.265603770730176440f, 0.264864250833259320f, - 0.264124575123527490f, - 0.263384744036113390f, 0.262644758006240100f, 0.261904617469222560f, - 0.261164322860466590f, - 0.260423874615468010f, 0.259683273169813930f, 0.258942518959180580f, - 0.258201612419334870f, - 0.257460553986133210f, 0.256719344095520720f, 0.255977983183532380f, - 0.255236471686291820f, - 0.254494810040010790f, 0.253752998680989940f, 0.253011038045617980f, - 0.252268928570370810f, - 0.251526670691812780f, 0.250784264846594550f, 0.250041711471454650f, - 0.249299011003218300f, - 0.248556163878796620f, 0.247813170535187620f, 0.247070031409475370f, - 0.246326746938829060f, - 0.245583317560504000f, 0.244839743711840750f, 0.244096025830264210f, - 0.243352164353284880f, - 0.242608159718496890f, 0.241864012363579210f, 0.241119722726294730f, - 0.240375291244489500f, - 0.239630718356093560f, 0.238886004499120170f, 0.238141150111664870f, - 0.237396155631906550f, - 0.236651021498106460f, 0.235905748148607370f, 0.235160336021834860f, - 0.234414785556295250f, - 0.233669097190576820f, 0.232923271363349120f, 0.232177308513361770f, - 0.231431209079445730f, - 0.230684973500512310f, 0.229938602215552260f, 0.229192095663636740f, - 0.228445454283916550f, - 0.227698678515621170f, 0.226951768798059980f, 0.226204725570620270f, - 0.225457549272768540f, - 0.224710240344049570f, 0.223962799224085520f, 0.223215226352576960f, - 0.222467522169301990f, - 0.221719687114115240f, 0.220971721626949060f, 0.220223626147812460f, - 0.219475401116790340f, - 0.218727046974044600f, 0.217978564159812290f, 0.217229953114406790f, - 0.216481214278216900f, - 0.215732348091705940f, 0.214983354995412820f, 0.214234235429951100f, - 0.213484989836008080f, - 0.212735618654345870f, 0.211986122325800410f, 0.211236501291280710f, - 0.210486755991769890f, - 0.209736886868323370f, 0.208986894362070070f, 0.208236778914211470f, - 0.207486540966020700f, - 0.206736180958843660f, 0.205985699334098050f, 0.205235096533272380f, - 0.204484372997927180f, - 0.203733529169694010f, 0.202982565490274460f, 0.202231482401441620f, - 0.201480280345037820f, - 0.200728959762976140f, 0.199977521097239290f, 0.199225964789878890f, - 0.198474291283016360f, - 0.197722501018842030f, 0.196970594439614370f, 0.196218571987660850f, - 0.195466434105377090f, - 0.194714181235225990f, 0.193961813819739010f, 0.193209332301514080f, - 0.192456737123216840f, - 0.191704028727579940f, 0.190951207557401860f, 0.190198274055548120f, - 0.189445228664950340f, - 0.188692071828605260f, 0.187938803989575850f, 0.187185425590990440f, - 0.186431937076041640f, - 0.185678338887987790f, 0.184924631470150870f, 0.184170815265917720f, - 0.183416890718739230f, - 0.182662858272129360f, 0.181908718369666160f, 0.181154471454990920f, - 0.180400117971807270f, - 0.179645658363882100f, 0.178891093075044830f, 0.178136422549186320f, - 0.177381647230260200f, - 0.176626767562280960f, 0.175871783989325040f, 0.175116696955530060f, - 0.174361506905093830f, - 0.173606214282275410f, 0.172850819531394200f, 0.172095323096829040f, - 0.171339725423019260f, - 0.170584026954463700f, 0.169828228135719880f, 0.169072329411405180f, - 0.168316331226194910f, - 0.167560234024823590f, 0.166804038252083870f, 0.166047744352825850f, - 0.165291352771957970f, - 0.164534863954446110f, 0.163778278345312690f, 0.163021596389637810f, - 0.162264818532558110f, - 0.161507945219266150f, 0.160750976895011390f, 0.159993914005098350f, - 0.159236756994887850f, - 0.158479506309796100f, 0.157722162395293690f, 0.156964725696906750f, - 0.156207196660216040f, - 0.155449575730855880f, 0.154691863354515400f, 0.153934059976937460f, - 0.153176166043917870f, - 0.152418182001306500f, 0.151660108295005400f, 0.150901945370970040f, - 0.150143693675208330f, - 0.149385353653779810f, 0.148626925752796540f, 0.147868410418422360f, - 0.147109808096871850f, - 0.146351119234411440f, 0.145592344277358450f, 0.144833483672080240f, - 0.144074537864995330f, - 0.143315507302571590f, 0.142556392431327340f, 0.141797193697830530f, - 0.141037911548697770f, - 0.140278546430595420f, 0.139519098790238600f, 0.138759569074390380f, - 0.137999957729862760f, - 0.137240265203515700f, 0.136480491942256310f, 0.135720638393040080f, - 0.134960705002868830f, - 0.134200692218792020f, 0.133440600487905820f, 0.132680430257352130f, - 0.131920181974319760f, - 0.131159856086043410f, 0.130399453039802740f, 0.129638973282923540f, - 0.128878417262776660f, - 0.128117785426777150f, 0.127357078222385570f, 0.126596296097105960f, - 0.125835439498487020f, - 0.125074508874121300f, 0.124313504671644300f, 0.123552427338735370f, - 0.122791277323116900f, - 0.122030055072553410f, 0.121268761034852550f, 0.120507395657864240f, - 0.119745959389479630f, - 0.118984452677632520f, 0.118222875970297250f, 0.117461229715489990f, - 0.116699514361267840f, - 0.115937730355727850f, 0.115175878147008180f, 0.114413958183287050f, - 0.113651970912781920f, - 0.112889916783750470f, 0.112127796244489750f, 0.111365609743335190f, - 0.110603357728661910f, - 0.109841040648882680f, 0.109078658952449240f, 0.108316213087851300f, - 0.107553703503615710f, - 0.106791130648307380f, 0.106028494970528530f, 0.105265796918917650f, - 0.104503036942150550f, - 0.103740215488939480f, 0.102977333008032250f, 0.102214389948213370f, - 0.101451386758302160f, - 0.100688323887153970f, 0.099925201783659226f, 0.099162020896742573f, - 0.098398781675363881f, - 0.097635484568517339f, 0.096872130025230527f, 0.096108718494565468f, - 0.095345250425617742f, - 0.094581726267515473f, 0.093818146469420494f, 0.093054511480527333f, - 0.092290821750062355f, - 0.091527077727284981f, 0.090763279861485704f, 0.089999428601987341f, - 0.089235524398144139f, - 0.088471567699340822f, 0.087707558954993645f, 0.086943498614549489f, - 0.086179387127484922f, - 0.085415224943307277f, 0.084651012511553700f, 0.083886750281790226f, - 0.083122438703613077f, - 0.082358078226646619f, 0.081593669300544638f, 0.080829212374989468f, - 0.080064707899690932f, - 0.079300156324387569f, 0.078535558098845590f, 0.077770913672857989f, - 0.077006223496245585f, - 0.076241488018856149f, 0.075476707690563416f, 0.074711882961268378f, - 0.073947014280897269f, - 0.073182102099402888f, 0.072417146866763538f, 0.071652149032982254f, - 0.070887109048087787f, - 0.070122027362133646f, 0.069356904425197236f, 0.068591740687380900f, - 0.067826536598810966f, - 0.067061292609636836f, 0.066296009170032283f, 0.065530686730193397f, - 0.064765325740339871f, - 0.063999926650714078f, 0.063234489911580136f, 0.062469015973224969f, - 0.061703505285957416f, - 0.060937958300107238f, 0.060172375466026218f, 0.059406757234087247f, - 0.058641104054683348f, - 0.057875416378229017f, 0.057109694655158132f, 0.056343939335925283f, - 0.055578150871004817f, - 0.054812329710889909f, 0.054046476306093640f, 0.053280591107148056f, - 0.052514674564603257f, - 0.051748727129028414f, 0.050982749251010900f, 0.050216741381155325f, - 0.049450703970084824f, - 0.048684637468439020f, 0.047918542326875327f, 0.047152418996068000f, - 0.046386267926707213f, - 0.045620089569500123f, 0.044853884375169933f, 0.044087652794454979f, - 0.043321395278109784f, - 0.042555112276904117f, 0.041788804241622082f, 0.041022471623063397f, - 0.040256114872041358f, - 0.039489734439384118f, 0.038723330775933762f, 0.037956904332545366f, - 0.037190455560088091f, - 0.036423984909444228f, 0.035657492831508264f, 0.034890979777187955f, - 0.034124446197403423f, - 0.033357892543086159f, 0.032591319265180385f, 0.031824726814640963f, - 0.031058115642434700f, - 0.030291486199539423f, 0.029524838936943035f, 0.028758174305644590f, - 0.027991492756653365f, - 0.027224794740987910f, 0.026458080709677145f, 0.025691351113759395f, - 0.024924606404281485f, - 0.024157847032300020f, 0.023391073448879338f, 0.022624286105092803f, - 0.021857485452021874f, - 0.021090671940755180f, 0.020323846022389572f, 0.019557008148029204f, - 0.018790158768784596f, - 0.018023298335773701f, 0.017256427300120978f, 0.016489546112956454f, - 0.015722655225417017f, - 0.014955755088644378f, 0.014188846153786343f, 0.013421928871995907f, - 0.012655003694430301f, - 0.011888071072252072f, 0.011121131456628141f, 0.010354185298728884f, - 0.009587233049729183f, - 0.008820275160807512f, 0.008053312083144991f, 0.007286344267926684f, - 0.006519372166339549f, - 0.005752396229573737f, 0.004985416908821652f, 0.004218434655277024f, - 0.003451449920135975f, - 0.002684463154596083f, 0.001917474809855460f, 0.001150485337113809f, - 0.000383495187571497f -}; - -static const float32_t cos_factors_8192[8192] = { - 1.999999990808214700, 1.999999917273932200, 1.999999770205369800, - 1.999999549602533100, - 1.999999255465430200, 1.999998887794072000, 1.999998446588471700, - 1.999997931848645600, - 1.999997343574612800, 1.999996681766395000, 1.999995946424016200, - 1.999995137547503600, - 1.999994255136887000, 1.999993299192198700, 1.999992269713474200, - 1.999991166700750800, - 1.999989990154069600, 1.999988740073473500, 1.999987416459008600, - 1.999986019310723500, - 1.999984548628669600, 1.999983004412901000, 1.999981386663474400, - 1.999979695380449400, - 1.999977930563888100, 1.999976092213855400, 1.999974180330418700, - 1.999972194913648900, - 1.999970135963618400, 1.999968003480403000, 1.999965797464081200, - 1.999963517914734100, - 1.999961164832445800, 1.999958738217302300, 1.999956238069392900, - 1.999953664388809800, - 1.999951017175647600, 1.999948296430003500, 1.999945502151977600, - 1.999942634341672600, - 1.999939692999193900, 1.999936678124649700, 1.999933589718150700, - 1.999930427779810900, - 1.999927192309745900, 1.999923883308075200, 1.999920500774920300, - 1.999917044710405500, - 1.999913515114657900, 1.999909911987807200, 1.999906235329986100, - 1.999902485141329400, - 1.999898661421975400, 1.999894764172064600, 1.999890793391740000, - 1.999886749081147800, - 1.999882631240436700, 1.999878439869758200, 1.999874174969266300, - 1.999869836539117700, - 1.999865424579472000, 1.999860939090491600, 1.999856380072341000, - 1.999851747525188200, - 1.999847041449203300, 1.999842261844559700, 1.999837408711432600, - 1.999832482050000900, - 1.999827481860445300, 1.999822408142949900, 1.999817260897701400, - 1.999812040124888700, - 1.999806745824704000, 1.999801377997341800, 1.999795936642999600, - 1.999790421761877400, - 1.999784833354177900, 1.999779171420106700, 1.999773435959872000, - 1.999767626973684400, - 1.999761744461757700, 1.999755788424308200, 1.999749758861554900, - 1.999743655773719400, - 1.999737479161026100, 1.999731229023702200, 1.999724905361977200, - 1.999718508176084000, - 1.999712037466257600, 1.999705493232735800, 1.999698875475759600, - 1.999692184195571900, - 1.999685419392419000, 1.999678581066549400, 1.999671669218214600, - 1.999664683847668800, - 1.999657624955168700, 1.999650492540973900, 1.999643286605346800, - 1.999636007148552400, - 1.999628654170857900, 1.999621227672533800, 1.999613727653853500, - 1.999606154115092500, - 1.999598507056529000, 1.999590786478444600, 1.999582992381123000, - 1.999575124764850800, - 1.999567183629917100, 1.999559168976613900, 1.999551080805236100, - 1.999542919116081000, - 1.999534683909448600, 1.999526375185641800, 1.999517992944965800, - 1.999509537187729200, - 1.999501007914242600, 1.999492405124819700, 1.999483728819776900, - 1.999474978999432800, - 1.999466155664109600, 1.999457258814131500, 1.999448288449825500, - 1.999439244571521700, - 1.999430127179552500, 1.999420936274252800, 1.999411671855960900, - 1.999402333925017300, - 1.999392922481765500, 1.999383437526551300, 1.999373879059723500, - 1.999364247081633500, - 1.999354541592635500, 1.999344762593086500, 1.999334910083345700, - 1.999324984063775700, - 1.999314984534741100, 1.999304911496609700, 1.999294764949752100, - 1.999284544894541100, - 1.999274251331352400, 1.999263884260564600, 1.999253443682558900, - 1.999242929597719200, - 1.999232342006432000, 1.999221680909086400, 1.999210946306074500, - 1.999200138197791100, - 1.999189256584633600, 1.999178301467001900, 1.999167272845298900, - 1.999156170719930100, - 1.999144995091303600, 1.999133745959830600, 1.999122423325924200, - 1.999111027190001000, - 1.999099557552479900, 1.999088014413782800, 1.999076397774334000, - 1.999064707634560700, - 1.999052943994892300, 1.999041106855761900, 1.999029196217604100, - 1.999017212080857400, - 1.999005154445962200, 1.998993023313361700, 1.998980818683502100, - 1.998968540556831800, - 1.998956188933802800, 1.998943763814868800, 1.998931265200486900, - 1.998918693091116200, - 1.998906047487219600, 1.998893328389261400, 1.998880535797709700, - 1.998867669713034500, - 1.998854730135709400, 1.998841717066209400, 1.998828630505013400, - 1.998815470452602400, - 1.998802236909460500, 1.998788929876074100, 1.998775549352932400, - 1.998762095340527400, - 1.998748567839354000, 1.998734966849909000, 1.998721292372693100, - 1.998707544408208700, - 1.998693722956961500, 1.998679828019459300, 1.998665859596213500, - 1.998651817687737300, - 1.998637702294547000, 1.998623513417161700, 1.998609251056103100, - 1.998594915211895600, - 1.998580505885066100, 1.998566023076144600, 1.998551466785663400, - 1.998536837014157900, - 1.998522133762165900, 1.998507357030227900, 1.998492506818887200, - 1.998477583128690100, - 1.998462585960185000, 1.998447515313923400, 1.998432371190459500, - 1.998417153590349900, - 1.998401862514154200, 1.998386497962434800, 1.998371059935756300, - 1.998355548434686400, - 1.998339963459795400, 1.998324305011656600, 1.998308573090845200, - 1.998292767697940100, - 1.998276888833522300, 1.998260936498175400, 1.998244910692486000, - 1.998228811417043700, - 1.998212638672439900, 1.998196392459269400, 1.998180072778129600, - 1.998163679629620500, - 1.998147213014344900, 1.998130672932908000, 1.998114059385918400, - 1.998097372373986300, - 1.998080611897725700, 1.998063777957752600, 1.998046870554686100, - 1.998029889689147700, - 1.998012835361761900, 1.997995707573155600, 1.997978506323958600, - 1.997961231614803200, - 1.997943883446324800, 1.997926461819161000, 1.997908966733952500, - 1.997891398191342400, - 1.997873756191977000, 1.997856040736504500, 1.997838251825576400, - 1.997820389459846700, - 1.997802453639972300, 1.997784444366612600, 1.997766361640429800, - 1.997748205462088500, - 1.997729975832256600, 1.997711672751604200, 1.997693296220804000, - 1.997674846240532000, - 1.997656322811466500, 1.997637725934288300, 1.997619055609681600, - 1.997600311838332500, - 1.997581494620930300, 1.997562603958166600, 1.997543639850736200, - 1.997524602299336500, - 1.997505491304667000, 1.997486306867430900, 1.997467048988333000, - 1.997447717668082000, - 1.997428312907388200, 1.997408834706965000, 1.997389283067528800, - 1.997369657989798400, - 1.997349959474495200, 1.997330187522343700, 1.997310342134070800, - 1.997290423310406100, - 1.997270431052081900, 1.997250365359833200, 1.997230226234397900, - 1.997210013676516700, - 1.997189727686932400, 1.997169368266390900, 1.997148935415640600, - 1.997128429135433400, - 1.997107849426522600, 1.997087196289665000, 1.997066469725620200, - 1.997045669735150000, - 1.997024796319019300, 1.997003849477995600, 1.996982829212848900, - 1.996961735524351900, - 1.996940568413280600, 1.996919327880412900, 1.996898013926530000, - 1.996876626552415400, - 1.996855165758855600, 1.996833631546639300, 1.996812023916558800, - 1.996790342869408000, - 1.996768588405984300, 1.996746760527087700, 1.996724859233520500, - 1.996702884526087900, - 1.996680836405598100, 1.996658714872861800, 1.996636519928692000, - 1.996614251573904900, - 1.996591909809319400, 1.996569494635756600, 1.996547006054041100, - 1.996524444064999400, - 1.996501808669461000, 1.996479099868258400, 1.996456317662226300, - 1.996433462052202600, - 1.996410533039027400, 1.996387530623543900, 1.996364454806597500, - 1.996341305589037100, - 1.996318082971713500, 1.996294786955480800, 1.996271417541195300, - 1.996247974729716200, - 1.996224458521905600, 1.996200868918628100, 1.996177205920750800, - 1.996153469529144100, - 1.996129659744680300, 1.996105776568235100, 1.996081820000686500, - 1.996057790042915500, - 1.996033686695805300, 1.996009509960242400, 1.995985259837115500, - 1.995960936327316300, - 1.995936539431739000, 1.995912069151280800, 1.995887525486841300, - 1.995862908439323100, - 1.995838218009630800, 1.995813454198672700, 1.995788617007359100, - 1.995763706436603200, - 1.995738722487320600, 1.995713665160430600, 1.995688534456853800, - 1.995663330377514400, - 1.995638052923339300, 1.995612702095257400, 1.995587277894201400, - 1.995561780321105600, - 1.995536209376907600, 1.995510565062547800, 1.995484847378968600, - 1.995459056327116000, - 1.995433191907938000, 1.995407254122385700, 1.995381242971412600, - 1.995355158455975200, - 1.995329000577032800, 1.995302769335546500, 1.995276464732481200, - 1.995250086768804100, - 1.995223635445484900, 1.995197110763496000, 1.995170512723813100, - 1.995143841327413400, - 1.995117096575278200, 1.995090278468390600, 1.995063387007736600, - 1.995036422194304700, - 1.995009384029086800, 1.994982272513076600, 1.994955087647271000, - 1.994927829432669800, - 1.994900497870274900, 1.994873092961091200, 1.994845614706126400, - 1.994818063106391000, - 1.994790438162897600, 1.994762739876662100, 1.994734968248702800, - 1.994707123280041100, - 1.994679204971700100, 1.994651213324707000, 1.994623148340090700, - 1.994595010018883000, - 1.994566798362118300, 1.994538513370834200, 1.994510155046070700, - 1.994481723388870100, - 1.994453218400277900, 1.994424640081342100, 1.994395988433113700, - 1.994367263456646100, - 1.994338465152995000, 1.994309593523219600, 1.994280648568381500, - 1.994251630289544600, - 1.994222538687776100, 1.994193373764145500, 1.994164135519725000, - 1.994134823955589800, - 1.994105439072817700, 1.994075980872488800, 1.994046449355686200, - 1.994016844523496000, - 1.993987166377006600, 1.993957414917308700, 1.993927590145496900, - 1.993897692062667200, - 1.993867720669919400, 1.993837675968354700, 1.993807557959078600, - 1.993777366643197900, - 1.993747102021822900, 1.993716764096066200, 1.993686352867043200, - 1.993655868335872300, - 1.993625310503674100, 1.993594679371572200, 1.993563974940692800, - 1.993533197212164800, - 1.993502346187119700, 1.993471421866692200, 1.993440424252018900, - 1.993409353344239600, - 1.993378209144496700, 1.993346991653935300, 1.993315700873703200, - 1.993284336804950900, - 1.993252899448831400, 1.993221388806500900, 1.993189804879117500, - 1.993158147667842800, - 1.993126417173840500, 1.993094613398277400, 1.993062736342323000, - 1.993030786007148800, - 1.992998762393930000, 1.992966665503844000, 1.992934495338070800, - 1.992902251897793000, - 1.992869935184196300, 1.992837545198469000, 1.992805081941801700, - 1.992772545415388200, - 1.992739935620424700, 1.992707252558110200, 1.992674496229646500, - 1.992641666636237700, - 1.992608763779091000, 1.992575787659416100, 1.992542738278425300, - 1.992509615637334100, - 1.992476419737359900, 1.992443150579723500, 1.992409808165648100, - 1.992376392496359300, - 1.992342903573086000, 1.992309341397059600, 1.992275705969513800, - 1.992241997291685400, - 1.992208215364813700, 1.992174360190140900, 1.992140431768911500, - 1.992106430102373400, - 1.992072355191776300, 1.992038207038373300, 1.992003985643419700, - 1.991969691008174100, - 1.991935323133897000, 1.991900882021852200, 1.991866367673306200, - 1.991831780089527500, - 1.991797119271788300, 1.991762385221362600, 1.991727577939527600, - 1.991692697427563300, - 1.991657743686751700, 1.991622716718378400, 1.991587616523731000, - 1.991552443104099800, - 1.991517196460778500, 1.991481876595062800, 1.991446483508251500, - 1.991411017201645500, - 1.991375477676549100, 1.991339864934268800, 1.991304178976114100, - 1.991268419803397200, - 1.991232587417432600, 1.991196681819537900, 1.991160703011033200, - 1.991124650993241400, - 1.991088525767488200, 1.991052327335101300, 1.991016055697411900, - 1.990979710855753900, - 1.990943292811463000, 1.990906801565878600, 1.990870237120342400, - 1.990833599476198800, - 1.990796888634794400, 1.990760104597479400, 1.990723247365606200, - 1.990686316940529800, - 1.990649313323608100, 1.990612236516201300, 1.990575086519673200, - 1.990537863335389400, - 1.990500566964718400, 1.990463197409031700, 1.990425754669703100, - 1.990388238748109100, - 1.990350649645629600, 1.990312987363646000, 1.990275251903543600, - 1.990237443266709400, - 1.990199561454533600, 1.990161606468409300, 1.990123578309731700, - 1.990085476979899000, - 1.990047302480312300, 1.990009054812374800, 1.989970733977493000, - 1.989932339977075900, - 1.989893872812535000, 1.989855332485284800, 1.989816718996742200, - 1.989778032348326700, - 1.989739272541461100, 1.989700439577570400, 1.989661533458082100, - 1.989622554184426800, - 1.989583501758037700, 1.989544376180350600, 1.989505177452804100, - 1.989465905576839600, - 1.989426560553900500, 1.989387142385433900, 1.989347651072888900, - 1.989308086617717500, - 1.989268449021374300, 1.989228738285316900, 1.989188954411005100, - 1.989149097399901500, - 1.989109167253472000, 1.989069163973184300, 1.989029087560509700, - 1.988988938016921000, - 1.988948715343894900, 1.988908419542910100, 1.988868050615448100, - 1.988827608562993200, - 1.988787093387032600, 1.988746505089055600, 1.988705843670554500, - 1.988665109133024500, - 1.988624301477963200, 1.988583420706871100, 1.988542466821251000, - 1.988501439822608900, - 1.988460339712453200, 1.988419166492295000, 1.988377920163648000, - 1.988336600728029000, - 1.988295208186956700, 1.988253742541953800, 1.988212203794544000, - 1.988170591946255100, - 1.988128906998616800, 1.988087148953161700, 1.988045317811425700, - 1.988003413574946000, - 1.987961436245263800, 1.987919385823922400, 1.987877262312467600, - 1.987835065712448600, - 1.987792796025416500, 1.987750453252925500, 1.987708037396532800, - 1.987665548457797400, - 1.987622986438281700, 1.987580351339550700, 1.987537643163171700, - 1.987494861910715100, - 1.987452007583754100, 1.987409080183863800, 1.987366079712622900, - 1.987323006171612500, - 1.987279859562415900, 1.987236639886619700, 1.987193347145813000, - 1.987149981341587400, - 1.987106542475537400, 1.987063030549260300, 1.987019445564355700, - 1.986975787522426100, - 1.986932056425076800, 1.986888252273915500, 1.986844375070552900, - 1.986800424816602200, - 1.986756401513679400, 1.986712305163403000, 1.986668135767394300, - 1.986623893327277500, - 1.986579577844678900, 1.986535189321228000, 1.986490727758556800, - 1.986446193158300400, - 1.986401585522095600, 1.986356904851583000, 1.986312151148405200, - 1.986267324414207500, - 1.986222424650638400, 1.986177451859348200, 1.986132406041990900, - 1.986087287200222700, - 1.986042095335702300, 1.985996830450091200, 1.985951492545054100, - 1.985906081622257300, - 1.985860597683371000, 1.985815040730067200, 1.985769410764020900, - 1.985723707786909900, - 1.985677931800414500, 1.985632082806217900, 1.985586160806005700, - 1.985540165801466200, - 1.985494097794290800, 1.985447956786173100, 1.985401742778809500, - 1.985355455773899500, - 1.985309095773144500, 1.985262662778249300, 1.985216156790921000, - 1.985169577812869500, - 1.985122925845807400, 1.985076200891450000, 1.985029402951515200, - 1.984982532027723700, - 1.984935588121798700, 1.984888571235466200, 1.984841481370454900, - 1.984794318528496200, - 1.984747082711324100, 1.984699773920675300, 1.984652392158289500, - 1.984604937425908300, - 1.984557409725276700, 1.984509809058142300, 1.984462135426255000, - 1.984414388831367900, - 1.984366569275236400, 1.984318676759618400, 1.984270711286275200, - 1.984222672856969800, - 1.984174561473469200, 1.984126377137541700, 1.984078119850959200, - 1.984029789615495900, - 1.983981386432928800, 1.983932910305037400, 1.983884361233604100, - 1.983835739220414000, - 1.983787044267254700, 1.983738276375916800, 1.983689435548192900, - 1.983640521785879200, - 1.983591535090773800, 1.983542475464678000, 1.983493342909395500, - 1.983444137426732600, - 1.983394859018498900, 1.983345507686505900, 1.983296083432567900, - 1.983246586258502700, - 1.983197016166129400, 1.983147373157271300, 1.983097657233753100, - 1.983047868397403100, - 1.982998006650051400, 1.982948071993531700, 1.982898064429679900, - 1.982847983960334600, - 1.982797830587336800, 1.982747604312531200, 1.982697305137763700, - 1.982646933064884200, - 1.982596488095744300, 1.982545970232199000, 1.982495379476105800, - 1.982444715829324600, - 1.982393979293718200, 1.982343169871152000, 1.982292287563494300, - 1.982241332372615600, - 1.982190304300389400, 1.982139203348692200, 1.982088029519402300, - 1.982036782814401900, - 1.981985463235574700, 1.981934070784807400, 1.981882605463990200, - 1.981831067275015000, - 1.981779456219776600, 1.981727772300172500, 1.981676015518103500, - 1.981624185875472000, - 1.981572283374183800, 1.981520308016147200, 1.981468259803273300, - 1.981416138737475800, - 1.981363944820670800, 1.981311678054777500, 1.981259338441717400, - 1.981206925983415300, - 1.981154440681797800, 1.981101882538794900, 1.981049251556338900, - 1.980996547736364900, - 1.980943771080810700, 1.980890921591616600, 1.980837999270726100, - 1.980785004120084700, - 1.980731936141640900, 1.980678795337345900, 1.980625581709153600, - 1.980572295259020600, - 1.980518935988905700, 1.980465503900771000, 1.980411998996581200, - 1.980358421278303200, - 1.980304770747907300, 1.980251047407365600, 1.980197251258653900, - 1.980143382303749500, - 1.980089440544633600, 1.980035425983289300, 1.979981338621702200, - 1.979927178461861500, - 1.979872945505758000, 1.979818639755386100, 1.979764261212742400, - 1.979709809879825800, - 1.979655285758638900, 1.979600688851186100, 1.979546019159474900, - 1.979491276685515300, - 1.979436461431320000, 1.979381573398904400, 1.979326612590286400, - 1.979271579007487100, - 1.979216472652529900, 1.979161293527440500, 1.979106041634248100, - 1.979050716974983800, - 1.978995319551682100, 1.978939849366379700, 1.978884306421115900, - 1.978828690717932900, - 1.978773002258875600, 1.978717241045991700, 1.978661407081331100, - 1.978605500366946700, - 1.978549520904894000, 1.978493468697231300, 1.978437343746019600, - 1.978381146053322000, - 1.978324875621205300, 1.978268532451738200, 1.978212116546992100, - 1.978155627909041300, - 1.978099066539962900, 1.978042432441836400, 1.977985725616743900, - 1.977928946066770600, - 1.977872093794004200, 1.977815168800534500, 1.977758171088455100, - 1.977701100659861300, - 1.977643957516851400, 1.977586741661526500, 1.977529453095990200, - 1.977472091822348700, - 1.977414657842711200, 1.977357151159189400, 1.977299571773897700, - 1.977241919688953000, - 1.977184194906475000, 1.977126397428586000, 1.977068527257411300, - 1.977010584395078300, - 1.976952568843717700, 1.976894480605462500, 1.976836319682448300, - 1.976778086076813600, - 1.976719779790699500, 1.976661400826249500, 1.976602949185610500, - 1.976544424870931400, - 1.976485827884363800, 1.976427158228062100, 1.976368415904183900, - 1.976309600914888400, - 1.976250713262338600, 1.976191752948699200, 1.976132719976138000, - 1.976073614346825800, - 1.976014436062935700, 1.975955185126643300, 1.975895861540127200, - 1.975836465305568400, - 1.975776996425151000, 1.975717454901061400, 1.975657840735488800, - 1.975598153930624900, - 1.975538394488664200, 1.975478562411804100, 1.975418657702244300, - 1.975358680362187400, - 1.975298630393838500, 1.975238507799405500, 1.975178312581099100, - 1.975118044741132300, - 1.975057704281721000, 1.974997291205083700, 1.974936805513442000, - 1.974876247209019100, - 1.974815616294042200, 1.974754912770740200, 1.974694136641345300, - 1.974633287908091500, - 1.974572366573216400, 1.974511372638960000, 1.974450306107564900, - 1.974389166981275900, - 1.974327955262341400, 1.974266670953011400, 1.974205314055540000, - 1.974143884572182400, - 1.974082382505197400, 1.974020807856846400, 1.973959160629393100, - 1.973897440825104200, - 1.973835648446248900, 1.973773783495099500, 1.973711845973930000, - 1.973649835885018100, - 1.973587753230643400, 1.973525598013088800, 1.973463370234639600, - 1.973401069897583200, - 1.973338697004211100, 1.973276251556815600, 1.973213733557693400, - 1.973151143009142800, - 1.973088479913465100, 1.973025744272964200, 1.972962936089946800, - 1.972900055366722000, - 1.972837102105601900, 1.972774076308901200, 1.972710977978936900, - 1.972647807118029300, - 1.972584563728500700, 1.972521247812676600, 1.972457859372884500, - 1.972394398411455800, - 1.972330864930723200, 1.972267258933022600, 1.972203580420693000, - 1.972139829396075200, - 1.972076005861513700, 1.972012109819354600, 1.971948141271947500, - 1.971884100221644300, - 1.971819986670799500, 1.971755800621770400, 1.971691542076916800, - 1.971627211038601500, - 1.971562807509189800, 1.971498331491049700, 1.971433782986551400, - 1.971369161998068400, - 1.971304468527976800, 1.971239702578655000, 1.971174864152484400, - 1.971109953251848600, - 1.971044969879134600, 1.970979914036731500, 1.970914785727030800, - 1.970849584952427900, - 1.970784311715319400, 1.970718966018105500, 1.970653547863188600, - 1.970588057252973900, - 1.970522494189869800, 1.970456858676286300, 1.970391150714636800, - 1.970325370307337100, - 1.970259517456806100, 1.970193592165464700, 1.970127594435737000, - 1.970061524270049400, - 1.969995381670831100, 1.969929166640514100, 1.969862879181532700, - 1.969796519296324300, - 1.969730086987328900, 1.969663582256988600, 1.969597005107748900, - 1.969530355542057800, - 1.969463633562365400, 1.969396839171125200, 1.969329972370792700, - 1.969263033163826800, - 1.969196021552688500, 1.969128937539841500, 1.969061781127752400, - 1.968994552318890300, - 1.968927251115727200, 1.968859877520737300, 1.968792431536398000, - 1.968724913165188900, - 1.968657322409592500, 1.968589659272094000, 1.968521923755181000, - 1.968454115861344000, - 1.968386235593076300, 1.968318282952873600, 1.968250257943234200, - 1.968182160566659000, - 1.968113990825652200, 1.968045748722719900, 1.967977434260371300, - 1.967909047441118100, - 1.967840588267474500, 1.967772056741957900, 1.967703452867087800, - 1.967634776645386600, - 1.967566028079379200, 1.967497207171593500, 1.967428313924559600, - 1.967359348340810700, - 1.967290310422882700, 1.967221200173313400, 1.967152017594644200, - 1.967082762689418500, - 1.967013435460182700, 1.966944035909485600, 1.966874564039879300, - 1.966805019853917500, - 1.966735403354157500, 1.966665714543159000, 1.966595953423483800, - 1.966526119997697100, - 1.966456214268366600, 1.966386236238062200, 1.966316185909357200, - 1.966246063284826700, - 1.966175868367049400, 1.966105601158605600, 1.966035261662079300, - 1.965964849880056600, - 1.965894365815126000, 1.965823809469879400, 1.965753180846910900, - 1.965682479948817100, - 1.965611706778197700, 1.965540861337654600, 1.965469943629792700, - 1.965398953657219600, - 1.965327891422544900, 1.965256756928382100, 1.965185550177345900, - 1.965114271172054800, - 1.965042919915129400, 1.964971496409193100, 1.964900000656872000, - 1.964828432660794500, - 1.964756792423592200, 1.964685079947899200, 1.964613295236352000, - 1.964541438291590000, - 1.964469509116255000, 1.964397507712991800, 1.964325434084447600, - 1.964253288233272400, - 1.964181070162119000, 1.964108779873642100, 1.964036417370500300, - 1.963963982655353400, - 1.963891475730865400, 1.963818896599701400, 1.963746245264530700, - 1.963673521728023900, - 1.963600725992855200, 1.963527858061700600, 1.963454917937239800, - 1.963381905622154400, - 1.963308821119128700, 1.963235664430850200, 1.963162435560008100, - 1.963089134509295300, - 1.963015761281406800, 1.962942315879040000, 1.962868798304895400, - 1.962795208561676200, - 1.962721546652088200, 1.962647812578839400, 1.962574006344640900, - 1.962500127952206300, - 1.962426177404252200, 1.962352154703497200, 1.962278059852663000, - 1.962203892854473800, - 1.962129653711656800, 1.962055342426941400, 1.961980959003059500, - 1.961906503442746300, - 1.961831975748739200, 1.961757375923778700, 1.961682703970607100, - 1.961607959891970200, - 1.961533143690616000, 1.961458255369295400, 1.961383294930761700, - 1.961308262377770900, - 1.961233157713082200, 1.961157980939456400, 1.961082732059657800, - 1.961007411076453000, - 1.960932017992611500, 1.960856552810905200, 1.960781015534108800, - 1.960705406164999300, - 1.960629724706357100, 1.960553971160964500, 1.960478145531606700, - 1.960402247821071900, - 1.960326278032150200, 1.960250236167635100, 1.960174122230322400, - 1.960097936223010400, - 1.960021678148500500, 1.959945348009596500, 1.959868945809104500, - 1.959792471549834000, - 1.959715925234596600, 1.959639306866206600, 1.959562616447480900, - 1.959485853981239600, - 1.959409019470304700, 1.959332112917501400, 1.959255134325657000, - 1.959178083697602300, - 1.959100961036169800, 1.959023766344195200, 1.958946499624516700, - 1.958869160879975500, - 1.958791750113414700, 1.958714267327680500, 1.958636712525621900, - 1.958559085710090500, - 1.958481386883940100, 1.958403616050027600, 1.958325773211212300, - 1.958247858370356400, - 1.958169871530324600, 1.958091812693984400, 1.958013681864205500, - 1.957935479043860600, - 1.957857204235825100, 1.957778857442976900, 1.957700438668196700, - 1.957621947914367500, - 1.957543385184375300, 1.957464750481108700, 1.957386043807458800, - 1.957307265166319500, - 1.957228414560587200, 1.957149491993160900, 1.957070497466942400, - 1.956991430984836400, - 1.956912292549749500, 1.956833082164591600, 1.956753799832275300, - 1.956674445555715000, - 1.956595019337829000, 1.956515521181537000, 1.956435951089762200, - 1.956356309065430100, - 1.956276595111468900, 1.956196809230809500, 1.956116951426385600, - 1.956037021701132900, - 1.955957020057990500, 1.955876946499899700, 1.955796801029804800, - 1.955716583650652000, - 1.955636294365391300, 1.955555933176974300, 1.955475500088355900, - 1.955394995102493100, - 1.955314418222346100, 1.955233769450877200, 1.955153048791052000, - 1.955072256245838000, - 1.954991391818206000, 1.954910455511129000, 1.954829447327582900, - 1.954748367270545900, - 1.954667215342999600, 1.954585991547927100, 1.954504695888315000, - 1.954423328367152600, - 1.954341888987431100, 1.954260377752145000, 1.954178794664291200, - 1.954097139726869600, - 1.954015412942881900, 1.953933614315333200, 1.953851743847231100, - 1.953769801541585400, - 1.953687787401409400, 1.953605701429718100, 1.953523543629529700, - 1.953441314003864900, - 1.953359012555747200, 1.953276639288202400, 1.953194194204259200, - 1.953111677306948800, - 1.953029088599305100, 1.952946428084364900, 1.952863695765167100, - 1.952780891644753500, - 1.952698015726169100, 1.952615068012460300, 1.952532048506677300, - 1.952448957211872200, - 1.952365794131100300, 1.952282559267419100, 1.952199252623889200, - 1.952115874203572900, - 1.952032424009536600, 1.951948902044847900, 1.951865308312577900, - 1.951781642815800100, - 1.951697905557590700, 1.951614096541028500, 1.951530215769194700, - 1.951446263245173500, - 1.951362238972051500, 1.951278142952918200, 1.951193975190865600, - 1.951109735688987900, - 1.951025424450382900, 1.950941041478150100, 1.950856586775392200, - 1.950772060345214300, - 1.950687462190724200, 1.950602792315032200, 1.950518050721251600, - 1.950433237412498000, - 1.950348352391889600, 1.950263395662547700, 1.950178367227595900, - 1.950093267090159800, - 1.950008095253369200, 1.949922851720355100, 1.949837536494251700, - 1.949752149578196000, - 1.949666690975327100, 1.949581160688787400, 1.949495558721721500, - 1.949409885077276500, - 1.949324139758602700, 1.949238322768852800, 1.949152434111181700, - 1.949066473788747300, - 1.948980441804710300, 1.948894338162233900, 1.948808162864483600, - 1.948721915914628100, - 1.948635597315838200, 1.948549207071288000, 1.948462745184153400, - 1.948376211657613500, - 1.948289606494849800, 1.948202929699046800, 1.948116181273391100, - 1.948029361221072400, - 1.947942469545282500, 1.947855506249216700, 1.947768471336071700, - 1.947681364809048100, - 1.947594186671348000, 1.947506936926177300, 1.947419615576743600, - 1.947332222626257500, - 1.947244758077932200, 1.947157221934983500, 1.947069614200629900, - 1.946981934878092300, - 1.946894183970594900, 1.946806361481363500, 1.946718467413627300, - 1.946630501770618000, - 1.946542464555569800, 1.946454355771719300, 1.946366175422306500, - 1.946277923510573200, - 1.946189600039764300, 1.946101205013127000, 1.946012738433911600, - 1.945924200305370700, - 1.945835590630759400, 1.945746909413335900, 1.945658156656360700, - 1.945569332363096700, - 1.945480436536810100, 1.945391469180769200, 1.945302430298244900, - 1.945213319892511200, - 1.945124137966844200, 1.945034884524523100, 1.944945559568829200, - 1.944856163103046800, - 1.944766695130463000, 1.944677155654366900, 1.944587544678050900, - 1.944497862204809900, - 1.944408108237940700, 1.944318282780743900, 1.944228385836521700, - 1.944138417408579400, - 1.944048377500225100, 1.943958266114769200, 1.943868083255524800, - 1.943777828925807600, - 1.943687503128936200, 1.943597105868231500, 1.943506637147017300, - 1.943416096968619400, - 1.943325485336367300, 1.943234802253592400, 1.943144047723628400, - 1.943053221749812400, - 1.942962324335484100, 1.942871355483985200, 1.942780315198660200, - 1.942689203482856900, - 1.942598020339924700, 1.942506765773216500, 1.942415439786087300, - 1.942324042381895000, - 1.942232573564000000, 1.942141033335765400, 1.942049421700556600, - 1.941957738661741900, - 1.941865984222692900, 1.941774158386782200, 1.941682261157386700, - 1.941590292537884700, - 1.941498252531658200, 1.941406141142090600, 1.941313958372568900, - 1.941221704226482500, - 1.941129378707223000, 1.941036981818185400, 1.940944513562766300, - 1.940851973944365900, - 1.940759362966386600, 1.940666680632233200, 1.940573926945313700, - 1.940481101909038200, - 1.940388205526819600, 1.940295237802073500, 1.940202198738217900, - 1.940109088338673600, - 1.940015906606864300, 1.939922653546215500, 1.939829329160156500, - 1.939735933452118000, - 1.939642466425534300, 1.939548928083841800, 1.939455318430479500, - 1.939361637468889100, - 1.939267885202515400, 1.939174061634805000, 1.939080166769207700, - 1.938986200609175600, - 1.938892163158163700, 1.938798054419629500, 1.938703874397032800, - 1.938609623093837000, - 1.938515300513506700, 1.938420906659510600, 1.938326441535318500, - 1.938231905144404400, - 1.938137297490243500, 1.938042618576314400, 1.937947868406098500, - 1.937853046983079300, - 1.937758154310742900, 1.937663190392578500, 1.937568155232077600, - 1.937473048832734500, - 1.937377871198045600, 1.937282622331510500, 1.937187302236631500, - 1.937091910916912900, - 1.936996448375861900, 1.936900914616988900, 1.936805309643805800, - 1.936709633459828200, - 1.936613886068573500, 1.936518067473562300, 1.936422177678317300, - 1.936326216686364400, - 1.936230184501231500, 1.936134081126449800, 1.936037906565552400, - 1.935941660822075600, - 1.935845343899558000, 1.935748955801540800, 1.935652496531568000, - 1.935555966093186300, - 1.935459364489944500, 1.935362691725394500, 1.935265947803090900, - 1.935169132726590500, - 1.935072246499453000, 1.934975289125240500, 1.934878260607517900, - 1.934781160949852600, - 1.934683990155814800, 1.934586748228977100, 1.934489435172914900, - 1.934392050991206300, - 1.934294595687431300, 1.934197069265173500, 1.934099471728018700, - 1.934001803079554700, - 1.933904063323373300, 1.933806252463067500, 1.933708370502233800, - 1.933610417444471000, - 1.933512393293380600, 1.933414298052566600, 1.933316131725635800, - 1.933217894316197300, - 1.933119585827862900, 1.933021206264247600, 1.932922755628968100, - 1.932824233925644300, - 1.932725641157898600, 1.932626977329356100, 1.932528242443643900, - 1.932429436504392800, - 1.932330559515235100, 1.932231611479806800, 1.932132592401745400, - 1.932033502284691700, - 1.931934341132289100, 1.931835108948183300, 1.931735805736022800, - 1.931636431499459000, - 1.931536986242145200, 1.931437469967737900, 1.931337882679895900, - 1.931238224382281000, - 1.931138495078557300, 1.931038694772391200, 1.930938823467452500, - 1.930838881167413100, - 1.930738867875947400, 1.930638783596732700, 1.930538628333448900, - 1.930438402089778200, - 1.930338104869405900, 1.930237736676019500, 1.930137297513309300, - 1.930036787384968200, - 1.929936206294691400, 1.929835554246177400, 1.929734831243126600, - 1.929634037289242400, - 1.929533172388230700, 1.929432236543799900, 1.929331229759661200, - 1.929230152039528500, - 1.929129003387117800, 1.929027783806148300, 1.928926493300341400, - 1.928825131873421500, - 1.928723699529115000, 1.928622196271151800, 1.928520622103263400, - 1.928418977029184600, - 1.928317261052652700, 1.928215474177407100, 1.928113616407190600, - 1.928011687745748300, - 1.927909688196827400, 1.927807617764178300, 1.927705476451554000, - 1.927603264262709900, - 1.927500981201404100, 1.927398627271397000, 1.927296202476451900, - 1.927193706820335100, - 1.927091140306814500, 1.926988502939661400, 1.926885794722649600, - 1.926783015659555300, - 1.926680165754157500, 1.926577245010237400, 1.926474253431579500, - 1.926371191021970100, - 1.926268057785198700, 1.926164853725057300, 1.926061578845340600, - 1.925958233149845000, - 1.925854816642371000, 1.925751329326720600, 1.925647771206698600, - 1.925544142286112800, - 1.925440442568773000, 1.925336672058492300, 1.925232830759086000, - 1.925128918674371900, - 1.925024935808170600, 1.924920882164305300, 1.924816757746601800, - 1.924712562558888100, - 1.924608296604995800, 1.924503959888757900, 1.924399552414010700, - 1.924295074184593000, - 1.924190525204346300, 1.924085905477114400, 1.923981215006744100, - 1.923876453797084300, - 1.923771621851986700, 1.923666719175306100, 1.923561745770898900, - 1.923456701642625200, - 1.923351586794346900, 1.923246401229928600, 1.923141144953238300, - 1.923035817968145300, - 1.922930420278522500, 1.922824951888245000, 1.922719412801190600, - 1.922613803021239600, - 1.922508122552275100, 1.922402371398182600, 1.922296549562850100, - 1.922190657050168800, - 1.922084693864031700, 1.921978660008334600, 1.921872555486976700, - 1.921766380303858500, - 1.921660134462884100, 1.921553817967959900, 1.921447430822994500, - 1.921340973031900000, - 1.921234444598590100, 1.921127845526981600, 1.921021175820994100, - 1.920914435484549100, - 1.920807624521571700, 1.920700742935988600, 1.920593790731729600, - 1.920486767912727300, - 1.920379674482916500, 1.920272510446234400, 1.920165275806621400, - 1.920057970568020100, - 1.919950594734376000, 1.919843148309637000, 1.919735631297753400, - 1.919628043702678300, - 1.919520385528367300, 1.919412656778779000, 1.919304857457874200, - 1.919196987569616200, - 1.919089047117971100, 1.918981036106907700, 1.918872954540397300, - 1.918764802422413500, - 1.918656579756932800, 1.918548286547934400, 1.918439922799399800, - 1.918331488515313300, - 1.918222983699661600, 1.918114408356434300, 1.918005762489623400, - 1.917897046103223200, - 1.917788259201231200, 1.917679401787647100, 1.917570473866473200, - 1.917461475441714500, - 1.917352406517378600, 1.917243267097475700, 1.917134057186018300, - 1.917024776787022100, - 1.916915425904504700, 1.916806004542486800, 1.916696512704991500, - 1.916586950396044400, - 1.916477317619674100, 1.916367614379911100, 1.916257840680788900, - 1.916147996526343700, - 1.916038081920614400, 1.915928096867641800, 1.915818041371470000, - 1.915707915436145200, - 1.915597719065716700, 1.915487452264236000, 1.915377115035757200, - 1.915266707384337200, - 1.915156229314035200, 1.915045680828913400, 1.914935061933036300, - 1.914824372630470800, - 1.914713612925287100, 1.914602782821557000, 1.914491882323355700, - 1.914380911434760500, - 1.914269870159851700, 1.914158758502712000, 1.914047576467426500, - 1.913936324058083100, - 1.913825001278772100, 1.913713608133586600, 1.913602144626622500, - 1.913490610761977600, - 1.913379006543752800, 1.913267331976051400, 1.913155587062979500, - 1.913043771808645700, - 1.912931886217160900, 1.912819930292639000, 1.912707904039196300, - 1.912595807460951500, - 1.912483640562026200, 1.912371403346544400, 1.912259095818632700, - 1.912146717982420500, - 1.912034269842039600, 1.911921751401624200, 1.911809162665311500, - 1.911696503637241100, - 1.911583774321554700, 1.911470974722397500, 1.911358104843916500, - 1.911245164690262000, - 1.911132154265586100, 1.911019073574044200, 1.910905922619793800, - 1.910792701406995000, - 1.910679409939810600, 1.910566048222406300, 1.910452616258949900, - 1.910339114053611900, - 1.910225541610565800, 1.910111898933986900, 1.909998186028053700, - 1.909884402896947100, - 1.909770549544850500, 1.909656625975950200, 1.909542632194434700, - 1.909428568204495100, - 1.909314434010325400, 1.909200229616121700, 1.909085955026083200, - 1.908971610244411600, - 1.908857195275310800, 1.908742710122987700, 1.908628154791651300, - 1.908513529285513500, - 1.908398833608789100, 1.908284067765694900, 1.908169231760450400, - 1.908054325597278200, - 1.907939349280402400, 1.907824302814050900, 1.907709186202453600, - 1.907593999449842800, - 1.907478742560453600, 1.907363415538523700, 1.907248018388293400, - 1.907132551114005600, - 1.907017013719905600, 1.906901406210241200, 1.906785728589263300, - 1.906669980861224900, - 1.906554163030381500, 1.906438275100991600, 1.906322317077316300, - 1.906206288963618700, - 1.906090190764164700, 1.905974022483223300, 1.905857784125065500, - 1.905741475693964800, - 1.905625097194197900, 1.905508648630043700, 1.905392130005783400, - 1.905275541325701400, - 1.905158882594083900, 1.905042153815220700, 1.904925354993402900, - 1.904808486132925300, - 1.904691547238084800, 1.904574538313180700, 1.904457459362515200, - 1.904340310390393100, - 1.904223091401121600, 1.904105802399010300, 1.903988443388371600, - 1.903871014373520700, - 1.903753515358774800, 1.903635946348454500, 1.903518307346881800, - 1.903400598358382600, - 1.903282819387284200, 1.903164970437917400, 1.903047051514615000, - 1.902929062621712600, - 1.902811003763547900, 1.902692874944462300, 1.902574676168798700, - 1.902456407440902700, - 1.902338068765123200, 1.902219660145810800, 1.902101181587319000, - 1.901982633094004200, - 1.901864014670225000, 1.901745326320342500, 1.901626568048721000, - 1.901507739859726200, - 1.901388841757727600, 1.901269873747096600, 1.901150835832207100, - 1.901031728017436300, - 1.900912550307162700, 1.900793302705768900, 1.900673985217638900, - 1.900554597847159400, - 1.900435140598720500, 1.900315613476714100, 1.900196016485534700, - 1.900076349629579600, - 1.899956612913248800, 1.899836806340944300, 1.899716929917071500, - 1.899596983646037600, - 1.899476967532252900, 1.899356881580129800, 1.899236725794083600, - 1.899116500178532200, - 1.898996204737895900, 1.898875839476597700, 1.898755404399062900, - 1.898634899509719500, - 1.898514324812998300, 1.898393680313332600, 1.898272966015157800, - 1.898152181922912600, - 1.898031328041037700, 1.897910404373976500, 1.897789410926175000, - 1.897668347702081900, - 1.897547214706148300, 1.897426011942827900, 1.897304739416577200, - 1.897183397131854600, - 1.897061985093121800, 1.896940503304842800, 1.896818951771484000, - 1.896697330497514800, - 1.896575639487406300, 1.896453878745633100, 1.896332048276672100, - 1.896210148085002400, - 1.896088178175106200, 1.895966138551467700, 1.895844029218574100, - 1.895721850180915000, - 1.895599601442982600, 1.895477283009271400, 1.895354894884279100, - 1.895232437072505300, - 1.895109909578452500, 1.894987312406625700, 1.894864645561532100, - 1.894741909047682500, - 1.894619102869589100, 1.894496227031767100, 1.894373281538734400, - 1.894250266395011600, - 1.894127181605121100, 1.894004027173588700, 1.893880803104942600, - 1.893757509403713100, - 1.893634146074433500, 1.893510713121639300, 1.893387210549869000, - 1.893263638363663400, - 1.893139996567565900, 1.893016285166122500, 1.892892504163881600, - 1.892768653565394300, - 1.892644733375214300, 1.892520743597897700, 1.892396684238003300, - 1.892272555300092300, - 1.892148356788728700, 1.892024088708479200, 1.891899751063912200, - 1.891775343859599400, - 1.891650867100115300, 1.891526320790036100, 1.891401704933941100, - 1.891277019536412400, - 1.891152264602033800, 1.891027440135392600, 1.890902546141078000, - 1.890777582623682300, - 1.890652549587799700, 1.890527447038027300, 1.890402274978965100, - 1.890277033415215200, - 1.890151722351382200, 1.890026341792073500, 1.889900891741899100, - 1.889775372205471300, - 1.889649783187405100, 1.889524124692318200, 1.889398396724830500, - 1.889272599289564900, - 1.889146732391146400, 1.889020796034202700, 1.888894790223364600, - 1.888768714963264400, - 1.888642570258537700, 1.888516356113822700, 1.888390072533759700, - 1.888263719522991900, - 1.888137297086165000, 1.888010805227927000, 1.887884243952928600, - 1.887757613265823400, - 1.887630913171267000, 1.887504143673917700, 1.887377304778437000, - 1.887250396489487800, - 1.887123418811736500, 1.886996371749851700, 1.886869255308504200, - 1.886742069492368000, - 1.886614814306119400, 1.886487489754437300, 1.886360095842002600, - 1.886232632573499700, - 1.886105099953614900, 1.885977497987037000, 1.885849826678457800, - 1.885722086032571200, - 1.885594276054074300, 1.885466396747665700, 1.885338448118047700, - 1.885210430169924200, - 1.885082342908002400, 1.884954186336991400, 1.884825960461603100, - 1.884697665286552400, - 1.884569300816556000, 1.884440867056333700, 1.884312364010607600, - 1.884183791684102400, - 1.884055150081545200, 1.883926439207665800, 1.883797659067196800, - 1.883668809664872600, - 1.883539891005431100, 1.883410903093611900, 1.883281845934157800, - 1.883152719531813800, - 1.883023523891327300, 1.882894259017448900, 1.882764924914930700, - 1.882635521588528400, - 1.882506049042999700, 1.882376507283104900, 1.882246896313606800, - 1.882117216139270700, - 1.881987466764865100, 1.881857648195159900, 1.881727760434928500, - 1.881597803488946500, - 1.881467777361992100, 1.881337682058845700, 1.881207517584290600, - 1.881077283943112900, - 1.880946981140100500, 1.880816609180044700, 1.880686168067738500, - 1.880555657807977800, - 1.880425078405561600, 1.880294429865290600, 1.880163712191968300, - 1.880032925390400900, - 1.879902069465397200, 1.879771144421768200, 1.879640150264327600, - 1.879509086997891900, - 1.879377954627279700, 1.879246753157312700, 1.879115482592814500, - 1.878984142938611600, - 1.878852734199532900, 1.878721256380410100, 1.878589709486077300, - 1.878458093521370800, - 1.878326408491130200, 1.878194654400196600, 1.878062831253414900, - 1.877930939055631100, - 1.877798977811695200, 1.877666947526458700, 1.877534848204775800, - 1.877402679851504000, - 1.877270442471502100, 1.877138136069632400, 1.877005760650759500, - 1.876873316219750200, - 1.876740802781474500, 1.876608220340804100, 1.876475568902614000, - 1.876342848471781200, - 1.876210059053185600, 1.876077200651709500, 1.875944273272237800, - 1.875811276919657500, - 1.875678211598858800, 1.875545077314734000, 1.875411874072178100, - 1.875278601876088700, - 1.875145260731365700, 1.875011850642911600, 1.874878371615631900, - 1.874744823654434000, - 1.874611206764227800, 1.874477520949926500, 1.874343766216444800, - 1.874209942568701100, - 1.874076050011615400, 1.873942088550110400, 1.873808058189111700, - 1.873673958933546900, - 1.873539790788347100, 1.873405553758444600, 1.873271247848775400, - 1.873136873064277000, - 1.873002429409890600, 1.872867916890558900, 1.872733335511227700, - 1.872598685276845000, - 1.872463966192361900, 1.872329178262731200, 1.872194321492908700, - 1.872059395887852900, - 1.871924401452524700, 1.871789338191887100, 1.871654206110906500, - 1.871519005214550700, - 1.871383735507791100, 1.871248396995601300, 1.871112989682956800, - 1.870977513574836500, - 1.870841968676221400, 1.870706354992095000, 1.870570672527443600, - 1.870434921287255700, - 1.870299101276522400, 1.870163212500237900, 1.870027254963397800, - 1.869891228671001200, - 1.869755133628049600, 1.869618969839546500, 1.869482737310498100, - 1.869346436045913800, - 1.869210066050804600, 1.869073627330184700, 1.868937119889070300, - 1.868800543732480600, - 1.868663898865437200, 1.868527185292963700, 1.868390403020087100, - 1.868253552051836200, - 1.868116632393243000, 1.867979644049341200, 1.867842587025167800, - 1.867705461325761800, - 1.867568266956164800, 1.867431003921421500, 1.867293672226578300, - 1.867156271876684500, - 1.867018802876792200, 1.866881265231955500, 1.866743658947231300, - 1.866605984027679000, - 1.866468240478360600, 1.866330428304340300, 1.866192547510685300, - 1.866054598102465000, - 1.865916580084751500, 1.865778493462619100, 1.865640338241145100, - 1.865502114425408900, - 1.865363822020492700, 1.865225461031480900, 1.865087031463460900, - 1.864948533321522300, - 1.864809966610757400, 1.864671331336260600, 1.864532627503129100, - 1.864393855116463200, - 1.864255014181364500, 1.864116104702938000, 1.863977126686291200, - 1.863838080136534000, - 1.863698965058778300, 1.863559781458139300, 1.863420529339734100, - 1.863281208708683000, - 1.863141819570107900, 1.863002361929134500, 1.862862835790889400, - 1.862723241160503300, - 1.862583578043108100, 1.862443846443839300, 1.862304046367834200, - 1.862164177820232700, - 1.862024240806177800, 1.861884235330814300, 1.861744161399289600, - 1.861604019016754200, - 1.861463808188360500, 1.861323528919263800, 1.861183181214621600, - 1.861042765079594200, - 1.860902280519344500, 1.860761727539037300, 1.860621106143840500, - 1.860480416338924600, - 1.860339658129461800, 1.860198831520627900, 1.860057936517600700, - 1.859916973125560000, - 1.859775941349689000, 1.859634841195173100, 1.859493672667199800, - 1.859352435770959900, - 1.859211130511645900, 1.859069756894453400, 1.858928314924580300, - 1.858786804607227100, - 1.858645225947596300, 1.858503578950893900, 1.858361863622327400, - 1.858220079967107600, - 1.858078227990447300, 1.857936307697561900, 1.857794319093669900, - 1.857652262183991000, - 1.857510136973749000, 1.857367943468169100, 1.857225681672479300, - 1.857083351591910300, - 1.856940953231694900, 1.856798486597069000, 1.856655951693270600, - 1.856513348525540300, - 1.856370677099121100, 1.856227937419258700, 1.856085129491201100, - 1.855942253320199200, - 1.855799308911506100, 1.855656296270377300, 1.855513215402071000, - 1.855370066311848000, - 1.855226849004971500, 1.855083563486706900, 1.854940209762322700, - 1.854796787837089500, - 1.854653297716280400, 1.854509739405171300, 1.854366112909040300, - 1.854222418233168400, - 1.854078655382838300, 1.853934824363336200, 1.853790925179950500, - 1.853646957837971500, - 1.853502922342692600, 1.853358818699409900, 1.853214646913421200, - 1.853070406990027500, - 1.852926098934532200, 1.852781722752241000, 1.852637278448462200, - 1.852492766028506400, - 1.852348185497687300, 1.852203536861320600, 1.852058820124724300, - 1.851914035293219700, - 1.851769182372129600, 1.851624261366780400, 1.851479272282500000, - 1.851334215124619300, - 1.851189089898471800, 1.851043896609393400, 1.850898635262721900, - 1.850753305863798800, - 1.850607908417967200, 1.850462442930572900, 1.850316909406964200, - 1.850171307852492200, - 1.850025638272510000, 1.849879900672373600, 1.849734095057441200, - 1.849588221433073700, - 1.849442279804634600, 1.849296270177489800, 1.849150192557007300, - 1.849004046948558200, - 1.848857833357515900, 1.848711551789256300, 1.848565202249157400, - 1.848418784742600400, - 1.848272299274968500, 1.848125745851647800, 1.847979124478026100, - 1.847832435159495000, - 1.847685677901447200, 1.847538852709279100, 1.847391959588388300, - 1.847244998544176300, - 1.847097969582046200, 1.846950872707404000, 1.846803707925657600, - 1.846656475242218300, - 1.846509174662499300, 1.846361806191916000, 1.846214369835887500, - 1.846066865599834000, - 1.845919293489179000, 1.845771653509348200, 1.845623945665770100, - 1.845476169963875500, - 1.845328326409097400, 1.845180415006871800, 1.845032435762637100, - 1.844884388681833800, - 1.844736273769905300, 1.844588091032297400, 1.844439840474458200, - 1.844291522101838800, - 1.844143135919891900, 1.843994681934073600, 1.843846160149842200, - 1.843697570572658200, - 1.843548913207985000, 1.843400188061288000, 1.843251395138035800, - 1.843102534443698900, - 1.842953605983750400, 1.842804609763666100, 1.842655545788924000, - 1.842506414065004900, - 1.842357214597392100, 1.842207947391570900, 1.842058612453029600, - 1.841909209787258900, - 1.841759739399751800, 1.841610201296003800, 1.841460595481513100, - 1.841310921961780500, - 1.841161180742308500, 1.841011371828603200, 1.840861495226172600, - 1.840711550940526700, - 1.840561538977179200, 1.840411459341645400, 1.840261312039443100, - 1.840111097076092800, - 1.839960814457117600, 1.839810464188043100, 1.839660046274397100, - 1.839509560721709800, - 1.839359007535514400, 1.839208386721346500, 1.839057698284743500, - 1.838906942231246100, - 1.838756118566397200, 1.838605227295741800, 1.838454268424828400, - 1.838303241959206700, - 1.838152147904429800, 1.838000986266052900, 1.837849757049633900, - 1.837698460260732900, - 1.837547095904912700, 1.837395663987738700, 1.837244164514778600, - 1.837092597491602100, - 1.836940962923782700, 1.836789260816895000, 1.836637491176516600, - 1.836485654008228200, - 1.836333749317611700, 1.836181777110252900, 1.836029737391738700, - 1.835877630167659800, - 1.835725455443608200, 1.835573213225179400, 1.835420903517970500, - 1.835268526327581900, - 1.835116081659615700, 1.834963569519677100, 1.834810989913373500, - 1.834658342846314800, - 1.834505628324113200, 1.834352846352383700, 1.834199996936744000, - 1.834047080082813300, - 1.833894095796214400, 1.833741044082571900, 1.833587924947513100, - 1.833434738396668000, - 1.833281484435668400, 1.833128163070149300, 1.832974774305747600, - 1.832821318148103500, - 1.832667794602858400, 1.832514203675657600, 1.832360545372147900, - 1.832206819697979000, - 1.832053026658802700, 1.831899166260273700, 1.831745238508049300, - 1.831591243407788300, - 1.831437180965153100, 1.831283051185808300, 1.831128854075420500, - 1.830974589639659000, - 1.830820257884196100, 1.830665858814705600, 1.830511392436864800, - 1.830356858756352800, - 1.830202257778851300, 1.830047589510044500, 1.829892853955619200, - 1.829738051121264600, - 1.829583181012672400, 1.829428243635536500, 1.829273238995553700, - 1.829118167098423100, - 1.828963027949846100, 1.828807821555527000, 1.828652547921171900, - 1.828497207052490100, - 1.828341798955192900, 1.828186323634994200, 1.828030781097610400, - 1.827875171348760400, - 1.827719494394165500, 1.827563750239549400, 1.827407938890638600, - 1.827252060353161500, - 1.827096114632849700, 1.826940101735436500, 1.826784021666658400, - 1.826627874432253700, - 1.826471660037963800, 1.826315378489531800, 1.826159029792704400, - 1.826002613953229500, - 1.825846130976858100, 1.825689580869344100, 1.825532963636443000, - 1.825376279283913200, - 1.825219527817515800, 1.825062709243013800, 1.824905823566173000, - 1.824748870792761900, - 1.824591850928550800, 1.824434763979313300, 1.824277609950824700, - 1.824120388848863300, - 1.823963100679209600, 1.823805745447646600, 1.823648323159960100, - 1.823490833821937600, - 1.823333277439369600, 1.823175654018049300, 1.823017963563772000, - 1.822860206082335300, - 1.822702381579539800, 1.822544490061187800, 1.822386531533084900, - 1.822228506001038800, - 1.822070413470859600, 1.821912253948359700, 1.821754027439354400, - 1.821595733949661100, - 1.821437373485099900, 1.821278946051493100, 1.821120451654665700, - 1.820961890300445400, - 1.820803261994661500, 1.820644566743146800, 1.820485804551735800, - 1.820326975426265600, - 1.820168079372576300, 1.820009116396509800, 1.819850086503910700, - 1.819690989700625900, - 1.819531825992505500, 1.819372595385401000, 1.819213297885166900, - 1.819053933497660300, - 1.818894502228740600, 1.818735004084269600, 1.818575439070111200, - 1.818415807192132600, - 1.818256108456203000, 1.818096342868193800, 1.817936510433979300, - 1.817776611159436000, - 1.817616645050443000, 1.817456612112881900, 1.817296512352636300, - 1.817136345775592900, - 1.816976112387640700, 1.816815812194670700, 1.816655445202576700, - 1.816495011417255300, - 1.816334510844604700, 1.816173943490526400, 1.816013309360923900, - 1.815852608461703300, - 1.815691840798773000, 1.815531006378043900, 1.815370105205429600, - 1.815209137286846200, - 1.815048102628211500, 1.814887001235446600, 1.814725833114474700, - 1.814564598271221300, - 1.814403296711615000, 1.814241928441585800, 1.814080493467067300, - 1.813918991793994900, - 1.813757423428306000, 1.813595788375941700, 1.813434086642844400, - 1.813272318234959700, - 1.813110483158235400, 1.812948581418621500, 1.812786613022070700, - 1.812624577974538000, - 1.812462476281981200, 1.812300307950360300, 1.812138072985637800, - 1.811975771393778300, - 1.811813403180749300, 1.811650968352521000, 1.811488466915065000, - 1.811325898874356800, - 1.811163264236372900, 1.811000563007093100, 1.810837795192499400, - 1.810674960798576600, - 1.810512059831311400, 1.810349092296693400, 1.810186058200714100, - 1.810022957549368000, - 1.809859790348652200, 1.809696556604565300, 1.809533256323109200, - 1.809369889510288100, - 1.809206456172108200, 1.809042956314578900, 1.808879389943711200, - 1.808715757065519200, - 1.808552057686019200, 1.808388291811230000, 1.808224459447172800, - 1.808060560599871200, - 1.807896595275351200, 1.807732563479641300, 1.807568465218772900, - 1.807404300498778800, - 1.807240069325695400, 1.807075771705560800, 1.806911407644415700, - 1.806746977148303300, - 1.806582480223269500, 1.806417916875362000, 1.806253287110631600, - 1.806088590935131000, - 1.805923828354915900, 1.805758999376044100, 1.805594104004575800, - 1.805429142246573600, - 1.805264114108102900, 1.805099019595231200, 1.804933858714028700, - 1.804768631470567500, - 1.804603337870923000, 1.804437977921172300, 1.804272551627395400, - 1.804107058995674500, - 1.803941500032094200, 1.803775874742741500, 1.803610183133706400, - 1.803444425211080400, - 1.803278600980958300, 1.803112710449436900, 1.802946753622615400, - 1.802780730506595700, - 1.802614641107481900, 1.802448485431380900, 1.802282263484401300, - 1.802115975272655000, - 1.801949620802255600, 1.801783200079319900, 1.801616713109966300, - 1.801450159900316300, - 1.801283540456493700, 1.801116854784624400, 1.800950102890836800, - 1.800783284781262200, - 1.800616400462033800, 1.800449449939287800, 1.800282433219162000, - 1.800115350307797600, - 1.799948201211337500, 1.799780985935927300, 1.799613704487715200, - 1.799446356872851400, - 1.799278943097489100, 1.799111463167783400, 1.798943917089892000, - 1.798776304869975200, - 1.798608626514195800, 1.798440882028718500, 1.798273071419711000, - 1.798105194693343500, - 1.797937251855787700, 1.797769242913218800, 1.797601167871813800, - 1.797433026737752700, - 1.797264819517217200, 1.797096546216391900, 1.796928206841463800, - 1.796759801398622100, - 1.796591329894058800, 1.796422792333968000, 1.796254188724546500, - 1.796085519071992900, - 1.795916783382509200, 1.795747981662299200, 1.795579113917569200, - 1.795410180154527900, - 1.795241180379386800, 1.795072114598359200, 1.794902982817661500, - 1.794733785043511900, - 1.794564521282131300, 1.794395191539743400, 1.794225795822573600, - 1.794056334136850300, - 1.793886806488804100, 1.793717212884667900, 1.793547553330677300, - 1.793377827833070100, - 1.793208036398086900, 1.793038179031970000, 1.792868255740965000, - 1.792698266531319400, - 1.792528211409282900, 1.792358090381108300, 1.792187903453050100, - 1.792017650631366100, - 1.791847331922315600, 1.791676947332161000, 1.791506496867166600, - 1.791335980533599300, - 1.791165398337728900, 1.790994750285827000, 1.790824036384167900, - 1.790653256639028100, - 1.790482411056686800, 1.790311499643425500, 1.790140522405528200, - 1.789969479349281100, - 1.789798370480973000, 1.789627195806895200, 1.789455955333341100, - 1.789284649066606800, - 1.789113277012990900, 1.788941839178794100, 1.788770335570319700, - 1.788598766193873600, - 1.788427131055763600, 1.788255430162300400, 1.788083663519796800, - 1.787911831134568300, - 1.787739933012932900, 1.787567969161210300, 1.787395939585723500, - 1.787223844292797500, - 1.787051683288759500, 1.786879456579939700, 1.786707164172670200, - 1.786534806073285700, - 1.786362382288123400, 1.786189892823522700, 1.786017337685825700, - 1.785844716881376700, - 1.785672030416522300, 1.785499278297612000, 1.785326460530997300, - 1.785153577123032000, - 1.784980628080072900, 1.784807613408478300, 1.784634533114609800, - 1.784461387204831400, - 1.784288175685508700, 1.784114898563010200, 1.783941555843707100, - 1.783768147533972200, - 1.783594673640181800, 1.783421134168713800, 1.783247529125948900, - 1.783073858518269700, - 1.782900122352062000, 1.782726320633713200, 1.782552453369613800, - 1.782378520566156200, - 1.782204522229735600, 1.782030458366749200, 1.781856328983596900, - 1.781682134086680900, - 1.781507873682406200, 1.781333547777179200, 1.781159156377410100, - 1.780984699489510200, - 1.780810177119894100, 1.780635589274978600, 1.780460935961182300, - 1.780286217184927000, - 1.780111432952636600, 1.779936583270737400, 1.779761668145658300, - 1.779586687583830200, - 1.779411641591686500, 1.779236530175663600, 1.779061353342199500, - 1.778886111097735000, - 1.778710803448713400, 1.778535430401580100, 1.778359991962783000, - 1.778184488138772900, - 1.778008918936002000, 1.777833284360925900, 1.777657584420002000, - 1.777481819119690200, - 1.777305988466453000, 1.777130092466755200, 1.776954131127064200, - 1.776778104453849100, - 1.776602012453582400, 1.776425855132738100, 1.776249632497793200, - 1.776073344555227000, - 1.775896991311520800, 1.775720572773158900, 1.775544088946627600, - 1.775367539838415700, - 1.775190925455014400, 1.775014245802917200, 1.774837500888620400, - 1.774660690718622000, - 1.774483815299423100, 1.774306874637527000, 1.774129868739439100, - 1.773952797611667100, - 1.773775661260722100, 1.773598459693116500, 1.773421192915365400, - 1.773243860933986400, - 1.773066463755499800, 1.772889001386427800, 1.772711473833295200, - 1.772533881102629000, - 1.772356223200959100, 1.772178500134817100, 1.772000711910737700, - 1.771822858535257600, - 1.771644940014915700, 1.771466956356254000, 1.771288907565816000, - 1.771110793650148500, - 1.770932614615799800, 1.770754370469321400, 1.770576061217266500, - 1.770397686866191300, - 1.770219247422653700, 1.770040742893215000, 1.769862173284438000, - 1.769683538602888000, - 1.769504838855133100, 1.769326074047743700, 1.769147244187292200, - 1.768968349280353800, - 1.768789389333506000, 1.768610364353328600, 1.768431274346403900, - 1.768252119319316400, - 1.768072899278653200, 1.767893614231003800, 1.767714264182959500, - 1.767534849141115100, - 1.767355369112067100, 1.767175824102414000, 1.766996214118757800, - 1.766816539167701800, - 1.766636799255852300, 1.766456994389817600, 1.766277124576209000, - 1.766097189821639300, - 1.765917190132724600, 1.765737125516083000, 1.765556995978334800, - 1.765376801526102700, - 1.765196542166012100, 1.765016217904690900, 1.764835828748768400, - 1.764655374704877700, - 1.764474855779653200, 1.764294271979732100, 1.764113623311754000, - 1.763932909782361100, - 1.763752131398197200, 1.763571288165909400, 1.763390380092146400, - 1.763209407183560200, - 1.763028369446804500, 1.762847266888535100, 1.762666099515411100, - 1.762484867334093400, - 1.762303570351245300, 1.762122208573532600, 1.761940782007623600, - 1.761759290660188400, - 1.761577734537900500, 1.761396113647435000, 1.761214427995469100, - 1.761032677588683800, - 1.760850862433760700, 1.760668982537384900, 1.760487037906243600, - 1.760305028547026500, - 1.760122954466425600, 1.759940815671135100, 1.759758612167851700, - 1.759576343963274600, - 1.759394011064105100, 1.759211613477047200, 1.759029151208807400, - 1.758846624266093800, - 1.758664032655617500, 1.758481376384092500, 1.758298655458233600, - 1.758115869884759700, - 1.757933019670390800, 1.757750104821850000, 1.757567125345862700, - 1.757384081249156100, - 1.757200972538460700, 1.757017799220508500, 1.756834561302034400, - 1.756651258789775800, - 1.756467891690471700, 1.756284460010864200, 1.756100963757697900, - 1.755917402937718900, - 1.755733777557676500, 1.755550087624322000, 1.755366333144409200, - 1.755182514124693900, - 1.754998630571935200, 1.754814682492893600, 1.754630669894332600, - 1.754446592783017500, - 1.754262451165716300, 1.754078245049199600, 1.753893974440240000, - 1.753709639345612600, - 1.753525239772095100, 1.753340775726466700, 1.753156247215510400, - 1.752971654246010300, - 1.752786996824753600, 1.752602274958529500, 1.752417488654129700, - 1.752232637918348200, - 1.752047722757981600, 1.751862743179828600, 1.751677699190690400, - 1.751492590797370600, - 1.751307418006674800, 1.751122180825411800, 1.750936879260391700, - 1.750751513318427700, - 1.750566083006335600, 1.750380588330932500, 1.750195029299038900, - 1.750009405917477100, - 1.749823718193071800, 1.749637966132650900, 1.749452149743043100, - 1.749266269031080700, - 1.749080324003598100, 1.748894314667431800, 1.748708241029421000, - 1.748522103096407300, - 1.748335900875233900, 1.748149634372747200, 1.747963303595795500, - 1.747776908551230000, - 1.747590449245904000, 1.747403925686672500, 1.747217337880393900, - 1.747030685833928200, - 1.746843969554138200, 1.746657189047889200, 1.746470344322048200, - 1.746283435383485100, - 1.746096462239072000, 1.745909424895683200, 1.745722323360195900, - 1.745535157639489100, - 1.745347927740444200, 1.745160633669945200, 1.744973275434878300, - 1.744785853042132300, - 1.744598366498598200, 1.744410815811169300, 1.744223200986741100, - 1.744035522032211900, - 1.743847778954482000, 1.743659971760454200, 1.743472100457033700, - 1.743284165051127700, - 1.743096165549646400, 1.742908101959502100, 1.742719974287608900, - 1.742531782540884100, - 1.742343526726246800, 1.742155206850618800, 1.741966822920923800, - 1.741778374944088000, - 1.741589862927040800, 1.741401286876712800, 1.741212646800037300, - 1.741023942703950200, - 1.740835174595389600, 1.740646342481295900, 1.740457446368612000, - 1.740268486264283200, - 1.740079462175256900, 1.739890374108482600, 1.739701222070913200, - 1.739512006069502800, - 1.739322726111208500, 1.739133382202989500, 1.738943974351807600, - 1.738754502564626700, - 1.738564966848413100, 1.738375367210135400, 1.738185703656765200, - 1.737995976195275000, - 1.737806184832640900, 1.737616329575841300, 1.737426410431856200, - 1.737236427407668800, - 1.737046380510263800, 1.736856269746629000, 1.736666095123754000, - 1.736475856648631400, - 1.736285554328254900, 1.736095188169622500, 1.735904758179732400, - 1.735714264365586700, - 1.735523706734189100, 1.735333085292545900, 1.735142400047666100, - 1.734951651006560100, - 1.734760838176241400, 1.734569961563725600, 1.734379021176030600, - 1.734188017020177100, - 1.733996949103187500, 1.733805817432086900, 1.733614622013902600, - 1.733423362855664100, - 1.733232039964403900, 1.733040653347156300, 1.732849203010957900, - 1.732657688962847600, - 1.732466111209867200, 1.732274469759060200, 1.732082764617472800, - 1.731890995792153600, - 1.731699163290153100, 1.731507267118524500, 1.731315307284323700, - 1.731123283794607800, - 1.730931196656437600, 1.730739045876875200, 1.730546831462985500, - 1.730354553421835600, - 1.730162211760495300, 1.729969806486036500, 1.729777337605533000, - 1.729584805126061400, - 1.729392209054700900, 1.729199549398532400, 1.729006826164639400, - 1.728814039360108100, - 1.728621188992026400, 1.728428275067485100, 1.728235297593577100, - 1.728042256577397200, - 1.727849152026043500, 1.727655983946615700, 1.727462752346216000, - 1.727269457231948900, - 1.727076098610921500, 1.726882676490243000, 1.726689190877025000, - 1.726495641778381200, - 1.726302029201427900, 1.726108353153283900, 1.725914613641069900, - 1.725720810671909300, - 1.725526944252927700, 1.725333014391252900, 1.725139021094015200, - 1.724944964368347000, - 1.724750844221383500, 1.724556660660261800, 1.724362413692121400, - 1.724168103324104300, - 1.723973729563354600, 1.723779292417019200, 1.723584791892246700, - 1.723390227996188600, - 1.723195600735998100, 1.723000910118831300, 1.722806156151846400, - 1.722611338842204000, - 1.722416458197066900, 1.722221514223600100, 1.722026506928971500, - 1.721831436320350800, - 1.721636302404910200, 1.721441105189824000, 1.721245844682269600, - 1.721050520889425600, - 1.720855133818473900, 1.720659683476597900, 1.720464169870984200, - 1.720268593008821100, - 1.720072952897299100, 1.719877249543611900, 1.719681482954954500, - 1.719485653138524800, - 1.719289760101522900, 1.719093803851151400, 1.718897784394614900, - 1.718701701739120400, - 1.718505555891877400, 1.718309346860097600, 1.718113074650995200, - 1.717916739271786500, - 1.717720340729689700, 1.717523879031926500, 1.717327354185719900, - 1.717130766198295700, - 1.716934115076881800, 1.716737400828708400, 1.716540623461008100, - 1.716343782981016200, - 1.716146879395969500, 1.715949912713108100, 1.715752882939673300, - 1.715555790082909900, - 1.715358634150064000, 1.715161415148384500, 1.714964133085122900, - 1.714766787967532600, - 1.714569379802868900, 1.714371908598390800, 1.714174374361358000, - 1.713976777099033700, - 1.713779116818682900, 1.713581393527573000, 1.713383607232973600, - 1.713185757942156800, - 1.712987845662396800, 1.712789870400970700, 1.712591832165157200, - 1.712393730962237500, - 1.712195566799495500, 1.711997339684216700, 1.711799049623689900, - 1.711600696625205300, - 1.711402280696055800, 1.711203801843536700, 1.711005260074945200, - 1.710806655397581600, - 1.710607987818747700, 1.710409257345748100, 1.710210463985889500, - 1.710011607746480600, - 1.709812688634833300, 1.709613706658261100, 1.709414661824080000, - 1.709215554139608400, - 1.709016383612166600, 1.708817150249077900, 1.708617854057667300, - 1.708418495045262300, - 1.708219073219193300, 1.708019588586791700, 1.707820041155392500, - 1.707620430932332400, - 1.707420757924950300, 1.707221022140587900, 1.707021223586588700, - 1.706821362270298600, - 1.706621438199066300, 1.706421451380242000, 1.706221401821179200, - 1.706021289529232800, - 1.705821114511760300, 1.705620876776121600, 1.705420576329679000, - 1.705220213179796900, - 1.705019787333842200, 1.704819298799183700, 1.704618747583193100, - 1.704418133693243800, - 1.704217457136711900, 1.704016717920976000, 1.703815916053416300, - 1.703615051541415900, - 1.703414124392360000, 1.703213134613636100, 1.703012082212634000, - 1.702810967196746000, - 1.702609789573366300, 1.702408549349891500, 1.702207246533721000, - 1.702005881132255800, - 1.701804453152900000, 1.701602962603059100, 1.701401409490141300, - 1.701199793821557300, - 1.700998115604720000, 1.700796374847044300, 1.700594571555948100, - 1.700392705738850400, - 1.700190777403173700, 1.699988786556342300, 1.699786733205783000, - 1.699584617358924400, - 1.699382439023197700, 1.699180198206036600, 1.698977894914877100, - 1.698775529157156700, - 1.698573100940316400, 1.698370610271798800, 1.698168057159048700, - 1.697965441609513300, - 1.697762763630642700, 1.697560023229888200, 1.697357220414704500, - 1.697154355192547900, - 1.696951427570877000, 1.696748437557152900, 1.696545385158839200, - 1.696342270383401200, - 1.696139093238307400, 1.695935853731027600, 1.695732551869034300, - 1.695529187659802400, - 1.695325761110809200, 1.695122272229534000, 1.694918721023458600, - 1.694715107500066800, - 1.694511431666845000, 1.694307693531282000, 1.694103893100868100, - 1.693900030383096900, - 1.693696105385463800, 1.693492118115466500, 1.693288068580604900, - 1.693083956788381500, - 1.692879782746300700, 1.692675546461869900, 1.692471247942597600, - 1.692266887195995600, - 1.692062464229577600, 1.691857979050859900, 1.691653431667360600, - 1.691448822086600400, - 1.691244150316102000, 1.691039416363390800, 1.690834620235994300, - 1.690629761941442100, - 1.690424841487266700, 1.690219858881001800, 1.690014814130184300, - 1.689809707242353200, - 1.689604538225049700, 1.689399307085817300, 1.689194013832201500, - 1.688988658471750600, - 1.688783241012014700, 1.688577761460546800, 1.688372219824901400, - 1.688166616112636100, - 1.687960950331309800, 1.687755222488484600, 1.687549432591724400, - 1.687343580648595700, - 1.687137666666667100, 1.686931690653509000, 1.686725652616694900, - 1.686519552563800400, - 1.686313390502403000, 1.686107166440082600, 1.685900880384421800, - 1.685694532343004600, - 1.685488122323418400, 1.685281650333251900, 1.685075116380096800, - 1.684868520471546600, - 1.684661862615197000, 1.684455142818646700, 1.684248361089495800, - 1.684041517435347400, - 1.683834611863806100, 1.683627644382479800, 1.683420614998977900, - 1.683213523720911800, - 1.683006370555896400, 1.682799155511547600, 1.682591878595484300, - 1.682384539815327400, - 1.682177139178700400, 1.681969676693228600, 1.681762152366539600, - 1.681554566206263900, - 1.681346918220033800, 1.681139208415483700, 1.680931436800250600, - 1.680723603381973500, - 1.680515708168294200, 1.680307751166856300, 1.680099732385305300, - 1.679891651831290100, - 1.679683509512460900, 1.679475305436470600, 1.679267039610974300, - 1.679058712043629300, - 1.678850322742095200, 1.678641871714033900, 1.678433358967109400, - 1.678224784508988400, - 1.678016148347339300, 1.677807450489833300, 1.677598690944143400, - 1.677389869717945000, - 1.677180986818916300, 1.676972042254736900, 1.676763036033089600, - 1.676553968161658600, - 1.676344838648130600, 1.676135647500194700, 1.675926394725542700, - 1.675717080331867900, - 1.675507704326866200, 1.675298266718235900, 1.675088767513677200, - 1.674879206720892900, - 1.674669584347587800, 1.674459900401469700, 1.674250154890247300, - 1.674040347821632800, - 1.673830479203340000, 1.673620549043085500, 1.673410557348587600, - 1.673200504127567000, - 1.672990389387746700, 1.672780213136852300, 1.672569975382611300, - 1.672359676132753500, - 1.672149315395010900, 1.671938893177118000, 1.671728409486811500, - 1.671517864331830000, - 1.671307257719914800, 1.671096589658809500, 1.670885860156259300, - 1.670675069220012500, - 1.670464216857819200, 1.670253303077431800, 1.670042327886605200, - 1.669831291293095900, - 1.669620193304663500, 1.669409033929069500, 1.669197813174077200, - 1.668986531047453000, - 1.668775187556965000, 1.668563782710383600, 1.668352316515481700, - 1.668140788980034400, - 1.667929200111818400, 1.667717549918614100, 1.667505838408202700, - 1.667294065588368100, - 1.667082231466896900, 1.666870336051577800, 1.666658379350201000, - 1.666446361370560000, - 1.666234282120450100, 1.666022141607668600, 1.665809939840015500, - 1.665597676825292700, - 1.665385352571304500, 1.665172967085857700, 1.664960520376761000, - 1.664748012451825200, - 1.664535443318863900, 1.664322812985692600, 1.664110121460129000, - 1.663897368749993400, - 1.663684554863107800, 1.663471679807296800, 1.663258743590387400, - 1.663045746220208600, - 1.662832687704591800, 1.662619568051370500, 1.662406387268380100, - 1.662193145363459100, - 1.661979842344447600, 1.661766478219188300, 1.661553052995526000, - 1.661339566681307600, - 1.661126019284382200, 1.660912410812601900, 1.660698741273819700, - 1.660485010675892400, - 1.660271219026677700, 1.660057366334036300, 1.659843452605831200, - 1.659629477849926800, - 1.659415442074190900, 1.659201345286492900, 1.658987187494704200, - 1.658772968706699000, - 1.658558688930353400, 1.658344348173546300, 1.658129946444157700, - 1.657915483750071100, - 1.657700960099171200, 1.657486375499345900, 1.657271729958484500, - 1.657057023484479000, - 1.656842256085223800, 1.656627427768615000, 1.656412538542551200, - 1.656197588414933600, - 1.655982577393664700, 1.655767505486650500, 1.655552372701798200, - 1.655337179047017700, - 1.655121924530220900, 1.654906609159322500, 1.654691232942238500, - 1.654475795886888300, - 1.654260298001192200, 1.654044739293073900, 1.653829119770458900, - 1.653613439441274500, - 1.653397698313451300, 1.653181896394921000, 1.652966033693617800, - 1.652750110217479100, - 1.652534125974443000, 1.652318080972451400, 1.652101975219447200, - 1.651885808723375900, - 1.651669581492185300, 1.651453293533826000, 1.651236944856249600, - 1.651020535467411200, - 1.650804065375267400, 1.650587534587776700, 1.650370943112901000, - 1.650154290958603300, - 1.649937578132849400, 1.649720804643607400, 1.649503970498847200, - 1.649287075706541200, - 1.649070120274664000, 1.648853104211192700, 1.648636027524106100, - 1.648418890221385400, - 1.648201692311014300, 1.647984433800978600, 1.647767114699266100, - 1.647549735013867000, - 1.647332294752774200, 1.647114793923981600, 1.646897232535486500, - 1.646679610595287900, - 1.646461928111387300, 1.646244185091788400, 1.646026381544496400, - 1.645808517477519700, - 1.645590592898868600, 1.645372607816555400, 1.645154562238594800, - 1.644936456173004000, - 1.644718289627801600, 1.644500062611009300, 1.644281775130650900, - 1.644063427194751600, - 1.643845018811340300, 1.643626549988446200, 1.643408020734102600, - 1.643189431056343700, - 1.642970780963206800, 1.642752070462730800, 1.642533299562957100, - 1.642314468271929300, - 1.642095576597693200, 1.641876624548297000, 1.641657612131790500, - 1.641438539356226500, - 1.641219406229659700, 1.641000212760146800, 1.640780958955747200, - 1.640561644824521700, - 1.640342270374534500, 1.640122835613851100, 1.639903340550539200, - 1.639683785192669600, - 1.639464169548314100, 1.639244493625547900, 1.639024757432447500, - 1.638804960977092100, - 1.638585104267562800, 1.638365187311943400, 1.638145210118319400, - 1.637925172694778800, - 1.637705075049411800, 1.637484917190310800, 1.637264699125570200, - 1.637044420863286600, - 1.636824082411559600, 1.636603683778490100, 1.636383224972181500, - 1.636162706000739300, - 1.635942126872271800, 1.635721487594888400, 1.635500788176702100, - 1.635280028625826900, - 1.635059208950379700, 1.634838329158479200, 1.634617389258246700, - 1.634396389257805700, - 1.634175329165281400, 1.633954208988801700, 1.633733028736496400, - 1.633511788416498000, - 1.633290488036940500, 1.633069127605960800, 1.632847707131697600, - 1.632626226622291700, - 1.632404686085886300, 1.632183085530627200, 1.631961424964661700, - 1.631739704396139900, - 1.631517923833213400, 1.631296083284036900, 1.631074182756766300, - 1.630852222259560700, - 1.630630201800580900, 1.630408121387990000, 1.630185981029953000, - 1.629963780734637400, - 1.629741520510213000, 1.629519200364851800, 1.629296820306727700, - 1.629074380344017100, - 1.628851880484898200, 1.628629320737551700, 1.628406701110161100, - 1.628184021610910700, - 1.627961282247988300, 1.627738483029583100, 1.627515623963887000, - 1.627292705059093700, - 1.627069726323399500, 1.626846687765002700, 1.626623589392103500, - 1.626400431212904800, - 1.626177213235611400, 1.625953935468430500, 1.625730597919571300, - 1.625507200597245500, - 1.625283743509666300, 1.625060226665050000, 1.624836650071614500, - 1.624613013737580000, - 1.624389317671169500, 1.624165561880607000, 1.623941746374119500, - 1.623717871159936300, - 1.623493936246288300, 1.623269941641409400, 1.623045887353534900, - 1.622821773390902700, - 1.622597599761753000, 1.622373366474327800, 1.622149073536871800, - 1.621924720957631300, - 1.621700308744855200, 1.621475836906794500, 1.621251305451702400, - 1.621026714387834300, - 1.620802063723447700, 1.620577353466802700, 1.620352583626160500, - 1.620127754209786100, - 1.619902865225945300, 1.619677916682906700, 1.619452908588941300, - 1.619227840952321800, - 1.619002713781323200, 1.618777527084222800, 1.618552280869300300, - 1.618326975144837000, - 1.618101609919117200, 1.617876185200426600, 1.617650700997053500, - 1.617425157317288200, - 1.617199554169423500, 1.616973891561754200, 1.616748169502577200, - 1.616522388000191500, - 1.616296547062898500, 1.616070646699001800, 1.615844686916807300, - 1.615618667724622700, - 1.615392589130757900, 1.615166451143525300, 1.614940253771239400, - 1.614713997022216900, - 1.614487680904776600, 1.614261305427239200, 1.614034870597928400, - 1.613808376425168900, - 1.613581822917288900, 1.613355210082617800, 1.613128537929487500, - 1.612901806466232200, - 1.612675015701188000, 1.612448165642693400, 1.612221256299089200, - 1.611994287678718100, - 1.611767259789925100, 1.611540172641057200, 1.611313026240463800, - 1.611085820596496600, - 1.610858555717509200, 1.610631231611857800, 1.610403848287899700, - 1.610176405753995800, - 1.609948904018508200, 1.609721343089801600, 1.609493722976242900, - 1.609266043686200700, - 1.609038305228046400, 1.608810507610153100, 1.608582650840896200, - 1.608354734928653800, - 1.608126759881805400, 1.607898725708732900, 1.607670632417820500, - 1.607442480017454700, - 1.607214268516024000, 1.606985997921919000, 1.606757668243532500, - 1.606529279489259600, - 1.606300831667497600, 1.606072324786645500, 1.605843758855105300, - 1.605615133881280700, - 1.605386449873577300, 1.605157706840403300, 1.604928904790168700, - 1.604700043731286200, - 1.604471123672170500, 1.604242144621237800, 1.604013106586907400, - 1.603784009577600100, - 1.603554853601739700, 1.603325638667751000, 1.603096364784061900, - 1.602867031959102100, - 1.602637640201303400, 1.602408189519099800, 1.602178679920927900, - 1.601949111415226000, - 1.601719484010434300, 1.601489797714996000, 1.601260052537355700, - 1.601030248485960900, - 1.600800385569260300, 1.600570463795705700, 1.600340483173750400, - 1.600110443711850300, - 1.599880345418463100, 1.599650188302049100, 1.599419972371070500, - 1.599189697633991400, - 1.598959364099278700, 1.598728971775401000, 1.598498520670828900, - 1.598268010794035900, - 1.598037442153496900, 1.597806814757689200, 1.597576128615092200, - 1.597345383734188000, - 1.597114580123460100, 1.596883717791394800, 1.596652796746479600, - 1.596421816997205500, - 1.596190778552064800, 1.595959681419551800, 1.595728525608163700, - 1.595497311126399300, - 1.595266037982759500, 1.595034706185747500, 1.594803315743869000, - 1.594571866665631700, - 1.594340358959544800, 1.594108792634120600, 1.593877167697873100, - 1.593645484159318200, - 1.593413742026974500, 1.593181941309362400, 1.592950082015004700, - 1.592718164152426000, - 1.592486187730153300, 1.592254152756715600, 1.592022059240644400, - 1.591789907190473100, - 1.591557696614737100, 1.591325427521974100, 1.591093099920724200, - 1.590860713819529400, - 1.590628269226933600, 1.590395766151483400, 1.590163204601727100, - 1.589930584586215500, - 1.589697906113501000, 1.589465169192139100, 1.589232373830686400, - 1.588999520037702300, - 1.588766607821748200, 1.588533637191387400, 1.588300608155185600, - 1.588067520721711000, - 1.587834374899533400, 1.587601170697224600, 1.587367908123358900, - 1.587134587186513000, - 1.586901207895265300, 1.586667770258196600, 1.586434274283889500, - 1.586200719980929200, - 1.585967107357902700, 1.585733436423399000, 1.585499707186010200, - 1.585265919654329300, - 1.585032073836952100, 1.584798169742476400, 1.584564207379502500, - 1.584330186756632200, - 1.584096107882470000, 1.583861970765622100, 1.583627775414697000, - 1.583393521838305700, - 1.583159210045060900, 1.582924840043577400, 1.582690411842472700, - 1.582455925450365600, - 1.582221380875877800, 1.581986778127632700, 1.581752117214255900, - 1.581517398144375800, - 1.581282620926621300, 1.581047785569625400, 1.580812892082021900, - 1.580577940472447200, - 1.580342930749539800, 1.580107862921940700, 1.579872736998292100, - 1.579637552987239100, - 1.579402310897428900, 1.579167010737510600, 1.578931652516135700, - 1.578696236241957200, - 1.578460761923630800, 1.578225229569814700, 1.577989639189168100, - 1.577753990790353500, - 1.577518284382034800, 1.577282519972878200, 1.577046697571552000, - 1.576810817186727000, - 1.576574878827075700, 1.576338882501273000, 1.576102828217995600, - 1.575866715985922500, - 1.575630545813735200, 1.575394317710116600, 1.575158031683752300, - 1.574921687743330300, - 1.574685285897539800, 1.574448826155072400, 1.574212308524622500, - 1.573975733014886000, - 1.573739099634561500, 1.573502408392348600, 1.573265659296950300, - 1.573028852357070800, - 1.572791987581417100, 1.572555064978698100, 1.572318084557624800, - 1.572081046326909900, - 1.571843950295269000, 1.571606796471419100, 1.571369584864080100, - 1.571132315481973200, - 1.570894988333822400, 1.570657603428353300, 1.570420160774294000, - 1.570182660380374600, - 1.569945102255327200, 1.569707486407886600, 1.569469812846788500, - 1.569232081580771900, - 1.568994292618577400, 1.568756445968948000, 1.568518541640628400, - 1.568280579642366000, - 1.568042559982909500, 1.567804482671010500, 1.567566347715422500, - 1.567328155124900800, - 1.567089904908203200, 1.566851597074089500, 1.566613231631321500, - 1.566374808588663300, - 1.566136327954881000, 1.565897789738742900, 1.565659193949019400, - 1.565420540594482800, - 1.565181829683907700, 1.564943061226071100, 1.564704235229751500, - 1.564465351703730400, - 1.564226410656790000, 1.563987412097716200, 1.563748356035296000, - 1.563509242478319000, - 1.563270071435576500, 1.563030842915862100, 1.562791556927971800, - 1.562552213480703300, - 1.562312812582856500, 1.562073354243233700, 1.561833838470639200, - 1.561594265273878800, - 1.561354634661761300, 1.561114946643096900, 1.560875201226698900, - 1.560635398421381400, - 1.560395538235961800, 1.560155620679258400, 1.559915645760092900, - 1.559675613487288200, - 1.559435523869669500, 1.559195376916064700, 1.558955172635302800, - 1.558714911036215700, - 1.558474592127637100, 1.558234215918402600, 1.557993782417350400, - 1.557753291633320500, - 1.557512743575155000, 1.557272138251698300, 1.557031475671796400, - 1.556790755844298400, - 1.556549978778054300, 1.556309144481917300, 1.556068252964741600, - 1.555827304235384500, - 1.555586298302704900, 1.555345235175563900, 1.555104114862824600, - 1.554862937373352500, - 1.554621702716015000, 1.554380410899681300, 1.554139061933223200, - 1.553897655825514600, - 1.553656192585431100, 1.553414672221850700, 1.553173094743653300, - 1.552931460159721100, - 1.552689768478938500, 1.552448019710191300, 1.552206213862368500, - 1.551964350944360100, - 1.551722430965059000, 1.551480453933359800, 1.551238419858159700, - 1.550996328748356800, - 1.550754180612852900, 1.550511975460550500, 1.550269713300355100, - 1.550027394141174000, - 1.549785017991916400, 1.549542584861493900, 1.549300094758820000, - 1.549057547692810600, - 1.548814943672383300, 1.548572282706457900, 1.548329564803956300, - 1.548086789973802700, - 1.547843958224923000, 1.547601069566245900, 1.547358124006701400, - 1.547115121555221700, - 1.546872062220741700, 1.546628946012197800, 1.546385772938528600, - 1.546142543008675300, - 1.545899256231580300, 1.545655912616188800, 1.545412512171447700, - 1.545169054906306200, - 1.544925540829715600, 1.544681969950629300, 1.544438342278002600, - 1.544194657820792800, - 1.543950916587959700, 1.543707118588464800, 1.543463263831272000, - 1.543219352325347200, - 1.542975384079658300, 1.542731359103175300, 1.542487277404870100, - 1.542243138993717000, - 1.541998943878692300, 1.541754692068774600, 1.541510383572944000, - 1.541266018400183200, - 1.541021596559476700, 1.540777118059811100, 1.540532582910175500, - 1.540287991119560600, - 1.540043342696959100, 1.539798637651366400, 1.539553875991779300, - 1.539309057727197300, - 1.539064182866621400, 1.538819251419055100, 1.538574263393503800, - 1.538329218798974800, - 1.538084117644477900, 1.537838959939025200, 1.537593745691629500, - 1.537348474911307300, - 1.537103147607076200, 1.536857763787956400, 1.536612323462969800, - 1.536366826641140800, - 1.536121273331495300, 1.535875663543061700, 1.535629997284870400, - 1.535384274565953600, - 1.535138495395346400, 1.534892659782085100, 1.534646767735208000, - 1.534400819263756400, - 1.534154814376772700, 1.533908753083302200, 1.533662635392391700, - 1.533416461313090100, - 1.533170230854448400, 1.532923944025520200, 1.532677600835360600, - 1.532431201293027000, - 1.532184745407578500, 1.531938233188077100, 1.531691664643585900, - 1.531445039783170500, - 1.531198358615898800, 1.530951621150840700, 1.530704827397067800, - 1.530457977363654000, - 1.530211071059675200, 1.529964108494209700, 1.529717089676337500, - 1.529470014615140800, - 1.529222883319703700, 1.528975695799112500, 1.528728452062455600, - 1.528481152118823700, - 1.528233795977309400, 1.527986383647006500, 1.527738915137012400, - 1.527491390456425600, - 1.527243809614346600, 1.526996172619878900, 1.526748479482126700, - 1.526500730210197200, - 1.526252924813199500, 1.526005063300244900, 1.525757145680446200, - 1.525509171962918800, - 1.525261142156779900, 1.525013056271149000, 1.524764914315147200, - 1.524516716297898300, - 1.524268462228527900, 1.524020152116163200, 1.523771785969934000, - 1.523523363798972000, - 1.523274885612411200, 1.523026351419387100, 1.522777761229038100, - 1.522529115050503600, - 1.522280412892925900, 1.522031654765448900, 1.521782840677218700, - 1.521533970637383800, - 1.521285044655094300, 1.521036062739502300, 1.520787024899762100, - 1.520537931145030400, - 1.520288781484465700, 1.520039575927228500, 1.519790314482481100, - 1.519540997159388300, - 1.519291623967116600, 1.519042194914835200, 1.518792710011714500, - 1.518543169266927600, - 1.518293572689648900, 1.518043920289055900, 1.517794212074327500, - 1.517544448054644500, - 1.517294628239190400, 1.517044752637150000, 1.516794821257710500, - 1.516544834110061600, - 1.516294791203394200, 1.516044692546901800, 1.515794538149779700, - 1.515544328021225500, - 1.515294062170438700, 1.515043740606620800, 1.514793363338975600, - 1.514542930376708600, - 1.514292441729027300, 1.514041897405141700, 1.513791297414263800, - 1.513540641765606800, - 1.513289930468387300, 1.513039163531823000, 1.512788340965133500, - 1.512537462777541200, - 1.512286528978270300, 1.512035539576546600, 1.511784494581598600, - 1.511533394002656100, - 1.511282237848951400, 1.511031026129719100, 1.510779758854195400, - 1.510528436031618900, - 1.510277057671229400, 1.510025623782270000, 1.509774134373984800, - 1.509522589455620600, - 1.509270989036425800, 1.509019333125651200, 1.508767621732549400, - 1.508515854866375100, - 1.508264032536385000, 1.508012154751837700, 1.507760221521994700, - 1.507508232856118200, - 1.507256188763473200, 1.507004089253327000, 1.506751934334948000, - 1.506499724017607900, - 1.506247458310579400, 1.505995137223137500, 1.505742760764559300, - 1.505490328944124200, - 1.505237841771113200, 1.504985299254809800, 1.504732701404498900, - 1.504480048229468000, - 1.504227339739006500, 1.503974575942405700, 1.503721756848958700, - 1.503468882467961600, - 1.503215952808711500, 1.502962967880507600, 1.502709927692651900, - 1.502456832254447600, - 1.502203681575200700, 1.501950475664218600, 1.501697214530810700, - 1.501443898184289200, - 1.501190526633967600, 1.500937099889161600, 1.500683617959188900, - 1.500430080853369500, - 1.500176488581024900, 1.499922841151479600, 1.499669138574058800, - 1.499415380858090800, - 1.499161568012905300, 1.498907700047834600, 1.498653776972212600, - 1.498399798795375000, - 1.498145765526660300, 1.497891677175408500, 1.497637533750961300, - 1.497383335262663300, - 1.497129081719860400, 1.496874773131900800, 1.496620409508134800, - 1.496365990857914600, - 1.496111517190594300, 1.495856988515530400, 1.495602404842080800, - 1.495347766179606400, - 1.495093072537469100, 1.494838323925033400, 1.494583520351665500, - 1.494328661826734200, - 1.494073748359609600, 1.493818779959664300, 1.493563756636272500, - 1.493308678398810800, - 1.493053545256657800, 1.492798357219194100, 1.492543114295801900, - 1.492287816495866200, - 1.492032463828773200, 1.491777056303911700, 1.491521593930672100, - 1.491266076718446900, - 1.491010504676631500, 1.490754877814621800, 1.490499196141816600, - 1.490243459667616600, - 1.489987668401424800, 1.489731822352645500, 1.489475921530685900, - 1.489219965944954300, - 1.488963955604861500, 1.488707890519820600, 1.488451770699245900, - 1.488195596152554800, - 1.487939366889165600, 1.487683082918499300, 1.487426744249978400, - 1.487170350893028500, - 1.486913902857075700, 1.486657400151549600, 1.486400842785880100, - 1.486144230769501000, - 1.485887564111846500, 1.485630842822354100, 1.485374066910462500, - 1.485117236385612200, - 1.484860351257246500, 1.484603411534810300, 1.484346417227750700, - 1.484089368345516300, - 1.483832264897558400, 1.483575106893329600, 1.483317894342285100, - 1.483060627253882000, - 1.482803305637578900, 1.482545929502837100, 1.482288498859119400, - 1.482031013715890700, - 1.481773474082618300, 1.481515879968770900, 1.481258231383819800, - 1.481000528337237800, - 1.480742770838499900, 1.480484958897083200, 1.480227092522466500, - 1.479969171724131200, - 1.479711196511560100, 1.479453166894238100, 1.479195082881652200, - 1.478936944483291600, - 1.478678751708647000, 1.478420504567211900, 1.478162203068481100, - 1.477903847221951400, - 1.477645437037121900, 1.477386972523493800, 1.477128453690569800, - 1.476869880547855300, - 1.476611253104856700, 1.476352571371083700, 1.476093835356046700, - 1.475835045069259000, - 1.475576200520235500, 1.475317301718493300, 1.475058348673551100, - 1.474799341394929900, - 1.474540279892153000, 1.474281164174744900, 1.474021994252233000, - 1.473762770134145800, - 1.473503491830014300, 1.473244159349371700, 1.472984772701752900, - 1.472725331896694400, - 1.472465836943735600, 1.472206287852416900, 1.471946684632281500, - 1.471687027292874400, - 1.471427315843742100, 1.471167550294433700, 1.470907730654499800, - 1.470647856933493300, - 1.470387929140969200, 1.470127947286484100, 1.469867911379596900, - 1.469607821429868500, - 1.469347677446861500, 1.469087479440140300, 1.468827227419272200, - 1.468566921393825700, - 1.468306561373371900, 1.468046147367482600, 1.467785679385733300, - 1.467525157437700200, - 1.467264581532962100, 1.467003951681099800, 1.466743267891695800, - 1.466482530174334500, - 1.466221738538602500, 1.465960892994088800, 1.465699993550383400, - 1.465439040217079400, - 1.465178033003770700, 1.464916971920054100, 1.464655856975527900, - 1.464394688179792900, - 1.464133465542451200, 1.463872189073107500, 1.463610858781367900, - 1.463349474676840700, - 1.463088036769136600, 1.462826545067867700, 1.462564999582648600, - 1.462303400323095000, - 1.462041747298825900, 1.461780040519460800, 1.461518279994622200, - 1.461256465733934400, - 1.460994597747023600, 1.460732676043517800, 1.460470700633046800, - 1.460208671525243400, - 1.459946588729741100, 1.459684452256176300, 1.459422262114186800, - 1.459160018313412400, - 1.458897720863495500, 1.458635369774079500, 1.458372965054810700, - 1.458110506715337000, - 1.457847994765308200, 1.457585429214375700, 1.457322810072193800, - 1.457060137348418000, - 1.456797411052706200, 1.456534631194717800, 1.456271797784114900, - 1.456008910830560500, - 1.455745970343720800, 1.455482976333263100, 1.455219928808857200, - 1.454956827780174100, - 1.454693673256887600, 1.454430465248673300, 1.454167203765208000, - 1.453903888816171900, - 1.453640520411245900, 1.453377098560113100, 1.453113623272459100, - 1.452850094557971000, - 1.452586512426338000, 1.452322876887251400, 1.452059187950404100, - 1.451795445625491300, - 1.451531649922210200, 1.451267800850259500, 1.451003898419340500, - 1.450739942639155800, - 1.450475933519410400, 1.450211871069811300, 1.449947755300067500, - 1.449683586219889400, - 1.449419363838989800, 1.449155088167083600, 1.448890759213887100, - 1.448626376989119400, - 1.448361941502500900, 1.448097452763754000, 1.447832910782603100, - 1.447568315568775100, - 1.447303667131997900, 1.447038965482002200, 1.446774210628520200, - 1.446509402581286400, - 1.446244541350036700, 1.445979626944509300, 1.445714659374444500, - 1.445449638649584500, - 1.445184564779673500, 1.444919437774456700, 1.444654257643682900, - 1.444389024397101600, - 1.444123738044464900, 1.443858398595526400, 1.443593006060042100, - 1.443327560447769600, - 1.443062061768468400, 1.442796510031900500, 1.442530905247829200, - 1.442265247426020200, - 1.441999536576240800, 1.441733772708260600, 1.441467955831850800, - 1.441202085956784900, - 1.440936163092837900, 1.440670187249787600, 1.440404158437412500, - 1.440138076665494100, - 1.439871941943815300, 1.439605754282161400, 1.439339513690319100, - 1.439073220178077400, - 1.438806873755226900, 1.438540474431560600, 1.438274022216873500, - 1.438007517120961900, - 1.437740959153624500, 1.437474348324662100, 1.437207684643876800, - 1.436940968121073600, - 1.436674198766058500, 1.436407376588640000, 1.436140501598628400, - 1.435873573805835900, - 1.435606593220076600, 1.435339559851166500, 1.435072473708924000, - 1.434805334803169100, - 1.434538143143723200, 1.434270898740410700, 1.434003601603057300, - 1.433736251741490700, - 1.433468849165540500, 1.433201393885038500, 1.432933885909818000, - 1.432666325249714700, - 1.432398711914566200, 1.432131045914211600, 1.431863327258492400, - 1.431595555957251700, - 1.431327732020334800, 1.431059855457588600, 1.430791926278862400, - 1.430523944494007400, - 1.430255910112876000, 1.429987823145323100, 1.429719683601205800, - 1.429451491490382900, - 1.429183246822714800, 1.428914949608064200, 1.428646599856295400, - 1.428378197577275100, - 1.428109742780871800, 1.427841235476955400, 1.427572675675398600, - 1.427304063386075200, - 1.427035398618861500, 1.426766681383635500, 1.426497911690277000, - 1.426229089548668200, - 1.425960214968693000, 1.425691287960236600, 1.425422308533187200, - 1.425153276697434000, - 1.424884192462868800, 1.424615055839385300, 1.424345866836878200, - 1.424076625465245500, - 1.423807331734385800, 1.423537985654200800, 1.423268587234593400, - 1.422999136485468600, - 1.422729633416733200, 1.422460078038296300, 1.422190470360068300, - 1.421920810391962500, - 1.421651098143893000, 1.421381333625776600, 1.421111516847531700, - 1.420841647819078600, - 1.420571726550339700, 1.420301753051239400, 1.420031727331703800, - 1.419761649401660500, - 1.419491519271040000, 1.419221336949774100, 1.418951102447796800, - 1.418680815775043500, - 1.418410476941452100, 1.418140085956961900, 1.417869642831514700, - 1.417599147575054000, - 1.417328600197524900, 1.417058000708874700, 1.416787349119052600, - 1.416516645438009600, - 1.416245889675698900, 1.415975081842075300, 1.415704221947095700, - 1.415433310000718600, - 1.415162346012905000, 1.414891329993617200, 1.414620261952819600, - 1.414349141900479000, - 1.414077969846563500, 1.413806745801043500, 1.413535469773890700, - 1.413264141775079300, - 1.412992761814585400, 1.412721329902386900, 1.412449846048463600, - 1.412178310262796900, - 1.411906722555370500, 1.411635082936170100, 1.411363391415182900, - 1.411091648002398500, - 1.410819852707807700, 1.410548005541404100, 1.410276106513182400, - 1.410004155633139500, - 1.409732152911274500, 1.409460098357588200, 1.409187991982083100, - 1.408915833794763800, - 1.408643623805636800, 1.408371362024710500, 1.408099048461995300, - 1.407826683127503000, - 1.407554266031248100, 1.407281797183246500, 1.407009276593515800, - 1.406736704272076400, - 1.406464080228949600, 1.406191404474159000, 1.405918677017730100, - 1.405645897869690400, - 1.405373067040069300, 1.405100184538898000, 1.404827250376209400, - 1.404554264562038400, - 1.404281227106422400, 1.404008138019399800, 1.403734997311011600, - 1.403461804991300100, - 1.403188561070310100, 1.402915265558087700, 1.402641918464681400, - 1.402368519800141200, - 1.402095069574519800, 1.401821567797870300, 1.401548014480249000, - 1.401274409631713600, - 1.401000753262323900, 1.400727045382141400, 1.400453286001229800, - 1.400179475129653700, - 1.399905612777481200, 1.399631698954780800, 1.399357733671623900, - 1.399083716938083600, - 1.398809648764234100, 1.398535529160152400, 1.398261358135917300, - 1.397987135701609200, - 1.397712861867310300, 1.397438536643105000, 1.397164160039079200, - 1.396889732065321300, - 1.396615252731921100, 1.396340722048970300, 1.396066140026562800, - 1.395791506674794100, - 1.395516822003761700, 1.395242086023564800, 1.394967298744304900, - 1.394692460176085300, - 1.394417570329010700, 1.394142629213188000, 1.393867636838725900, - 1.393592593215735600, - 1.393317498354329300, 1.393042352264621600, 1.392767154956728400, - 1.392491906440768600, - 1.392216606726861800, 1.391941255825130100, 1.391665853745697400, - 1.391390400498689700, - 1.391114896094234100, 1.390839340542460600, 1.390563733853500200, - 1.390288076037486500, - 1.390012367104554600, 1.389736607064841100, 1.389460795928485500, - 1.389184933705628300, - 1.388909020406412100, 1.388633056040981600, 1.388357040619483200, - 1.388080974152065200, - 1.387804856648877600, 1.387528688120072600, 1.387252468575804100, - 1.386976198026228100, - 1.386699876481501900, 1.386423503951785200, 1.386147080447239600, - 1.385870605978028100, - 1.385594080554316100, 1.385317504186270900, 1.385040876884061000, - 1.384764198657857200, - 1.384487469517832200, 1.384210689474160600, 1.383933858537019100, - 1.383656976716585600, - 1.383380044023040400, 1.383103060466565300, 1.382826026057344600, - 1.382548940805563800, - 1.382271804721410600, 1.381994617815074400, 1.381717380096746800, - 1.381440091576620700, - 1.381162752264891500, 1.380885362171756300, 1.380607921307413400, - 1.380330429682064000, - 1.380052887305910400, 1.379775294189157000, 1.379497650342010400, - 1.379219955774678700, - 1.378942210497371600, 1.378664414520301500, 1.378386567853681700, - 1.378108670507728300, - 1.377830722492658500, 1.377552723818691500, 1.377274674496048700, - 1.376996574534953300, - 1.376718423945630000, 1.376440222738305700, 1.376161970923209400, - 1.375883668510570900, - 1.375605315510623200, 1.375326911933600200, 1.375048457789738400, - 1.374769953089275400, - 1.374491397842451100, 1.374212792059507100, 1.373934135750687100, - 1.373655428926236400, - 1.373376671596402400, 1.373097863771434200, 1.372819005461582500, - 1.372540096677100200, - 1.372261137428242300, 1.371982127725264800, 1.371703067578426700, - 1.371423956997988000, - 1.371144795994210500, 1.370865584577358300, 1.370586322757697500, - 1.370307010545495500, - 1.370027647951022100, 1.369748234984548000, 1.369468771656347200, - 1.369189257976694200, - 1.368909693955866000, 1.368630079604142000, 1.368350414931802000, - 1.368070699949128800, - 1.367790934666406600, 1.367511119093921800, 1.367231253241962200, - 1.366951337120818000, - 1.366671370740780500, 1.366391354112143500, 1.366111287245202400, - 1.365831170150254300, - 1.365551002837598600, 1.365270785317536100, 1.364990517600369400, - 1.364710199696403300, - 1.364429831615944200, 1.364149413369300600, 1.363868944966782900, - 1.363588426418702600, - 1.363307857735373900, 1.363027238927112300, 1.362746570004235400, - 1.362465850977062900, - 1.362185081855915600, 1.361904262651116900, 1.361623393372991300, - 1.361342474031866000, - 1.361061504638069400, 1.360780485201932300, 1.360499415733786400, - 1.360218296243966200, - 1.359937126742807300, 1.359655907240648000, 1.359374637747827700, - 1.359093318274687800, - 1.358811948831571500, 1.358530529428824400, 1.358249060076792900, - 1.357967540785826300, - 1.357685971566275200, 1.357404352428492000, 1.357122683382830900, - 1.356840964439648200, - 1.356559195609301700, 1.356277376902151900, 1.355995508328559500, - 1.355713589898888800, - 1.355431621623504700, 1.355149603512774400, 1.354867535577067200, - 1.354585417826753800, - 1.354303250272206500, 1.354021032923800300, 1.353738765791911100, - 1.353456448886917200, - 1.353174082219199100, 1.352891665799137900, 1.352609199637117500, - 1.352326683743523300, - 1.352044118128742600, 1.351761502803164900, 1.351478837777180700, - 1.351196123061183100, - 1.350913358665566400, 1.350630544600727200, 1.350347680877063800, - 1.350064767504976400, - 1.349781804494866600, 1.349498791857138400, 1.349215729602197400, - 1.348932617740450600, - 1.348649456282307700, 1.348366245238179500, 1.348082984618478800, - 1.347799674433620500, - 1.347516314694020800, 1.347232905410098200, 1.346949446592273100, - 1.346665938250967100, - 1.346382380396604000, 1.346098773039609700, 1.345815116190411300, - 1.345531409859438200, - 1.345247654057121700, 1.344963848793894200, 1.344679994080190800, - 1.344396089926448000, - 1.344112136343103900, 1.343828133340598800, 1.343544080929374800, - 1.343259979119875600, - 1.342975827922546600, 1.342691627347835500, 1.342407377406191500, - 1.342123078108065700, - 1.341838729463910900, 1.341554331484181600, 1.341269884179334700, - 1.340985387559828100, - 1.340700841636122400, 1.340416246418678800, 1.340131601917961900, - 1.339846908144436600, - 1.339562165108570700, 1.339277372820833400, 1.338992531291695500, - 1.338707640531629800, - 1.338422700551110900, 1.338137711360615200, 1.337852672970621300, - 1.337567585391608900, - 1.337282448634059800, 1.336997262708457900, 1.336712027625288600, - 1.336426743395039000, - 1.336141410028198500, 1.335856027535258000, 1.335570595926709700, - 1.335285115213048500, - 1.334999585404770700, 1.334714006512374400, 1.334428378546359500, - 1.334142701517227600, - 1.333856975435482300, 1.333571200311629100, 1.333285376156174700, - 1.332999502979628700, - 1.332713580792501500, 1.332427609605305400, 1.332141589428554900, - 1.331855520272766200, - 1.331569402148457400, 1.331283235066148100, 1.330997019036359800, - 1.330710754069615700, - 1.330424440176441300, 1.330138077367363200, 1.329851665652910500, - 1.329565205043613800, - 1.329278695550004700, 1.328992137182618100, 1.328705529951989400, - 1.328418873868656900, - 1.328132168943159800, 1.327845415186039000, 1.327558612607838500, - 1.327271761219102500, - 1.326984861030378000, 1.326697912052213500, 1.326410914295159400, - 1.326123867769767500, - 1.325836772486591800, 1.325549628456188100, 1.325262435689113600, - 1.324975194195928000, - 1.324687903987191900, 1.324400565073468300, 1.324113177465321900, - 1.323825741173318700, - 1.323538256208027800, 1.323250722580018500, 1.322963140299862500, - 1.322675509378133900, - 1.322387829825407700, 1.322100101652261100, 1.321812324869273500, - 1.321524499487024800, - 1.321236625516098100, 1.320948702967077400, 1.320660731850549000, - 1.320372712177100700, - 1.320084643957322400, 1.319796527201805300, 1.319508361921142500, - 1.319220148125929100, - 1.318931885826762000, 1.318643575034239800, 1.318355215758962900, - 1.318066808011533200, - 1.317778351802554800, 1.317489847142633300, 1.317201294042376300, - 1.316912692512393300, - 1.316624042563294900, 1.316335344205694200, 1.316046597450205800, - 1.315757802307445900, - 1.315468958788033000, 1.315180066902586800, 1.314891126661728900, - 1.314602138076083300, - 1.314313101156274800, 1.314024015912930600, 1.313734882356679900, - 1.313445700498152800, - 1.313156470347981900, 1.312867191916801100, 1.312577865215246900, - 1.312288490253956900, - 1.311999067043570200, 1.311709595594728000, 1.311420075918073900, - 1.311130508024252400, - 1.310840891923910100, 1.310551227627695400, 1.310261515146258200, - 1.309971754490250700, - 1.309681945670326400, 1.309392088697140900, 1.309102183581351200, - 1.308812230333616500, - 1.308522228964597500, 1.308232179484956500, 1.307942081905358000, - 1.307651936236467800, - 1.307361742488954300, 1.307071500673486800, 1.306781210800736200, - 1.306490872881376200, - 1.306200486926081700, 1.305910052945529200, 1.305619570950396800, - 1.305329040951365100, - 1.305038462959116100, 1.304747836984333300, 1.304457163037702200, - 1.304166441129910300, - 1.303875671271646400, 1.303584853473601200, 1.303293987746467300, - 1.303003074100939100, - 1.302712112547712800, 1.302421103097485900, 1.302130045760958100, - 1.301838940548830600, - 1.301547787471806900, 1.301256586540591600, 1.300965337765891600, - 1.300674041158414800, - 1.300382696728871400, 1.300091304487973800, 1.299799864446435200, - 1.299508376614971500, - 1.299216841004299200, 1.298925257625137800, 1.298633626488207500, - 1.298341947604231300, - 1.298050220983932900, 1.297758446638038700, 1.297466624577275900, - 1.297174754812374400, - 1.296882837354065100, 1.296590872213081200, 1.296298859400157700, - 1.296006798926030200, - 1.295714690801437600, 1.295422535037119800, 1.295130331643818500, - 1.294838080632277000, - 1.294545782013240900, 1.294253435797456900, 1.293961041995673700, - 1.293668600618642000, - 1.293376111677113900, 1.293083575181843500, 1.292790991143586200, - 1.292498359573099700, - 1.292205680481143500, 1.291912953878477900, 1.291620179775866400, - 1.291327358184073200, - 1.291034489113864100, 1.290741572576007400, 1.290448608581273000, - 1.290155597140431700, - 1.289862538264257700, 1.289569431963524900, 1.289276278249010600, - 1.288983077131493000, - 1.288689828621752300, 1.288396532730570400, 1.288103189468731400, - 1.287809798847019800, - 1.287516360876223500, 1.287222875567130900, 1.286929342930532800, - 1.286635762977221800, - 1.286342135717991600, 1.286048461163638000, 1.285754739324958900, - 1.285460970212753500, - 1.285167153837822900, 1.284873290210969900, 1.284579379342998700, - 1.284285421244715900, - 1.283991415926929400, 1.283697363400448900, 1.283403263676086100, - 1.283109116764654000, - 1.282814922676967400, 1.282520681423843000, 1.282226393016099500, - 1.281932057464557000, - 1.281637674780037100, 1.281343244973363700, 1.281048768055361900, - 1.280754244036858900, - 1.280459672928683500, 1.280165054741666300, 1.279870389486639400, - 1.279575677174437100, - 1.279280917815894600, 1.278986111421849900, 1.278691258003142000, - 1.278396357570611900, - 1.278101410135101800, 1.277806415707456700, 1.277511374298522200, - 1.277216285919146500, - 1.276921150580179200, 1.276625968292471000, 1.276330739066875400, - 1.276035462914247000, - 1.275740139845442400, 1.275444769871319600, 1.275149353002738700, - 1.274853889250561200, - 1.274558378625650200, 1.274262821138871300, 1.273967216801090900, - 1.273671565623178100, - 1.273375867616002300, 1.273080122790436000, 1.272784331157352800, - 1.272488492727628100, - 1.272192607512139300, 1.271896675521764900, 1.271600696767385400, - 1.271304671259883200, - 1.271008599010142500, 1.270712480029048800, 1.270416314327489800, - 1.270120101916354600, - 1.269823842806533800, 1.269527537008920300, 1.269231184534408200, - 1.268934785393893700, - 1.268638339598274500, 1.268341847158450200, 1.268045308085321800, - 1.267748722389792100, - 1.267452090082765900, 1.267155411175149500, 1.266858685677851000, - 1.266561913601780100, - 1.266265094957848000, 1.265968229756968100, 1.265671318010055400, - 1.265374359728026500, - 1.265077354921799300, 1.264780303602294200, 1.264483205780432700, - 1.264186061467138500, - 1.263888870673336400, 1.263591633409954000, 1.263294349687918800, - 1.262997019518161700, - 1.262699642911614600, 1.262402219879211300, 1.262104750431887000, - 1.261807234580578900, - 1.261509672336225600, 1.261212063709767900, 1.260914408712147800, - 1.260616707354309500, - 1.260318959647198400, 1.260021165601761900, 1.259723325228949000, - 1.259425438539710300, - 1.259127505544998600, 1.258829526255768000, 1.258531500682973800, - 1.258233428837574300, - 1.257935310730528000, 1.257637146372796400, 1.257338935775342200, - 1.257040678949129500, - 1.256742375905124400, 1.256444026654294400, 1.256145631207609400, - 1.255847189576040100, - 1.255548701770560000, 1.255250167802143000, 1.254951587681765600, - 1.254652961420405600, - 1.254354289029042900, 1.254055570518658500, 1.253756805900235700, - 1.253457995184759300, - 1.253159138383215200, 1.252860235506592100, 1.252561286565879300, - 1.252262291572068900, - 1.251963250536153500, 1.251664163469128300, 1.251365030381989700, - 1.251065851285736200, - 1.250766626191367500, 1.250467355109885500, 1.250168038052293500, - 1.249868675029596200, - 1.249569266052800800, 1.249269811132915200, 1.248970310280950200, - 1.248670763507917100, - 1.248371170824829300, 1.248071532242702100, 1.247771847772552300, - 1.247472117425398700, - 1.247172341212261500, 1.246872519144162300, 1.246572651232124700, - 1.246272737487174300, - 1.245972777920338000, 1.245672772542644400, 1.245372721365123600, - 1.245072624398807900, - 1.244772481654731000, 1.244472293143928300, 1.244172058877436800, - 1.243871778866295400, - 1.243571453121544000, 1.243271081654225400, 1.242970664475383100, - 1.242670201596062700, - 1.242369693027311200, 1.242069138780177400, 1.241768538865712000, - 1.241467893294967200, - 1.241167202078996800, 1.240866465228856100, 1.240565682755603100, - 1.240264854670295900, - 1.239963980983995300, 1.239663061707763700, 1.239362096852665300, - 1.239061086429765300, - 1.238760030450130900, 1.238458928924831600, 1.238157781864937400, - 1.237856589281521000, - 1.237555351185656500, 1.237254067588419400, 1.236952738500886900, - 1.236651363934138300, - 1.236349943899254000, 1.236048478407316500, 1.235746967469409900, - 1.235445411096619500, - 1.235143809300033300, 1.234842162090739700, 1.234540469479829900, - 1.234238731478396000, - 1.233936948097532400, 1.233635119348334400, 1.233333245241899200, - 1.233031325789326400, - 1.232729361001716500, 1.232427350890172000, 1.232125295465796600, - 1.231823194739696300, - 1.231521048722978200, 1.231218857426751700, 1.230916620862127400, - 1.230614339040217800, - 1.230312011972136500, 1.230009639668999500, 1.229707222141924100, - 1.229404759402029400, - 1.229102251460436400, 1.228799698328266700, 1.228497100016644900, - 1.228194456536696500, - 1.227891767899548700, 1.227589034116330700, 1.227286255198173100, - 1.226983431156208200, - 1.226680562001569900, 1.226377647745394000, 1.226074688398817600, - 1.225771683972980200, - 1.225468634479021500, 1.225165539928084300, 1.224862400331312400, - 1.224559215699851500, - 1.224255986044848500, 1.223952711377453100, 1.223649391708814700, - 1.223346027050086400, - 1.223042617412421600, 1.222739162806975900, 1.222435663244906700, - 1.222132118737372400, - 1.221828529295533800, 1.221524894930552800, 1.221221215653593100, - 1.220917491475820500, - 1.220613722408401900, 1.220309908462505800, 1.220006049649302800, - 1.219702145979964600, - 1.219398197465665400, 1.219094204117580300, 1.218790165946886100, - 1.218486082964761500, - 1.218181955182386500, 1.217877782610943700, 1.217573565261616000, - 1.217269303145589000, - 1.216964996274049400, 1.216660644658185600, 1.216356248309187600, - 1.216051807238247800, - 1.215747321456559300, 1.215442790975316700, 1.215138215805717300, - 1.214833595958959300, - 1.214528931446242600, 1.214224222278769100, 1.213919468467741900, - 1.213614670024366000, - 1.213309826959847700, 1.213004939285395400, 1.212700007012219100, - 1.212395030151530300, - 1.212090008714541600, 1.211784942712468300, 1.211479832156526800, - 1.211174677057934800, - 1.210869477427912300, 1.210564233277680500, 1.210258944618462200, - 1.209953611461482200, - 1.209648233817966600, 1.209342811699143600, 1.209037345116242400, - 1.208731834080493800, - 1.208426278603131200, 1.208120678695388600, 1.207815034368502100, - 1.207509345633709600, - 1.207203612502250300, 1.206897834985365000, 1.206592013094296200, - 1.206286146840288300, - 1.205980236234587100, 1.205674281288440000, 1.205368282013096200, - 1.205062238419806200, - 1.204756150519822300, 1.204450018324398900, 1.204143841844791200, - 1.203837621092256800, - 1.203531356078054100, 1.203225046813444000, 1.202918693309688300, - 1.202612295578050900, - 1.202305853629797500, 1.201999367476194400, 1.201692837128510700, - 1.201386262598016500, - 1.201079643895983700, 1.200772981033685800, 1.200466274022397900, - 1.200159522873396800, - 1.199852727597960700, 1.199545888207369700, 1.199239004712905300, - 1.198932077125851100, - 1.198625105457491700, 1.198318089719113200, 1.198011029922004400, - 1.197703926077454200, - 1.197396778196754700, 1.197089586291198500, 1.196782350372080300, - 1.196475070450696100, - 1.196167746538343600, 1.195860378646322700, 1.195552966785933900, - 1.195245510968480300, - 1.194938011205265900, 1.194630467507596500, 1.194322879886780000, - 1.194015248354125100, - 1.193707572920943000, 1.193399853598545500, 1.193092090398246900, - 1.192784283331362700, - 1.192476432409210100, 1.192168537643107900, 1.191860599044376500, - 1.191552616624337800, - 1.191244590394315400, 1.190936520365635000, 1.190628406549622900, - 1.190320248957608100, - 1.190012047600920200, 1.189703802490891000, 1.189395513638853900, - 1.189087181056143900, - 1.188778804754097300, 1.188470384744052100, 1.188161921037348400, - 1.187853413645327100, - 1.187544862579331500, 1.187236267850706000, 1.186927629470796900, - 1.186618947450951600, - 1.186310221802519900, 1.186001452536852300, 1.185692639665301600, - 1.185383783199222000, - 1.185074883149969100, 1.184765939528900500, 1.184456952347374900, - 1.184147921616753200, - 1.183838847348397400, 1.183529729553671500, 1.183220568243940300, - 1.182911363430571200, - 1.182602115124932900, 1.182292823338395100, 1.181983488082330300, - 1.181674109368111300, - 1.181364687207113100, 1.181055221610712400, 1.180745712590287400, - 1.180436160157217800, - 1.180126564322885100, 1.179816925098671900, 1.179507242495962900, - 1.179197516526144600, - 1.178887747200604300, 1.178577934530731700, 1.178268078527917200, - 1.177958179203553800, - 1.177648236569035300, 1.177338250635757700, 1.177028221415118200, - 1.176718148918515700, - 1.176408033157350300, 1.176097874143024600, 1.175787671886942000, - 1.175477426400507700, - 1.175167137695128900, 1.174856805782213500, 1.174546430673171900, - 1.174236012379415600, - 1.173925550912357800, 1.173615046283413200, 1.173304498503998400, - 1.172993907585530900, - 1.172683273539430800, 1.172372596377118800, 1.172061876110017700, - 1.171751112749551900, - 1.171440306307147200, 1.171129456794231200, 1.170818564222232800, - 1.170507628602582800, - 1.170196649946713100, 1.169885628266057900, 1.169574563572052300, - 1.169263455876133200, - 1.168952305189739200, 1.168641111524310700, 1.168329874891289400, - 1.168018595302118000, - 1.167707272768241800, 1.167395907301107100, 1.167084498912162300, - 1.166773047612856400, - 1.166461553414641000, 1.166150016328968600, 1.165838436367293800, - 1.165526813541072100, - 1.165215147861761400, 1.164903439340820900, 1.164591687989710500, - 1.164279893819892800, - 1.163968056842831700, 1.163656177069992500, 1.163344254512841800, - 1.163032289182848800, - 1.162720281091483000, 1.162408230250216100, 1.162096136670521600, - 1.161784000363874000, - 1.161471821341749900, 1.161159599615627000, 1.160847335196984800, - 1.160535028097304600, - 1.160222678328068700, 1.159910285900761700, 1.159597850826869200, - 1.159285373117878500, - 1.158972852785278500, 1.158660289840559800, 1.158347684295214300, - 1.158035036160735900, - 1.157722345448619400, 1.157409612170361600, 1.157096836337461000, - 1.156784017961417500, - 1.156471157053732300, 1.156158253625908700, 1.155845307689450800, - 1.155532319255865300, - 1.155219288336659400, 1.154906214943342700, 1.154593099087426000, - 1.154279940780421400, - 1.153966740033842900, 1.153653496859206000, 1.153340211268028000, - 1.153026883271827300, - 1.152713512882124400, 1.152400100110440700, 1.152086644968299400, - 1.151773147467225300, - 1.151459607618745300, 1.151146025434387000, 1.150832400925680100, - 1.150518734104155400, - 1.150205024981345800, 1.149891273568785400, 1.149577479878009800, - 1.149263643920556800, - 1.148949765707964600, 1.148635845251773800, 1.148321882563526400, - 1.148007877654766200, - 1.147693830537038100, 1.147379741221888500, 1.147065609720865600, - 1.146751436045519300, - 1.146437220207400700, 1.146122962218062600, 1.145808662089060000, - 1.145494319831947800, - 1.145179935458284100, 1.144865508979627800, 1.144551040407539400, - 1.144236529753581000, - 1.143921977029316500, 1.143607382246310600, 1.143292745416130600, - 1.142978066550344400, - 1.142663345660522000, 1.142348582758234900, 1.142033777855056000, - 1.141718930962559500, - 1.141404042092321500, 1.141089111255919800, 1.140774138464933700, - 1.140459123730943200, - 1.140144067065530700, 1.139828968480280300, 1.139513827986776900, - 1.139198645596607400, - 1.138883421321360600, 1.138568155172625700, 1.138252847161994400, - 1.137937497301059600, - 1.137622105601416000, 1.137306672074659900, 1.136991196732388200, - 1.136675679586200500, - 1.136360120647697200, 1.136044519928480800, 1.135728877440154800, - 1.135413193194324800, - 1.135097467202597100, 1.134781699476580300, 1.134465890027884300, - 1.134150038868120500, - 1.133834146008902100, 1.133518211461843200, 1.133202235238559800, - 1.132886217350669500, - 1.132570157809791500, 1.132254056627546300, 1.131937913815556300, - 1.131621729385444900, - 1.131305503348837300, 1.130989235717360100, 1.130672926502642100, - 1.130356575716312500, - 1.130040183370002900, 1.129723749475346000, 1.129407274043976200, - 1.129090757087529500, - 1.128774198617643200, 1.128457598645956600, 1.128140957184109700, - 1.127824274243744500, - 1.127507549836505000, 1.127190783974035800, 1.126873976667983800, - 1.126557127929996800, - 1.126240237771724700, 1.125923306204818400, 1.125606333240930700, - 1.125289318891715900, - 1.124972263168829500, 1.124655166083928800, 1.124338027648672500, - 1.124020847874721100, - 1.123703626773736100, 1.123386364357381200, 1.123069060637320600, - 1.122751715625221400, - 1.122434329332750800, 1.122116901771578400, 1.121799432953375600, - 1.121481922889814300, - 1.121164371592568300, 1.120846779073313400, 1.120529145343726500, - 1.120211470415486200, - 1.119893754300272300, 1.119575997009766300, 1.119258198555651300, - 1.118940358949611900, - 1.118622478203333800, 1.118304556328505200, 1.117986593336814700, - 1.117668589239953200, - 1.117350544049612300, 1.117032457777486200, 1.116714330435269600, - 1.116396162034659600, - 1.116077952587353600, 1.115759702105052000, 1.115441410599455500, - 1.115123078082267000, - 1.114804704565190500, 1.114486290059931900, 1.114167834578198200, - 1.113849338131698300, - 1.113530800732142100, 1.113212222391241500, 1.112893603120710000, - 1.112574942932261600, - 1.112256241837613000, 1.111937499848481900, 1.111618716976587700, - 1.111299893233650600, - 1.110981028631393700, 1.110662123181539900, 1.110343176895814500, - 1.110024189785944900, - 1.109705161863658600, 1.109386093140686000, 1.109066983628758100, - 1.108747833339607200, - 1.108428642284968100, 1.108109410476576300, 1.107790137926169200, - 1.107470824645485600, - 1.107151470646265300, 1.106832075940250600, 1.106512640539184100, - 1.106193164454811100, - 1.105873647698877300, 1.105554090283131100, 1.105234492219321100, - 1.104914853519198400, - 1.104595174194514800, 1.104275454257024300, 1.103955693718482200, - 1.103635892590644900, - 1.103316050885270600, 1.102996168614119000, 1.102676245788951400, - 1.102356282421530300, - 1.102036278523620000, 1.101716234106985700, 1.101396149183395000, - 1.101076023764616400, - 1.100755857862419700, 1.100435651488577100, 1.100115404654861100, - 1.099795117373046200, - 1.099474789654909100, 1.099154421512226600, 1.098834012956778200, - 1.098513564000344300, - 1.098193074654706800, 1.097872544931649100, 1.097551974842956500, - 1.097231364400415000, - 1.096910713615813200, 1.096590022500939700, 1.096269291067585700, - 1.095948519327543800, - 1.095627707292607700, 1.095306854974572800, 1.094985962385235800, - 1.094665029536395100, - 1.094344056439850600, 1.094023043107403200, 1.093701989550856000, - 1.093380895782013000, - 1.093059761812680100, 1.092738587654664300, 1.092417373319774200, - 1.092096118819820200, - 1.091774824166613600, 1.091453489371968100, 1.091132114447697300, - 1.090810699405617900, - 1.090489244257547300, 1.090167749015304300, 1.089846213690709900, - 1.089524638295585400, - 1.089203022841754400, 1.088881367341041800, 1.088559671805274100, - 1.088237936246279100, - 1.087916160675885800, 1.087594345105925300, 1.087272489548229700, - 1.086950594014632700, - 1.086628658516969500, 1.086306683067076900, 1.085984667676792600, - 1.085662612357956500, - 1.085340517122409800, 1.085018381981994500, 1.084696206948555300, - 1.084373992033937000, - 1.084051737249986900, 1.083729442608553300, 1.083407108121486000, - 1.083084733800636200, - 1.082762319657857100, 1.082439865705002500, 1.082117371953928300, - 1.081794838416491700, - 1.081472265104551200, 1.081149652029967000, 1.080826999204601100, - 1.080504306640315500, - 1.080181574348975500, 1.079858802342446900, 1.079535990632596800, - 1.079213139231294500, - 1.078890248150409700, 1.078567317401815100, 1.078244346997383300, - 1.077921336948988600, - 1.077598287268508400, 1.077275197967819000, 1.076952069058800400, - 1.076628900553332700, - 1.076305692463297900, 1.075982444800579700, 1.075659157577062200, - 1.075335830804633000, - 1.075012464495178800, 1.074689058660589700, 1.074365613312755900, - 1.074042128463569500, - 1.073718604124924500, 1.073395040308715400, 1.073071437026839500, - 1.072747794291194300, - 1.072424112113678600, 1.072100390506194500, 1.071776629480643500, - 1.071452829048929800, - 1.071128989222958500, 1.070805110014635900, 1.070481191435870500, - 1.070157233498571600, - 1.069833236214650800, 1.069509199596019800, 1.069185123654592600, - 1.068861008402285200, - 1.068536853851013600, 1.068212660012696700, 1.067888426899253500, - 1.067564154522606000, - 1.067239842894676100, 1.066915492027387600, 1.066591101932666800, - 1.066266672622439700, - 1.065942204108635300, 1.065617696403183400, 1.065293149518014500, - 1.064968563465062100, - 1.064643938256259400, 1.064319273903543000, 1.063994570418849400, - 1.063669827814116300, - 1.063345046101285000, 1.063020225292295300, 1.062695365399091200, - 1.062370466433616400, - 1.062045528407815900, 1.061720551333637600, 1.061395535223029500, - 1.061070480087941800, - 1.060745385940325500, 1.060420252792134000, 1.060095080655320900, - 1.059769869541841800, - 1.059444619463654400, 1.059119330432716700, 1.058794002460989000, - 1.058468635560432500, - 1.058143229743009600, 1.057817785020685100, 1.057492301405424500, - 1.057166778909195000, - 1.056841217543965200, 1.056515617321704500, 1.056189978254385100, - 1.055864300353978900, - 1.055538583632461100, 1.055212828101807200, 1.054887033773993300, - 1.054561200660999200, - 1.054235328774803900, 1.053909418127389400, 1.053583468730738200, - 1.053257480596834700, - 1.052931453737664600, 1.052605388165214700, 1.052279283891473600, - 1.051953140928431100, - 1.051626959288079100, 1.051300738982409800, 1.050974480023417500, - 1.050648182423098000, - 1.050321846193448000, 1.049995471346466300, 1.049669057894152800, - 1.049342605848508200, - 1.049016115221536000, 1.048689586025239700, 1.048363018271625300, - 1.048036411972699500, - 1.047709767140470500, 1.047383083786948700, 1.047056361924144400, - 1.046729601564071200, - 1.046402802718742400, 1.046075965400174300, 1.045749089620383200, - 1.045422175391386800, - 1.045095222725206200, 1.044768231633861100, 1.044441202129375200, - 1.044114134223771900, - 1.043787027929076000, 1.043459883257315400, 1.043132700220517300, - 1.042805478830712200, - 1.042478219099930400, 1.042150921040204200, 1.041823584663568200, - 1.041496209982056600, - 1.041168797007707000, 1.040841345752557200, 1.040513856228645800, - 1.040186328448014800, - 1.039858762422705600, 1.039531158164762400, 1.039203515686230000, - 1.038875834999155100, - 1.038548116115585800, 1.038220359047570500, 1.037892563807160800, - 1.037564730406408200, - 1.037236858857366600, 1.036908949172090900, 1.036581001362636600, - 1.036253015441062700, - 1.035924991419427100, 1.035596929309791300, 1.035268829124216700, - 1.034940690874766300, - 1.034612514573505700, 1.034284300232500000, 1.033956047863817500, - 1.033627757479526700, - 1.033299429091697700, 1.032971062712402700, 1.032642658353714300, - 1.032314216027707700, - 1.031985735746457900, 1.031657217522042900, 1.031328661366541300, - 1.031000067292032300, - 1.030671435310598600, 1.030342765434322200, 1.030014057675287900, - 1.029685312045581100, - 1.029356528557288300, 1.029027707222499100, 1.028698848053302100, - 1.028369951061789600, - 1.028041016260053500, 1.027712043660187600, 1.027383033274288400, - 1.027053985114451100, - 1.026724899192775300, 1.026395775521359500, 1.026066614112305600, - 1.025737414977715200, - 1.025408178129692000, 1.025078903580341600, 1.024749591341769700, - 1.024420241426085200, - 1.024090853845396800, 1.023761428611814600, 1.023431965737451800, - 1.023102465234420700, - 1.022772927114837100, 1.022443351390816400, 1.022113738074476300, - 1.021784087177936000, - 1.021454398713315600, 1.021124672692737000, 1.020794909128323000, - 1.020465108032198300, - 1.020135269416488700, 1.019805393293321100, 1.019475479674824900, - 1.019145528573129000, - 1.018815540000365800, 1.018485513968667500, 1.018155450490168000, - 1.017825349577003300, - 1.017495211241309800, 1.017165035495226400, 1.016834822350892300, - 1.016504571820448000, - 1.016174283916036800, 1.015843958649801600, 1.015513596033888400, - 1.015183196080442900, - 1.014852758801613200, 1.014522284209548900, 1.014191772316400000, - 1.013861223134318900, - 1.013530636675459100, 1.013200012951974700, 1.012869351976022300, - 1.012538653759758900, - 1.012207918315344300, 1.011877145654937400, 1.011546335790700600, - 1.011215488734796800, - 1.010884604499389800, 1.010553683096645900, 1.010222724538731600, - 1.009891728837815700, - 1.009560696006067900, 1.009229626055658800, 1.008898518998761800, - 1.008567374847549900, - 1.008236193614199000, 1.007904975310885300, 1.007573719949786700, - 1.007242427543082900, - 1.006911098102953900, 1.006579731641582500, 1.006248328171152100, - 1.005916887703846500, - 1.005585410251852700, 1.005253895827357800, 1.004922344442551000, - 1.004590756109621900, - 1.004259130840762700, 1.003927468648166100, 1.003595769544025900, - 1.003264033540538500, - 1.002932260649900000, 1.002600450884309800, 1.002268604255967200, - 1.001936720777072400, - 1.001604800459829000, 1.001272843316440000, 1.000940849359111000, - 1.000608818600048100, - 1.000276751051459200, 0.999944646725553720, 0.999612505634541740, - 0.999280327790635690, - 0.998948113206048590, 0.998615861892994560, 0.998283573863690270, - 0.997951249130352380, - 0.997618887705200020, 0.997286489600452630, 0.996954054828332210, - 0.996621583401061110, - 0.996289075330862860, 0.995956530629963810, 0.995623949310589620, - 0.995291331384969390, - 0.994958676865332010, 0.994625985763907820, 0.994293258092929790, - 0.993960493864630480, - 0.993627693091245660, 0.993294855785010760, 0.992961981958163210, - 0.992629071622942340, - 0.992296124791587690, 0.991963141476341460, 0.991630121689446090, - 0.991297065443145440, - 0.990963972749685840, 0.990630843621313260, 0.990297678070276800, - 0.989964476108825210, - 0.989631237749210020, 0.989297963003683330, 0.988964651884498000, - 0.988631304403909890, - 0.988297920574174430, 0.987964500407549910, 0.987631043916294970, - 0.987297551112669370, - 0.986964022008935520, 0.986630456617355380, 0.986296854950194260, - 0.985963217019717120, - 0.985629542838190490, 0.985295832417883540, 0.984962085771065030, - 0.984628302910006580, - 0.984294483846980150, 0.983960628594258810, 0.983626737164118190, - 0.983292809568833910, - 0.982958845820684270, 0.982624845931947320, 0.982290809914904140, - 0.981956737781835790, - 0.981622629545024770, 0.981288485216756160, 0.980954304809314670, - 0.980620088334987930, - 0.980285835806063770, 0.979951547234831130, 0.979617222633581860, - 0.979282862014607240, - 0.978948465390201530, 0.978614032772659240, 0.978279564174275860, - 0.977945059607349900, - 0.977610519084179290, 0.977275942617064740, 0.976941330218307540, - 0.976606681900209830, - 0.976271997675076550, 0.975937277555212310, 0.975602521552924600, - 0.975267729680520560, - 0.974932901950310350, 0.974598038374604350, 0.974263138965714040, - 0.973928203735953460, - 0.973593232697636530, 0.973258225863079970, 0.972923183244600480, - 0.972588104854516410, - 0.972252990705148370, 0.971917840808816710, 0.971582655177844700, - 0.971247433824555920, - 0.970912176761274950, 0.970576884000329040, 0.970241555554045230, - 0.969906191434753320, - 0.969570791654783330, 0.969235356226466500, 0.968899885162136650, - 0.968564378474127350, - 0.968228836174775060, 0.967893258276415700, 0.967557644791388500, - 0.967221995732032490, - 0.966886311110688230, 0.966550590939698640, 0.966214835231406500, - 0.965879043998157160, - 0.965543217252296420, 0.965207355006171270, 0.964871457272131190, - 0.964535524062525410, - 0.964199555389706030, 0.963863551266025300, 0.963527511703836660, - 0.963191436715496120, - 0.962855326313359350, 0.962519180509785130, 0.962182999317132030, - 0.961846782747760140, - 0.961510530814032040, 0.961174243528309820, 0.960837920902958720, - 0.960501562950343390, - 0.960165169682831830, 0.959828741112791590, 0.959492277252591900, - 0.959155778114604400, - 0.958819243711200310, 0.958482674054753960, 0.958146069157639560, - 0.957809429032232760, - 0.957472753690911670, 0.957136043146054050, 0.956799297410040440, - 0.956462516495251940, - 0.956125700414070300, 0.955788849178880300, 0.955451962802066120, - 0.955115041296014880, - 0.954778084673113870, 0.954441092945751630, 0.954104066126319150, - 0.953767004227207060, - 0.953429907260809120, 0.953092775239518630, 0.952755608175731570, - 0.952418406081844360, - 0.952081168970254520, 0.951743896853362140, 0.951406589743566950, - 0.951069247653271500, - 0.950731870594878510, 0.950394458580791970, 0.950057011623418380, - 0.949719529735163940, - 0.949382012928437600, 0.949044461215648560, 0.948706874609207220, - 0.948369253121526420, - 0.948031596765018910, 0.947693905552099870, 0.947356179495185020, - 0.947018418606691230, - 0.946680622899037650, 0.946342792384643360, 0.946004927075930090, - 0.945667026985319680, - 0.945329092125236190, 0.944991122508104350, 0.944653118146349890, - 0.944315079052401090, - 0.943977005238685770, 0.943638896717634900, 0.943300753501679190, - 0.942962575603250920, - 0.942624363034784580, 0.942286115808714690, 0.941947833937478270, - 0.941609517433512730, - 0.941271166309256450, 0.940932780577150460, 0.940594360249635500, - 0.940255905339155150, - 0.939917415858152920, 0.939578891819073720, 0.939240333234364950, - 0.938901740116473540, - 0.938563112477849630, 0.938224450330942590, 0.937885753688204820, - 0.937547022562088990, - 0.937208256965048840, 0.936869456909540490, 0.936530622408019990, - 0.936191753472946030, - 0.935852850116777430, 0.935513912351974450, 0.935174940190999560, - 0.934835933646314900, - 0.934496892730385720, 0.934157817455677160, 0.933818707834655590, - 0.933479563879790030, - 0.933140385603548840, 0.932801173018403480, 0.932461926136825660, - 0.932122644971287830, - 0.931783329534265240, 0.931443979838232900, 0.931104595895668410, - 0.930765177719049210, - 0.930425725320855430, 0.930086238713567440, 0.929746717909666790, - 0.929407162921637610, - 0.929067573761963250, 0.928727950443130500, 0.928388292977625930, - 0.928048601377937210, - 0.927708875656554800, 0.927369115825968480, 0.927029321898671270, - 0.926689493887155820, - 0.926349631803916270, 0.926009735661449170, 0.925669805472250860, - 0.925329841248820340, - 0.924989843003656610, 0.924649810749260110, 0.924309744498133750, - 0.923969644262779830, - 0.923629510055703820, 0.923289341889410480, 0.922949139776407800, - 0.922608903729203570, - 0.922268633760306990, 0.921928329882229390, 0.921587992107482210, - 0.921247620448579440, - 0.920907214918035070, 0.920566775528364410, 0.920226302292085460, - 0.919885795221715540, - 0.919545254329774850, 0.919204679628783720, 0.918864071131263780, - 0.918523428849739030, - 0.918182752796733110, 0.917842042984772340, 0.917501299426383480, - 0.917160522134094160, - 0.916819711120434700, 0.916478866397934850, 0.916137987979127270, - 0.915797075876544350, - 0.915456130102721200, 0.915115150670193110, 0.914774137591496510, - 0.914433090879170130, - 0.914092010545752620, 0.913750896603785280, 0.913409749065809520, - 0.913068567944367970, - 0.912727353252005710, 0.912386105001267270, 0.912044823204700370, - 0.911703507874852440, - 0.911362159024272310, 0.911020776665511290, 0.910679360811120000, - 0.910337911473652390, - 0.909996428665661990, 0.909654912399703860, 0.909313362688335290, - 0.908971779544113350, - 0.908630162979597760, 0.908288513007348140, 0.907946829639926790, - 0.907605112889895870, - 0.907263362769819000, 0.906921579292262250, 0.906579762469791110, - 0.906237912314974080, - 0.905896028840379560, 0.905554112058577170, 0.905212161982139160, - 0.904870178623637170, - 0.904528161995645670, 0.904186112110739510, 0.903844028981494190, - 0.903501912620488070, - 0.903159763040298880, 0.902817580253507450, 0.902475364272694370, - 0.902133115110441470, - 0.901790832779333250, 0.901448517291953520, 0.901106168660889110, - 0.900763786898726380, - 0.900421372018054500, 0.900078924031462610, 0.899736442951541320, - 0.899393928790883420, - 0.899051381562081310, 0.898708801277730340, 0.898366187950425780, - 0.898023541592764210, - 0.897680862217344440, 0.897338149836764960, 0.896995404463627350, - 0.896652626110532870, - 0.896309814790084090, 0.895966970514885940, 0.895624093297543110, - 0.895281183150662960, - 0.894938240086852970, 0.894595264118721810, 0.894252255258880410, - 0.893909213519939460, - 0.893566138914512420, 0.893223031455212530, 0.892879891154655380, - 0.892536718025457090, - 0.892193512080234670, 0.891850273331607600, 0.891507001792195000, - 0.891163697474618880, - 0.890820360391500920, 0.890476990555464480, 0.890133587979135000, - 0.889790152675137610, - 0.889446684656100330, 0.889103183934650930, 0.888759650523418650, - 0.888416084435035060, - 0.888072485682131150, 0.887728854277341050, 0.887385190233298650, - 0.887041493562639060, - 0.886697764277999840, 0.886354002392018110, 0.886010207917333760, - 0.885666380866586560, - 0.885322521252418610, 0.884978629087472270, 0.884634704384391180, - 0.884290747155821230, - 0.883946757414407980, 0.883602735172799640, 0.883258680443644530, - 0.882914593239592320, - 0.882570473573294660, 0.882226321457403320, 0.881882136904572400, - 0.881537919927456340, - 0.881193670538710450, 0.880849388750992610, 0.880505074576960370, - 0.880160728029273920, - 0.879816349120593590, 0.879471937863580690, 0.879127494270899090, - 0.878783018355212220, - 0.878438510129186170, 0.878093969605486800, 0.877749396796782770, - 0.877404791715742370, - 0.877060154375035710, 0.876715484787334630, 0.876370782965310900, - 0.876026048921639160, - 0.875681282668993700, 0.875336484220050390, 0.874991653587487090, - 0.874646790783981660, - 0.874301895822214290, 0.873956968714865500, 0.873612009474616810, - 0.873267018114152300, - 0.872921994646155390, 0.872576939083312460, 0.872231851438309840, - 0.871886731723835020, - 0.871541579952577750, 0.871196396137227660, 0.870851180290476810, - 0.870505932425017060, - 0.870160652553543020, 0.869815340688749220, 0.869469996843331370, - 0.869124621029987670, - 0.868779213261415610, 0.868433773550315810, 0.868088301909388680, - 0.867742798351335720, - 0.867397262888861100, 0.867051695534668210, 0.866706096301463340, - 0.866360465201952980, - 0.866014802248844420, 0.865669107454847490, 0.865323380832671800, - 0.864977622395029290, - 0.864631832154632240, 0.864286010124194040, 0.863940156316430170, - 0.863594270744056040, - 0.863248353419789670, 0.862902404356348570, 0.862556423566453230, - 0.862210411062823810, - 0.861864366858181910, 0.861518290965251340, 0.861172183396755500, - 0.860826044165420630, - 0.860479873283972910, 0.860133670765139580, 0.859787436621650360, - 0.859441170866234390, - 0.859094873511623840, 0.858748544570550610, 0.858402184055747750, - 0.858055791979950740, - 0.857709368355894840, 0.857362913196317630, 0.857016426513956930, - 0.856669908321551650, - 0.856323358631843170, 0.855976777457572280, 0.855630164811482460, - 0.855283520706317080, - 0.854936845154821930, 0.854590138169742830, 0.854243399763827020, - 0.853896629949823630, - 0.853549828740481690, 0.853202996148552880, 0.852856132186788910, - 0.852509236867942440, - 0.852162310204768740, 0.851815352210022470, 0.851468362896461110, - 0.851121342276842110, - 0.850774290363923820, 0.850427207170467380, 0.850080092709233130, - 0.849732946992984290, - 0.849385770034483680, 0.849038561846496730, 0.848691322441788910, - 0.848344051833126780, - 0.847996750033279350, 0.847649417055015060, 0.847302052911105160, - 0.846954657614320980, - 0.846607231177434640, 0.846259773613221020, 0.845912284934454140, - 0.845564765153910990, - 0.845217214284368690, 0.844869632338605130, 0.844522019329400630, - 0.844174375269535320, - 0.843826700171791620, 0.843478994048952440, 0.843131256913801420, - 0.842783488779124570, - 0.842435689657707650, 0.842087859562339000, 0.841739998505806610, - 0.841392106500900900, - 0.841044183560412770, 0.840696229697133760, 0.840348244923857960, - 0.840000229253379030, - 0.839652182698493290, 0.839304105271996950, 0.838955996986687550, - 0.838607857855364740, - 0.838259687890827830, 0.837911487105878820, 0.837563255513319780, - 0.837214993125953600, - 0.836866699956585690, 0.836518376018021260, 0.836170021323067610, - 0.835821635884532730, - 0.835473219715225040, 0.835124772827955830, 0.834776295235535540, - 0.834427786950777460, - 0.834079247986494690, 0.833730678355502630, 0.833382078070616820, - 0.833033447144653880, - 0.832684785590432690, 0.832336093420771970, 0.831987370648492710, - 0.831638617286416190, - 0.831289833347364620, 0.830941018844162600, 0.830592173789634240, - 0.830243298196606360, - 0.829894392077905720, 0.829545455446360270, 0.829196488314800080, - 0.828847490696055010, - 0.828498462602957340, 0.828149404048339590, 0.827800315045035150, - 0.827451195605879990, - 0.827102045743709160, 0.826752865471360950, 0.826403654801672770, - 0.826054413747485010, - 0.825705142321637720, 0.825355840536972420, 0.825006508406332490, - 0.824657145942561230, - 0.824307753158504460, 0.823958330067008030, 0.823608876680918760, - 0.823259393013085820, - 0.822909879076357930, 0.822560334883586490, 0.822210760447622980, - 0.821861155781319800, - 0.821511520897531660, 0.821161855809112830, 0.820812160528920360, - 0.820462435069811090, - 0.820112679444643060, 0.819762893666276530, 0.819413077747571440, - 0.819063231701390170, - 0.818713355540594880, 0.818363449278050270, 0.818013512926620940, - 0.817663546499172720, - 0.817313550008573640, 0.816963523467691410, 0.816613466889396070, - 0.816263380286557980, - 0.815913263672048310, 0.815563117058740630, 0.815212940459508210, - 0.814862733887226740, - 0.814512497354771830, 0.814162230875020380, 0.813811934460851430, - 0.813461608125143560, - 0.813111251880778150, 0.812760865740636440, 0.812410449717600570, - 0.812060003824555230, - 0.811709528074384460, 0.811359022479975040, 0.811008487054213360, - 0.810657921809988410, - 0.810307326760189020, 0.809956701917705080, 0.809606047295428950, - 0.809255362906252440, - 0.808904648763069890, 0.808553904878775760, 0.808203131266265420, - 0.807852327938436750, - 0.807501494908186900, 0.807150632188415760, 0.806799739792023240, - 0.806448817731910130, - 0.806097866020979660, 0.805746884672134620, 0.805395873698280360, - 0.805044833112322000, - 0.804693762927166100, 0.804342663155721230, 0.803991533810895500, - 0.803640374905599810, - 0.803289186452744390, 0.802937968465242240, 0.802586720956006250, - 0.802235443937950320, - 0.801884137423990890, 0.801532801427043530, 0.801181435960026780, - 0.800830041035858750, - 0.800478616667459010, 0.800127162867749210, 0.799775679649650460, - 0.799424167026086540, - 0.799072625009981330, 0.798721053614259490, 0.798369452851848020, - 0.798017822735673680, - 0.797666163278665570, 0.797314474493752810, 0.796962756393865600, - 0.796611008991936490, - 0.796259232300897350, 0.795907426333682830, 0.795555591103226930, - 0.795203726622466520, - 0.794851832904338360, 0.794499909961779990, 0.794147957807731400, - 0.793795976455132220, - 0.793443965916924570, 0.793091926206050400, 0.792739857335452710, - 0.792387759318077150, - 0.792035632166868230, 0.791683475894773720, 0.791331290514740830, - 0.790979076039718180, - 0.790626832482656310, 0.790274559856505520, 0.789922258174218570, - 0.789569927448748320, - 0.789217567693048520, 0.788865178920075130, 0.788512761142783790, - 0.788160314374132590, - 0.787807838627079260, 0.787455333914584220, 0.787102800249607550, - 0.786750237645110430, - 0.786397646114056490, 0.786045025669408700, 0.785692376324132690, - 0.785339698091194080, - 0.784986990983559170, 0.784634255014197040, 0.784281490196075850, - 0.783928696542166680, - 0.783575874065440270, 0.783223022778868350, 0.782870142695425320, - 0.782517233828084580, - 0.782164296189822530, 0.781811329793615120, 0.781458334652439630, - 0.781105310779275470, - 0.780752258187101480, 0.780399176888899150, 0.780046066897649550, - 0.779692928226336290, - 0.779339760887942880, 0.778986564895453810, 0.778633340261856040, - 0.778280087000135730, - 0.777926805123281830, 0.777573494644283050, 0.777220155576129220, - 0.776866787931812410, - 0.776513391724324210, 0.776159966966658680, 0.775806513671809860, - 0.775453031852772920, - 0.775099521522545020, 0.774745982694123090, 0.774392415380506400, - 0.774038819594694230, - 0.773685195349686940, 0.773331542658487140, 0.772977861534096640, - 0.772624151989520280, - 0.772270414037761980, 0.771916647691828660, 0.771562852964726710, - 0.771209029869463940, - 0.770855178419050050, 0.770501298626494410, 0.770147390504808960, - 0.769793454067005500, - 0.769439489326096850, 0.769085496295098040, 0.768731474987023660, - 0.768377425414890850, - 0.768023347591716640, 0.767669241530518850, 0.767315107244318060, - 0.766960944746133740, - 0.766606754048988260, 0.766252535165903970, 0.765898288109903900, - 0.765544012894013530, - 0.765189709531257760, 0.764835378034664170, 0.764481018417259680, - 0.764126630692073870, - 0.763772214872136200, 0.763417770970477140, 0.763063299000129260, - 0.762708798974124800, - 0.762354270905498450, 0.761999714807284790, 0.761645130692519490, - 0.761290518574240350, - 0.760935878465484720, 0.760581210379292380, 0.760226514328703140, - 0.759871790326757670, - 0.759517038386499090, 0.759162258520969860, 0.758807450743214760, - 0.758452615066278920, - 0.758097751503208020, 0.757742860067050380, 0.757387940770853360, - 0.757032993627667290, - 0.756678018650541630, 0.756323015852528700, 0.755967985246680520, - 0.755612926846050080, - 0.755257840663692730, 0.754902726712663120, 0.754547585006018600, - 0.754192415556816380, - 0.753837218378114460, 0.753481993482973400, 0.753126740884452970, - 0.752771460595615500, - 0.752416152629523330, 0.752060816999239660, 0.751705453717829930, - 0.751350062798359140, - 0.750994644253894730, 0.750639198097504010, 0.750283724342255320, - 0.749928223001219310, - 0.749572694087465850, 0.749217137614067500, 0.748861553594096340, - 0.748505942040627040, - 0.748150302966733790, 0.747794636385492150, 0.747438942309979870, - 0.747083220753273820, - 0.746727471728453770, 0.746371695248599140, 0.746015891326790470, - 0.745660059976110400, - 0.745304201209641030, 0.744948315040467210, 0.744592401481673270, - 0.744236460546344850, - 0.743880492247569580, 0.743524496598434670, 0.743168473612029980, - 0.742812423301444810, - 0.742456345679769810, 0.742100240760097840, 0.741744108555520860, - 0.741387949079133860, - 0.741031762344030790, 0.740675548363308620, 0.740319307150063780, - 0.739963038717393880, - 0.739606743078398690, 0.739250420246177380, 0.738894070233831800, - 0.738537693054463370, - 0.738181288721174830, 0.737824857247070810, 0.737468398645255490, - 0.737111912928835710, - 0.736755400110918000, 0.736398860204609870, 0.736042293223021060, - 0.735685699179260850, - 0.735329078086440880, 0.734972429957672760, 0.734615754806068890, - 0.734259052644744230, - 0.733902323486812610, 0.733545567345390890, 0.733188784233595240, - 0.732831974164544150, - 0.732475137151356370, 0.732118273207151170, 0.731761382345050280, - 0.731404464578174760, - 0.731047519919648340, 0.730690548382594280, 0.730333549980137110, - 0.729976524725403530, - 0.729619472631519270, 0.729262393711613280, 0.728905287978813600, - 0.728548155446249730, - 0.728190996127053180, 0.727833810034354990, 0.727476597181288540, - 0.727119357580987220, - 0.726762091246585200, 0.726404798191218950, 0.726047478428024420, - 0.725690131970139980, - 0.725332758830703360, 0.724975359022855150, 0.724617932559735390, - 0.724260479454485130, - 0.723902999720247850, 0.723545493370166160, 0.723187960417385530, - 0.722830400875050790, - 0.722472814756308090, 0.722115202074305680, 0.721757562842191060, - 0.721399897073114470, - 0.721042204780225960, 0.720684485976676230, 0.720326740675618530, - 0.719968968890205230, - 0.719611170633591480, 0.719253345918932090, 0.718895494759382860, - 0.718537617168101610, - 0.718179713158245800, 0.717821782742975370, 0.717463825935449550, - 0.717105842748830160, - 0.716747833196278770, 0.716389797290958090, 0.716031735046032900, - 0.715673646474667140, - 0.715315531590027700, 0.714957390405280950, 0.714599222933594240, - 0.714241029188137260, - 0.713882809182079030, 0.713524562928591010, 0.713166290440844450, - 0.712807991732011590, - 0.712449666815266890, 0.712091315703784260, 0.711732938410739810, - 0.711374534949309800, - 0.711016105332671340, 0.710657649574003460, 0.710299167686484930, - 0.709940659683296890, - 0.709582125577619790, 0.709223565382636760, 0.708864979111530680, - 0.708506366777485130, - 0.708147728393686340, 0.707789063973319310, 0.707430373529572170, - 0.707071657075632460, - 0.706712914624688770, 0.706354146189931750, 0.705995351784551530, - 0.705636531421740880, - 0.705277685114692020, 0.704918812876598410, 0.704559914720655490, - 0.704200990660058150, - 0.703842040708003820, 0.703483064877689630, 0.703124063182313690, - 0.702765035635076310, - 0.702405982249177160, 0.702046903037818250, 0.701687798014201110, - 0.701328667191529980, - 0.700969510583008600, 0.700610328201841660, 0.700251120061236020, - 0.699891886174398130, - 0.699532626554536630, 0.699173341214860190, 0.698814030168578240, - 0.698454693428902320, - 0.698095331009043640, 0.697735942922215520, 0.697376529181631400, - 0.697017089800505250, - 0.696657624792053730, 0.696298134169492380, 0.695938617946039510, - 0.695579076134912990, - 0.695219508749331800, 0.694859915802517050, 0.694500297307689140, - 0.694140653278070950, - 0.693780983726884790, 0.693421288667355530, 0.693061568112707690, - 0.692701822076166820, - 0.692342050570960430, 0.691982253610315510, 0.691622431207461700, - 0.691262583375628180, - 0.690902710128045050, 0.690542811477944610, 0.690182887438558710, - 0.689822938023121220, - 0.689462963244866330, 0.689102963117028790, 0.688742937652845550, - 0.688382886865552930, - 0.688022810768389670, 0.687662709374594510, 0.687302582697406850, - 0.686942430750068330, - 0.686582253545819920, 0.686222051097905130, 0.685861823419566700, - 0.685501570524050140, - 0.685141292424600310, 0.684780989134463280, 0.684420660666887120, - 0.684060307035119440, - 0.683699928252410110, 0.683339524332008840, 0.682979095287166160, - 0.682618641131135020, - 0.682258161877167370, 0.681897657538517720, 0.681537128128440470, - 0.681176573660190910, - 0.680815994147026320, 0.680455389602203310, 0.680094760038981280, - 0.679734105470619080, - 0.679373425910376310, 0.679012721371515250, 0.678651991867297080, - 0.678291237410985510, - 0.677930458015843620, 0.677569653695137220, 0.677208824462131490, - 0.676847970330092700, - 0.676487091312289350, 0.676126187421989040, 0.675765258672461950, - 0.675404305076978020, - 0.675043326648808170, 0.674682323401225250, 0.674321295347501510, - 0.673960242500911690, - 0.673599164874730370, 0.673238062482232950, 0.672876935336696900, - 0.672515783451398950, - 0.672154606839618470, 0.671793405514634180, 0.671432179489727110, - 0.671070928778178090, - 0.670709653393269050, 0.670348353348283690, 0.669987028656505170, - 0.669625679331219300, - 0.669264305385711360, 0.668902906833267590, 0.668541483687176590, - 0.668180035960725840, - 0.667818563667205600, 0.667457066819905800, 0.667095545432117240, - 0.666733999517132860, - 0.666372429088244790, 0.666010834158747840, 0.665649214741936390, - 0.665287570851105680, - 0.664925902499553190, 0.664564209700575500, 0.664202492467472090, - 0.663840750813541210, - 0.663478984752084110, 0.663117194296401260, 0.662755379459794350, - 0.662393540255567070, - 0.662031676697022450, 0.661669788797465960, 0.661307876570202740, - 0.660945940028538900, - 0.660583979185782600, 0.660221994055241400, 0.659859984650225110, - 0.659497950984043510, - 0.659135893070007080, 0.658773810921428500, 0.658411704551619570, - 0.658049573973894850, - 0.657687419201568260, 0.657325240247955020, 0.656963037126372160, - 0.656600809850135910, - 0.656238558432565400, 0.655876282886978410, 0.655513983226695960, - 0.655151659465038060, - 0.654789311615326050, 0.654426939690883280, 0.654064543705032310, - 0.653702123671098150, - 0.653339679602405470, 0.652977211512280050, 0.652614719414049580, - 0.652252203321041060, - 0.651889663246583930, 0.651527099204007310, 0.651164511206641320, - 0.650801899267818060, - 0.650439263400868990, 0.650076603619127890, 0.649713919935928420, - 0.649351212364604910, - 0.648988480918494040, 0.648625725610931460, 0.648262946455255510, - 0.647900143464803730, - 0.647537316652916140, 0.647174466032932490, 0.646811591618193350, - 0.646448693422041360, - 0.646085771457818310, 0.645722825738868860, 0.645359856278536980, - 0.644996863090167570, - 0.644633846187107620, 0.644270805582703550, 0.643907741290304040, - 0.643544653323257610, - 0.643181541694913480, 0.642818406418622980, 0.642455247507736860, - 0.642092064975608220, - 0.641728858835589830, 0.641365629101035340, 0.641002375785300500, - 0.640639098901740200, - 0.640275798463712080, 0.639912474484572560, 0.639549126977681070, - 0.639185755956396480, - 0.638822361434078330, 0.638458943424088490, 0.638095501939787920, - 0.637732036994540290, - 0.637368548601708660, 0.637005036774657030, 0.636641501526751590, - 0.636277942871357530, - 0.635914360821842830, 0.635550755391574910, 0.635187126593922070, - 0.634823474442254840, - 0.634459798949942640, 0.634096100130357660, 0.633732377996871770, - 0.633368632562857470, - 0.633004863841689520, 0.632641071846741790, 0.632277256591390780, - 0.631913418089012020, - 0.631549556352983710, 0.631185671396683470, 0.630821763233490040, - 0.630457831876783950, - 0.630093877339945260, 0.629729899636356280, 0.629365898779399080, - 0.629001874782456500, - 0.628637827658913300, 0.628273757422153860, 0.627909664085564810, - 0.627545547662532230, - 0.627181408166443410, 0.626817245610687520, 0.626453060008652860, - 0.626088851373730380, - 0.625724619719310480, 0.625360365058784670, 0.624996087405546350, - 0.624631786772988030, - 0.624267463174504880, 0.623903116623491180, 0.623538747133343780, - 0.623174354717459190, - 0.622809939389234460, 0.622445501162069090, 0.622081040049361490, - 0.621716556064512820, - 0.621352049220923570, 0.620987519531995270, 0.620622967011131400, - 0.620258391671734690, - 0.619893793527210410, 0.619529172590963410, 0.619164528876399280, - 0.618799862396925750, - 0.618435173165949760, 0.618070461196880800, 0.617705726503127720, - 0.617340969098100430, - 0.616976188995210780, 0.616611386207870040, 0.616246560749491690, - 0.615881712633488340, - 0.615516841873275490, 0.615151948482267840, 0.614787032473881110, - 0.614422093861533010, - 0.614057132658640590, 0.613692148878623000, 0.613327142534899510, - 0.612962113640889710, - 0.612597062210015750, 0.612231988255698470, 0.611866891791361560, - 0.611501772830428060, - 0.611136631386322020, 0.610771467472469460, 0.610406281102295440, - 0.610041072289227990, - 0.609675841046694030, 0.609310587388121830, 0.608945311326941520, - 0.608580012876582370, - 0.608214692050476290, 0.607849348862054220, 0.607483983324749510, - 0.607118595451995420, - 0.606753185257225550, 0.606387752753876020, 0.606022297955381760, - 0.605656820875180360, - 0.605291321526709060, 0.604925799923405670, 0.604560256078710220, - 0.604194690006061960, - 0.603829101718902580, 0.603463491230673220, 0.603097858554815790, - 0.602732203704774650, - 0.602366526693992930, 0.602000827535916330, 0.601635106243990190, - 0.601269362831660550, - 0.600903597312375640, 0.600537809699582810, 0.600172000006731770, - 0.599806168247271620, - 0.599440314434653620, 0.599074438582328780, 0.598708540703749010, - 0.598342620812368000, - 0.597976678921638860, 0.597610715045016950, 0.597244729195957500, - 0.596878721387916090, - 0.596512691634350830, 0.596146639948718640, 0.595780566344478960, - 0.595414470835091030, - 0.595048353434014630, 0.594682214154711790, 0.594316053010643270, - 0.593949870015273000, - 0.593583665182063740, 0.593217438524479500, 0.592851190055986300, - 0.592484919790049140, - 0.592118627740135460, 0.591752313919712170, 0.591385978342248260, - 0.591019621021212420, - 0.590653241970074180, 0.590286841202305120, 0.589920418731375800, - 0.589553974570759530, - 0.589187508733928890, 0.588821021234357310, 0.588454512085520460, - 0.588087981300892900, - 0.587721428893951850, 0.587354854878173850, 0.586988259267036350, - 0.586621642074019120, - 0.586255003312600500, 0.585888342996261690, 0.585521661138483250, - 0.585154957752746730, - 0.584788232852535560, 0.584421486451332410, 0.584054718562622140, - 0.583687929199888990, - 0.583321118376619710, 0.582954286106300290, 0.582587432402417840, - 0.582220557278461340, - 0.581853660747918780, 0.581486742824280810, 0.581119803521037650, - 0.580752842851679940, - 0.580385860829700780, 0.580018857468592270, 0.579651832781848730, - 0.579284786782964360, - 0.578917719485433800, 0.578550630902754050, 0.578183521048421080, - 0.577816389935933090, - 0.577449237578788300, 0.577082063990485340, 0.576714869184524860, - 0.576347653174406840, - 0.575980415973633590, 0.575613157595706530, 0.575245878054129520, - 0.574878577362406000, - 0.574511255534040030, 0.574143912582537940, 0.573776548521405030, - 0.573409163364148930, - 0.573041757124277180, 0.572674329815297640, 0.572306881450720390, - 0.571939412044054740, - 0.571571921608812320, 0.571204410158504090, 0.570836877706642270, - 0.570469324266740570, - 0.570101749852312100, 0.569734154476872480, 0.569366538153936560, - 0.568998900897020210, - 0.568631242719641270, 0.568263563635316600, 0.567895863657565500, - 0.567528142799906490, - 0.567160401075860410, 0.566792638498947680, 0.566424855082689470, - 0.566057050840608870, - 0.565689225786228160, 0.565321379933072190, 0.564953513294665140, - 0.564585625884531870, - 0.564217717716199550, 0.563849788803194140, 0.563481839159044150, - 0.563113868797277870, - 0.562745877731423820, 0.562377865975012940, 0.562009833541575080, - 0.561641780444642640, - 0.561273706697747450, 0.560905612314422150, 0.560537497308201240, - 0.560169361692618440, - 0.559801205481210040, 0.559433028687510990, 0.559064831325059240, - 0.558696613407391630, - 0.558328374948046320, 0.557960115960563050, 0.557591836458480870, - 0.557223536455341280, - 0.556855215964685120, 0.556486875000054000, 0.556118513574991650, - 0.555750131703040880, - 0.555381729397746880, 0.555013306672654360, 0.554644863541308600, - 0.554276400017257090, - 0.553907916114046440, 0.553539411845225590, 0.553170887224342820, - 0.552802342264947400, - 0.552433776980590490, 0.552065191384822350, 0.551696585491195710, - 0.551327959313262280, - 0.550959312864576220, 0.550590646158691240, 0.550221959209161620, - 0.549853252029543830, - 0.549484524633393480, 0.549115777034268170, 0.548747009245725500, - 0.548378221281323520, - 0.548009413154622370, 0.547640584879181100, 0.547271736468561530, - 0.546902867936324590, - 0.546533979296032200, 0.546165070561248080, 0.545796141745535150, - 0.545427192862458780, - 0.545058223925583670, 0.544689234948475210, 0.544320225944701200, - 0.543951196927828010, - 0.543582147911424560, 0.543213078909059120, 0.542843989934301940, - 0.542474881000723050, - 0.542105752121893050, 0.541736603311384620, 0.541367434582769480, - 0.540998245949621760, - 0.540629037425515050, 0.540259809024023600, 0.539890560758723770, - 0.539521292643190930, - 0.539152004691002770, 0.538782696915736770, 0.538413369330970610, - 0.538044021950284450, - 0.537674654787257180, 0.537305267855470390, 0.536935861168504670, - 0.536566434739941920, - 0.536196988583365510, 0.535827522712358230, 0.535458037140505110, - 0.535088531881390050, - 0.534719006948599860, 0.534349462355720230, 0.533979898116337950, - 0.533610314244041710, - 0.533240710752419080, 0.532871087655060300, 0.532501444965554960, - 0.532131782697493170, - 0.531762100864467290, 0.531392399480068670, 0.531022678557890980, - 0.530652938111527360, - 0.530283178154571710, 0.529913398700619820, 0.529543599763266700, - 0.529173781356109600, - 0.528803943492745180, 0.528434086186771010, 0.528064209451786560, - 0.527694313301390160, - 0.527324397749182720, 0.526954462808764120, 0.526584508493736840, - 0.526214534817702310, - 0.525844541794263210, 0.525474529437023890, 0.525104497759587900, - 0.524734446775560910, - 0.524364376498548390, 0.523994286942156220, 0.523624178119992400, - 0.523254050045663940, - 0.522883902732780290, 0.522513736194950230, 0.522143550445783310, - 0.521773345498891090, - 0.521403121367884030, 0.521032878066375100, 0.520662615607976660, - 0.520292334006301820, - 0.519922033274965560, 0.519551713427582000, 0.519181374477767470, - 0.518811016439137520, - 0.518440639325310040, 0.518070243149902240, 0.517699827926532130, - 0.517329393668819580, - 0.516958940390383700, 0.516588468104845820, 0.516217976825826600, - 0.515847466566947580, - 0.515476937341832310, 0.515106389164103120, 0.514735822047384990, - 0.514365236005302040, - 0.513994631051479240, 0.513624007199543600, 0.513253364463121090, - 0.512882702855839920, - 0.512512022391327980, 0.512141323083213470, 0.511770604945127050, - 0.511399867990697920, - 0.511029112233557960, 0.510658337687338040, 0.510287544365671140, - 0.509916732282189920, - 0.509545901450527690, 0.509175051884319660, 0.508804183597200140, - 0.508433296602805670, - 0.508062390914772230, 0.507691466546736580, 0.507320523512337470, - 0.506949561825212450, - 0.506578581499001590, 0.506207582547344550, 0.505836564983881190, - 0.505465528822253710, - 0.505094474076103310, 0.504723400759073290, 0.504352308884806750, - 0.503981198466947000, - 0.503610069519139780, 0.503238922055029400, 0.502867756088262840, - 0.502496571632486070, - 0.502125368701347050, 0.501754147308493770, 0.501382907467574190, - 0.501011649192238950, - 0.500640372496137020, 0.500269077392920150, 0.499897763896239410, - 0.499526432019746450, - 0.499155081777094940, 0.498783713181937540, 0.498412326247929250, - 0.498040920988724490, - 0.497669497417978280, 0.497298055549347750, 0.496926595396488870, - 0.496555116973059980, - 0.496183620292718900, 0.495812105369124070, 0.495440572215935850, - 0.495069020846813650, - 0.494697451275419140, 0.494325863515413130, 0.493954257580458580, - 0.493582633484217940, - 0.493210991240354450, 0.492839330862533120, 0.492467652364417970, - 0.492095955759675460, - 0.491724241061971320, 0.491352508284972070, 0.490980757442346090, - 0.490608988547760690, - 0.490237201614885710, 0.489865396657390210, 0.489493573688943970, - 0.489121732723218740, - 0.488749873773885120, 0.488377996854616250, 0.488006101979084450, - 0.487634189160962910, - 0.487262258413926560, 0.486890309751649490, 0.486518343187807900, - 0.486146358736077200, - 0.485774356410135000, 0.485402336223658360, 0.485030298190324950, - 0.484658242323814380, - 0.484286168637805270, 0.483914077145978560, 0.483541967862014480, - 0.483169840799594130, - 0.482797695972400300, 0.482425533394114920, 0.482053353078422120, - 0.481681155039005550, - 0.481308939289549380, 0.480936705843739820, 0.480564454715261990, - 0.480192185917803270, - 0.479819899465050160, 0.479447595370691370, 0.479075273648415010, - 0.478702934311909910, - 0.478330577374866780, 0.477958202850975230, 0.477585810753927250, - 0.477213401097414220, - 0.476840973895128200, 0.476468529160763100, 0.476096066908011760, - 0.475723587150569390, - 0.475351089902130650, 0.474978575176390750, 0.474606042987046840, - 0.474233493347795020, - 0.473860926272333670, 0.473488341774360670, 0.473115739867574380, - 0.472743120565675250, - 0.472370483882362520, 0.471997829831337810, 0.471625158426301700, - 0.471252469680957190, - 0.470879763609006460, 0.470507040224152460, 0.470134299540099940, - 0.469761541570552780, - 0.469388766329217000, 0.469015973829798090, 0.468643164086002100, - 0.468270337111537040, - 0.467897492920109850, 0.467524631525429830, 0.467151752941205530, - 0.466778857181146260, - 0.466405944258963200, 0.466033014188366350, 0.465660066983068220, - 0.465287102656780530, - 0.464914121223215740, 0.464541122696088100, 0.464168107089110940, - 0.463795074415999760, - 0.463422024690469060, 0.463048957926235630, 0.462675874137015720, - 0.462302773336526080, - 0.461929655538485470, 0.461556520756611410, 0.461183369004623920, - 0.460810200296242310, - 0.460437014645186440, 0.460063812065178160, 0.459690592569938270, - 0.459317356173189750, - 0.458944102888655060, 0.458570832730057170, 0.458197545711121090, - 0.457824241845570630, - 0.457450921147131930, 0.457077583629530550, 0.456704229306492570, - 0.456330858191746010, - 0.455957470299017840, 0.455584065642037350, 0.455210644234532610, - 0.454837206090234200, - 0.454463751222871910, 0.454090279646176210, 0.453716791373879380, - 0.453343286419712720, - 0.452969764797409750, 0.452596226520703360, 0.452222671603327130, - 0.451849100059016350, - 0.451475511901505420, 0.451101907144530910, 0.450728285801828830, - 0.450354647887135640, - 0.449980993414189900, 0.449607322396728900, 0.449233634848492320, - 0.448859930783219170, - 0.448486210214649020, 0.448112473156523420, 0.447738719622582710, - 0.447364949626569590, - 0.446991163182225700, 0.446617360303294910, 0.446243541003520480, - 0.445869705296646270, - 0.445495853196417930, 0.445121984716580210, 0.444748099870879880, - 0.444374198673063330, - 0.444000281136877280, 0.443626347276070590, 0.443252397104390790, - 0.442878430635587910, - 0.442504447883411090, 0.442130448861610240, 0.441756433583937120, - 0.441382402064142250, - 0.441008354315978680, 0.440634290353198510, 0.440260210189554690, - 0.439886113838801880, - 0.439512001314693700, 0.439137872630986080, 0.438763727801433690, - 0.438389566839793740, - 0.438015389759822630, 0.437641196575277220, 0.437266987299916590, - 0.436892761947498260, - 0.436518520531782470, 0.436144263066528480, 0.435769989565496290, - 0.435395700042447710, - 0.435021394511143410, 0.434647072985346380, 0.434272735478819010, - 0.433898382005324050, - 0.433524012578626440, 0.433149627212489670, 0.432775225920679740, - 0.432400808716961900, - 0.432026375615101930, 0.431651926628867530, 0.431277461772025310, - 0.430902981058344070, - 0.430528484501591540, 0.430153972115537800, 0.429779443913952170, - 0.429404899910604490, - 0.429030340119266550, 0.428655764553708960, 0.428281173227704760, - 0.427906566155026040, - 0.427531943349445720, 0.427157304824738350, 0.426782650594677570, - 0.426407980673039090, - 0.426033295073598160, 0.425658593810130330, 0.425283876896413280, - 0.424909144346223290, - 0.424534396173339160, 0.424159632391538870, 0.423784853014600950, - 0.423410058056305830, - 0.423035247530432810, 0.422660421450763490, 0.422285579831078230, - 0.421910722685159720, - 0.421535850026790060, 0.421160961869751720, 0.420786058227829220, - 0.420411139114805770, - 0.420036204544466940, 0.419661254530597550, 0.419286289086983070, - 0.418911308227410740, - 0.418536311965666650, 0.418161300315539220, 0.417786273290816130, - 0.417411230905285650, - 0.417036173172737830, 0.416661100106961610, 0.416286011721748230, - 0.415910908030888200, - 0.415535789048172620, 0.415160654787394280, 0.414785505262345030, - 0.414410340486818910, - 0.414035160474608700, 0.413659965239509710, 0.413284754795316230, - 0.412909529155823300, - 0.412534288334827750, 0.412159032346125280, 0.411783761203513790, - 0.411408474920790520, - 0.411033173511753220, 0.410657856990201580, 0.410282525369933980, - 0.409907178664751180, - 0.409531816888453190, 0.409156440054840590, 0.408781048177715660, - 0.408405641270879690, - 0.408030219348136270, 0.407654782423288010, 0.407279330510138260, - 0.406903863622492260, - 0.406528381774153900, 0.406152884978929480, 0.405777373250624070, - 0.405401846603045010, - 0.405026305049998980, 0.404650748605293040, 0.404275177282736260, - 0.403899591096136380, - 0.403523990059303620, 0.403148374186047210, 0.402772743490177110, - 0.402397097985504990, - 0.402021437685841480, 0.401645762604999350, 0.401270072756790610, - 0.400894368155027990, - 0.400518648813525830, 0.400142914746097480, 0.399767165966558420, - 0.399391402488723400, - 0.399015624326407800, 0.398639831493428740, 0.398264024003602220, - 0.397888201870746420, - 0.397512365108678430, 0.397136513731217500, 0.396760647752182230, - 0.396384767185391620, - 0.396008872044666730, 0.395632962343827170, 0.395257038096694990, - 0.394881099317091370, - 0.394505146018838130, 0.394129178215758820, 0.393753195921675850, - 0.393377199150413860, - 0.393001187915796750, 0.392625162231649010, 0.392249122111796800, - 0.391873067570065240, - 0.391496998620281590, 0.391120915276272410, 0.390744817551864850, - 0.390368705460887750, - 0.389992579017168830, 0.389616438234538010, 0.389240283126824070, - 0.388864113707858060, - 0.388487929991470140, 0.388111731991491180, 0.387735519721753690, - 0.387359293196089140, - 0.386983052428331030, 0.386606797432312350, 0.386230528221866430, - 0.385854244810828530, - 0.385477947213032580, 0.385101635442314900, 0.384725309512510880, - 0.384348969437456610, - 0.383972615230989860, 0.383596246906947210, 0.383219864479167560, - 0.382843467961488940, - 0.382467057367749940, 0.382090632711791060, 0.381714194007451380, - 0.381337741268572390, - 0.380961274508994250, 0.380584793742559550, 0.380208298983109930, - 0.379831790244487540, - 0.379455267540536490, 0.379078730885099520, 0.378702180292021630, - 0.378325615775147170, - 0.377949037348320800, 0.377572445025389230, 0.377195838820197690, - 0.376819218746593910, - 0.376442584818424570, 0.376065937049537060, 0.375689275453780500, - 0.375312600045002780, - 0.374935910837054080, 0.374559207843783660, 0.374182491079041500, - 0.373805760556679190, - 0.373429016290547200, 0.373052258294498230, 0.372675486582383640, - 0.372298701168057190, - 0.371921902065371730, 0.371545089288180640, 0.371168262850339210, - 0.370791422765701320, - 0.370414569048123140, 0.370037701711460170, 0.369660820769568240, - 0.369283926236305070, - 0.368907018125527120, 0.368530096451093140, 0.368153161226860980, - 0.367776212466689010, - 0.367399250184437480, 0.367022274393965340, 0.366645285109133750, - 0.366268282343803150, - 0.365891266111834370, 0.365514236427090080, 0.365137193303431750, - 0.364760136754723020, - 0.364383066794826350, 0.364005983437606320, 0.363628886696926890, - 0.363251776586652310, - 0.362874653120648700, 0.362497516312780990, 0.362120366176916230, - 0.361743202726920790, - 0.361366025976661450, 0.360988835940006750, 0.360611632630824020, - 0.360234416062982840, - 0.359857186250351960, 0.359479943206800550, 0.359102686946199680, - 0.358725417482419150, - 0.358348134829330870, 0.357970839000806010, 0.357593530010716310, - 0.357216207872935120, - 0.356838872601334680, 0.356461524209789380, 0.356084162712172360, - 0.355706788122359060, - 0.355329400454223950, 0.354951999721642100, 0.354574585938490280, - 0.354197159118644080, - 0.353819719275981330, 0.353442266424378930, 0.353064800577714280, - 0.352687321749866610, - 0.352309829954713830, 0.351932325206136210, 0.351554807518012990, - 0.351177276904224070, - 0.350799733378650890, 0.350422176955173910, 0.350044607647675640, - 0.349667025470037810, - 0.349289430436142520, 0.348911822559873850, 0.348534201855114360, - 0.348156568335749040, - 0.347778922015661520, 0.347401262908737570, 0.347023591028862320, - 0.346645906389921150, - 0.346268209005801410, 0.345890498890388980, 0.345512776057572080, - 0.345135040521238170, - 0.344757292295274910, 0.344379531393571970, 0.344001757830017680, - 0.343623971618502560, - 0.343246172772916250, 0.342868361307148980, 0.342490537235092600, - 0.342112700570637750, - 0.341734851327677280, 0.341356989520103240, 0.340979115161808070, - 0.340601228266685980, - 0.340223328848629880, 0.339845416921535030, 0.339467492499295200, - 0.339089555595806560, - 0.338711606224964210, 0.338333644400663940, 0.337955670136803170, - 0.337577683447278010, - 0.337199684345986910, 0.336821672846827290, 0.336443648963697160, - 0.336065612710496290, - 0.335687564101123050, 0.335309503149478110, 0.334931429869461230, - 0.334553344274972690, - 0.334175246379914470, 0.333797136198187240, 0.333419013743693980, - 0.333040879030336690, - 0.332662732072017800, 0.332284572882641680, 0.331906401476111280, - 0.331528217866331690, - 0.331150022067206780, 0.330771814092642610, 0.330393593956544440, - 0.330015361672817750, - 0.329637117255370090, 0.329258860718107450, 0.328880592074938190, - 0.328502311339769700, - 0.328124018526509800, 0.327745713649068180, 0.327367396721353070, - 0.326989067757275040, - 0.326610726770743760, 0.326232373775669270, 0.325854008785963320, - 0.325475631815536570, - 0.325097242878301660, 0.324718841988170470, 0.324340429159055250, - 0.323962004404870050, - 0.323583567739527570, 0.323205119176942720, 0.322826658731029110, - 0.322448186415702550, - 0.322069702244877910, 0.321691206232470550, 0.321312698392397570, - 0.320934178738574720, - 0.320555647284919980, 0.320177104045350440, 0.319798549033783570, - 0.319419982264138650, - 0.319041403750333630, 0.318662813506288670, 0.318284211545923010, - 0.317905597883156250, - 0.317526972531909870, 0.317148335506103940, 0.316769686819660780, - 0.316391026486501690, - 0.316012354520548600, 0.315633670935725030, 0.315254975745953180, - 0.314876268965157470, - 0.314497550607261090, 0.314118820686189180, 0.313740079215866160, - 0.313361326210216840, - 0.312982561683167790, 0.312603785648644220, 0.312224998120573420, - 0.311846199112882030, - 0.311467388639496860, 0.311088566714346650, 0.310709733351358600, - 0.310330888564462340, - 0.309952032367586390, 0.309573164774659850, 0.309194285799613390, - 0.308815395456376430, - 0.308436493758880660, 0.308057580721056660, 0.307678656356835560, - 0.307299720680150270, - 0.306920773704932260, 0.306541815445115160, 0.306162845914631390, - 0.305783865127415400, - 0.305404873097400780, 0.305025869838521590, 0.304646855364713530, - 0.304267829689911010, - 0.303888792828050650, 0.303509744793068030, 0.303130685598899270, - 0.302751615259482190, - 0.302372533788753170, 0.301993441200650910, 0.301614337509113100, - 0.301235222728077840, - 0.300856096871485010, 0.300476959953273060, 0.300097811987382670, - 0.299718652987753580, - 0.299339482968325970, 0.298960301943041680, 0.298581109925841300, - 0.298201906930667390, - 0.297822692971461410, 0.297443468062166820, 0.297064232216726120, - 0.296684985449082390, - 0.296305727773180260, 0.295926459202963120, 0.295547179752376430, - 0.295167889435364820, - 0.294788588265873170, 0.294409276257848300, 0.294029953425235520, - 0.293650619781982260, - 0.293271275342035120, 0.292891920119341120, 0.292512554127848930, - 0.292133177381505850, - 0.291753789894261320, 0.291374391680063520, 0.290994982752862730, - 0.290615563126608250, - 0.290236132815249790, 0.289856691832738880, 0.289477240193025510, - 0.289097777910061970, - 0.288718304997799550, 0.288338821470189910, 0.287959327341186510, - 0.287579822624741350, - 0.287200307334808670, 0.286820781485341620, 0.286441245090293950, - 0.286061698163620930, - 0.285682140719276560, 0.285302572771216960, 0.284922994333397350, - 0.284543405419773240, - 0.284163806044301910, 0.283784196220939370, 0.283404575963643550, - 0.283024945286371230, - 0.282645304203081090, 0.282265652727731130, 0.281885990874279570, - 0.281506318656686290, - 0.281126636088910030, 0.280746943184911340, 0.280367239958650150, - 0.279987526424086530, - 0.279607802595182420, 0.279228068485898210, 0.278848324110196550, - 0.278468569482039130, - 0.278088804615388040, 0.277709029524206950, 0.277329244222458250, - 0.276949448724106480, - 0.276569643043115150, 0.276189827193448200, 0.275810001189071290, - 0.275430165043948570, - 0.275050318772046500, 0.274670462387330010, 0.274290595903766200, - 0.273910719335321300, - 0.273530832695961790, 0.273150935999655950, 0.272771029260370560, - 0.272391112492074590, - 0.272011185708736060, 0.271631248924323390, 0.271251302152806570, - 0.270871345408154380, - 0.270491378704337540, 0.270111402055325910, 0.269731415475089780, - 0.269351418977600950, - 0.268971412576829990, 0.268591396286749500, 0.268211370121331170, - 0.267831334094547010, - 0.267451288220370730, 0.267071232512774700, 0.266691166985733360, - 0.266311091653219700, - 0.265931006529208920, 0.265550911627675250, 0.265170806962593210, - 0.264790692547939020, - 0.264410568397687560, 0.264030434525815760, 0.263650290946299660, - 0.263270137673115630, - 0.262889974720241610, 0.262509802101654310, 0.262129619831332370, - 0.261749427923253670, - 0.261369226391396310, 0.260989015249740050, 0.260608794512263380, - 0.260228564192946710, - 0.259848324305769600, 0.259468074864711960, 0.259087815883755400, - 0.258707547376880010, - 0.258327269358068100, 0.257946981841300490, 0.257566684840560170, - 0.257186378369829110, - 0.256806062443089680, 0.256425737074325920, 0.256045402277520320, - 0.255665058066657680, - 0.255284704455721660, 0.254904341458696390, 0.254523969089567590, - 0.254143587362319620, - 0.253763196290938850, 0.253382795889410710, 0.253002386171721110, - 0.252621967151857420, - 0.252241538843805680, 0.251861101261554090, 0.251480654419089730, - 0.251100198330400150, - 0.250719733009474530, 0.250339258470300590, 0.249958774726868170, - 0.249578281793165680, - 0.249197779683183660, 0.248817268410911650, 0.248436747990339490, - 0.248056218435458720, - 0.247675679760259450, 0.247295131978733870, 0.246914575104873220, - 0.246534009152669040, - 0.246153434136114490, 0.245772850069201410, 0.245392256965923620, - 0.245011654840274010, - 0.244631043706245800, 0.244250423577833860, 0.243869794469031620, - 0.243489156393834590, - 0.243108509366237320, 0.242727853400234670, 0.242347188509823150, - 0.241966514708997830, - 0.241585832011755900, 0.241205140432093070, 0.240824439984007180, - 0.240443730681495050, - 0.240063012538553830, 0.239682285569182310, 0.239301549787377890, - 0.238920805207139960, - 0.238540051842467020, 0.238159289707357810, 0.237778518815812740, - 0.237397739181830820, - 0.237016950819413100, 0.236636153742559610, 0.236255347965270780, - 0.235874533501548580, - 0.235493710365393630, 0.235112878570808560, 0.234732038131795020, - 0.234351189062355030, - 0.233970331376492150, 0.233589465088208580, 0.233208590211508550, - 0.232827706760394850, - 0.232446814748872410, 0.232065914190945020, 0.231685005100616930, - 0.231304087491893930, - 0.230923161378780380, 0.230542226775282770, 0.230161283695406500, - 0.229780332153157300, - 0.229399372162542610, 0.229018403737568290, 0.228637426892242400, - 0.228256441640571880, - 0.227875447996564060, 0.227494445974227850, 0.227113435587570770, - 0.226732416850602300, - 0.226351389777330990, 0.225970354381765690, 0.225589310677916880, - 0.225208258679793520, - 0.224827198401406690, 0.224446129856766040, 0.224065053059883250, - 0.223683968024768950, - 0.223302874765434120, 0.222921773295891380, 0.222540663630151820, - 0.222159545782228660, - 0.221778419766134050, 0.221397285595880480, 0.221016143285482050, - 0.220634992848951380, - 0.220253834300303180, 0.219872667653551100, 0.219491492922709110, - 0.219110310121792800, - 0.218729119264816280, 0.218347920365795780, 0.217966713438746380, - 0.217585498497683580, - 0.217204275556624420, 0.216823044629584520, 0.216441805730581500, - 0.216060558873631570, - 0.215679304072752960, 0.215298041341962870, 0.214916770695278810, - 0.214535492146719880, - 0.214154205710303750, 0.213772911400050090, 0.213391609229977570, - 0.213010299214105140, - 0.212628981366453330, 0.212247655701041290, 0.211866322231890090, - 0.211484980973019880, - 0.211103631938451000, 0.210722275142205480, 0.210340910598303870, - 0.209959538320768660, - 0.209578158323621420, 0.209196770620883960, 0.208815375226579670, - 0.208433972154730530, - 0.208052561419360520, 0.207671143034492080, 0.207289717014149830, - 0.206908283372357230, - 0.206526842123138070, 0.206145393280517730, 0.205763936858520150, - 0.205382472871171230, - 0.205001001332495910, 0.204619522256519300, 0.204238035657268250, - 0.203856541548768030, - 0.203475039945045950, 0.203093530860128300, 0.202712014308041620, - 0.202330490302814110, - 0.201948958858472420, 0.201567419989045200, 0.201185873708560170, - 0.200804320031045230, - 0.200422758970529910, 0.200041190541042220, 0.199659614756612230, - 0.199278031631268500, - 0.198896441179041650, 0.198514843413961220, 0.198133238350057030, - 0.197751626001360480, - 0.197370006381901520, 0.196988379505712050, 0.196606745386822960, - 0.196225104039265410, - 0.195843455477072190, 0.195461799714274460, 0.195080136764905570, - 0.194698466642997730, - 0.194316789362583340, 0.193935104937696560, 0.193553413382369890, - 0.193171714710637930, - 0.192790008936534220, 0.192408296074092570, 0.192026576137348330, - 0.191644849140335360, - 0.191263115097089540, 0.190881374021645320, 0.190499625928039040, - 0.190117870830306100, - 0.189736108742482030, 0.189354339678604100, 0.188972563652707950, - 0.188590780678831250, - 0.188208990771010640, 0.187827193943283040, 0.187445390209686870, - 0.187063579584259070, - 0.186681762081038650, 0.186299937714063470, 0.185918106497371700, - 0.185536268445003070, - 0.185154423570995760, 0.184772571889390000, 0.184390713414225000, - 0.184008848159540110, - 0.183626976139376310, 0.183245097367773090, 0.182863211858771880, - 0.182481319626412670, - 0.182099420684737420, 0.181717515047787020, 0.181335602729602590, - 0.180953683744226880, - 0.180571758105701030, 0.180189825828068250, 0.179807886925370670, - 0.179425941411650660, - 0.179043989300952110, 0.178662030607317450, 0.178280065344791100, - 0.177898093527416370, - 0.177516115169236820, 0.177134130284297610, 0.176752138886642350, - 0.176370140990316640, - 0.175988136609365020, 0.175606125757832240, 0.175224108449764660, - 0.174842084699207030, - 0.174460054520206240, 0.174078017926807490, 0.173695974933058080, - 0.173313925553004180, - 0.172931869800692250, 0.172549807690170230, 0.172167739235484620, - 0.171785664450683800, - 0.171403583349815180, 0.171021495946926340, 0.170639402256066410, - 0.170257302291283000, - 0.169875196066625710, 0.169493083596143100, 0.169110964893883830, - 0.168728839973898290, - 0.168346708850235140, 0.167964571536945220, 0.167582428048078130, - 0.167200278397683750, - 0.166818122599813570, 0.166435960668517400, 0.166053792617847200, - 0.165671618461853270, - 0.165289438214587970, 0.164907251890102520, 0.164525059502448390, - 0.164142861065678550, - 0.163760656593844480, 0.163378446100999640, 0.162996229601196390, - 0.162614007108487250, - 0.162231778636926370, 0.161849544200566300, 0.161467303813461580, - 0.161085057489665670, - 0.160702805243232240, 0.160320547088216470, 0.159938283038672050, - 0.159556013108654580, - 0.159173737312218650, 0.158791455663418930, 0.158409168176311760, - 0.158026874864951870, - 0.157644575743395960, 0.157262270825699210, 0.156879960125918730, - 0.156497643658110590, - 0.156115321436331000, 0.155732993474637760, 0.155350659787087090, - 0.154968320387737170, - 0.154585975290645110, 0.154203624509868190, 0.153821268059465250, - 0.153438905953493550, - 0.153056538206012340, 0.152674164831079730, 0.152291785842754070, - 0.151909401255095250, - 0.151527011082161540, 0.151144615338013210, 0.150762214036709470, - 0.150379807192309620, - 0.149997394818874590, 0.149614976930463660, 0.149232553541138180, - 0.148850124664957870, - 0.148467690315984390, 0.148085250508278370, 0.147702805255900570, - 0.147320354572913260, - 0.146937898473377210, 0.146555436971355090, 0.146172970080908520, - 0.145790497816099230, - 0.145408020190990560, 0.145025537219644170, 0.144643048916123810, - 0.144260555294492000, - 0.143878056368811510, 0.143495552153146630, 0.143113042661560050, - 0.142730527908116440, - 0.142348007906879320, 0.141965482671912420, 0.141582952217280980, - 0.141200416557048680, - 0.140817875705281120, 0.140435329676042390, 0.140052778483398480, - 0.139670222141414250, - 0.139287660664154770, 0.138905094065686600, 0.138522522360074780, - 0.138139945561386200, - 0.137757363683686740, 0.137374776741042340, 0.136992184747520560, - 0.136609587717187310, - 0.136226985664110460, 0.135844378602356760, 0.135461766545993150, - 0.135079149509088060, - 0.134696527505708320, 0.134313900549922760, 0.133931268655799020, - 0.133548631837404950, - 0.133165990108809860, 0.132783343484081580, 0.132400691977289760, - 0.132018035602502530, - 0.131635374373789940, 0.131252708305220960, 0.130870037410864640, - 0.130487361704791580, - 0.130104681201070800, 0.129721995913773260, 0.129339305856968730, - 0.128956611044727220, - 0.128573911491120210, 0.128191207210217570, 0.127808498216091110, - 0.127425784522811530, - 0.127043066144449680, 0.126660343095077900, 0.126277615388766920, - 0.125894883039589430, - 0.125512146061616980, 0.125129404468921260, 0.124746658275575490, - 0.124363907495651240, - 0.123981152143222060, 0.123598392232359880, 0.123215627777138580, - 0.122832858791630880, - 0.122450085289909640, 0.122067307286049230, 0.121684524794122440, - 0.121301737828203960, - 0.120918946402367330, 0.120536150530686250, 0.120153350227235940, - 0.119770545506089950, - 0.119387736381323830, 0.119004922867011920, 0.118622104977228730, - 0.118239282726050290, - 0.117856456127550970, 0.117473625195807100, 0.117090789944893860, - 0.116707950388886520, - 0.116325106541861910, 0.115942258417895240, 0.115559406031063570, - 0.115176549395442460, - 0.114793688525109290, 0.114410823434140360, 0.114027954136612060, - 0.113645080646602280, - 0.113262202978187320, 0.112879321145445350, 0.112496435162453430, - 0.112113545043288730, - 0.111730650802029900, 0.111347752452754000, 0.110964850009539970, - 0.110581943486465610, - 0.110199032897608850, 0.109816118257049110, 0.109433199578864170, - 0.109050276877133770, - 0.108667350165936400, 0.108284419459350770, 0.107901484771457020, - 0.107518546116333660, - 0.107135603508061170, 0.106752656960718350, 0.106369706488385940, - 0.105986752105143480, - 0.105603793825070680, 0.105220831662248700, 0.104837865630757090, - 0.104454895744677270, - 0.104071922018089540, 0.103688944465074300, 0.103305963099713400, - 0.102922977936087120, - 0.102539988988277600, 0.102156996270365800, 0.101773999796432830, - 0.101390999580561250, - 0.101007995636832020, 0.100624987979327970, 0.100241976622130760, - 0.099858961579322170, - 0.099475942864985456, 0.099092920493202258, 0.098709894478056073, - 0.098326864833628791, - 0.097943831574004214, 0.097560794713264939, 0.097177754265493674, - 0.096794710244774623, - 0.096411662665190329, 0.096028611540825232, 0.095645556885762609, - 0.095262498714085819, - 0.094879437039879722, 0.094496371877227495, 0.094113303240214247, - 0.093730231142923864, - 0.093347155599440373, 0.092964076623849271, 0.092580994230234359, - 0.092197908432681386, - 0.091814819245274432, 0.091431726682099479, 0.091048630757241303, - 0.090665531484784803, - 0.090282428878816323, 0.089899322953420582, 0.089516213722684160, - 0.089133101200692441, - 0.088749985401530951, 0.088366866339286629, 0.087983744028044805, - 0.087600618481892656, - 0.087217489714916191, 0.086834357741201490, 0.086451222574836131, - 0.086068084229906014, - 0.085684942720498897, 0.085301798060701386, 0.084918650264600160, - 0.084535499346283349, - 0.084152345319837438, 0.083769188199350780, 0.083386027998910095, - 0.083002864732603973, - 0.082619698414519799, 0.082236529058745025, 0.081853356679368619, - 0.081470181290477811, - 0.081087002906161790, 0.080703821540508452, 0.080320637207605849, - 0.079937449921543474, - 0.079554259696409127, 0.079171066546292510, 0.078787870485282088, - 0.078404671527466441, - 0.078021469686935602, 0.077638264977777913, 0.077255057414083589, - 0.076871847009941652, - 0.076488633779441206, 0.076105417736672773, 0.075722198895725248, - 0.075338977270689375, - 0.074955752875654230, 0.074572525724710764, 0.074189295831948693, - 0.073806063211457842, - 0.073422827877329483, 0.073039589843653177, 0.072656349124520389, - 0.072273105734021334, - 0.071889859686246352, 0.071506610995287156, 0.071123359675233852, - 0.070740105740178361, - 0.070356849204211397, 0.069973590081423773, 0.069590328385907715, - 0.069207064131753759, - 0.068823797333054326, 0.068440528003900616, 0.068057256158383886, - 0.067673981810596848, - 0.067290704974630494, 0.066907425664577733, 0.066524143894529736, - 0.066140859678579578, - 0.065757573030819083, 0.065374283965340146, 0.064990992496236119, - 0.064607698637598646, - 0.064224402403521202, 0.063841103808096086, 0.063457802865415636, - 0.063074499589573618, - 0.062691193994662109, 0.062307886094775049, 0.061924575904005130, - 0.061541263436445129, - 0.061157948706189229, 0.060774631727329942, 0.060391312513961619, - 0.060007991080177375, - 0.059624667440070382, 0.059241341607735261, 0.058858013597264912, - 0.058474683422754095, - 0.058091351098295878, 0.057708016637985186, 0.057324680055915692, - 0.056941341366181127, - 0.056558000582876661, 0.056174657720095743, 0.055791312791933681, - 0.055407965812484541, - 0.055024616795842439, 0.054641265756102911, 0.054257912707359794, - 0.053874557663708772, - 0.053491200639244271, 0.053107841648060788, 0.052724480704254229, - 0.052341117821918783, - 0.051957753015150501, 0.051574386298044173, 0.051191017684694640, - 0.050807647189198162, - 0.050424274825649297, 0.050040900608144430, 0.049657524550778251, - 0.049274146667647289, - 0.048890766972846805, 0.048507385480472134, 0.048124002204620014, - 0.047740617159385448, - 0.047357230358865306, 0.046973841817155179, 0.046590451548350717, - 0.046207059566548990, - 0.045823665885845313, 0.045440270520336883, 0.045056873484119603, - 0.044673474791289434, - 0.044290074455943754, 0.043906672492178188, 0.043523268914090238, - 0.043139863735776100, - 0.042756456971332048, 0.042373048634855741, 0.041989638740443119, - 0.041606227302191955, - 0.041222814334198304, 0.040839399850560058, 0.040455983865373815, - 0.040072566392736257, - 0.039689147446745419, 0.039305727041497644, 0.038922305191091085, - 0.038538881909622631, - 0.038155457211189216, 0.037772031109889144, 0.037388603619819022, - 0.037005174755077273, - 0.036621744529761024, 0.036238312957967478, 0.035854880053795196, - 0.035471445831341021, - 0.035088010304703626, 0.034704573487980395, 0.034321135395268765, - 0.033937696040667535, - 0.033554255438273790, 0.033170813602186440, 0.032787370546502645, - 0.032403926285321405, - 0.032020480832740429, 0.031637034202857461, 0.031253586409771626, - 0.030870137467580314, - 0.030486687390382738, 0.030103236192276818, 0.029719783887360508, - 0.029336330489733147, - 0.028952876013492331, 0.028569420472737472, 0.028185963881566689, - 0.027802506254078142, - 0.027419047604371360, 0.027035587946544135, 0.026652127294696067, - 0.026268665662925468, - 0.025885203065330677, 0.025501739516011413, 0.025118275029065638, - 0.024734809618593138, - 0.024351343298691951, 0.023967876083461924, 0.023584407987001611, - 0.023200939023409587, - 0.022817469206785804, 0.022433998551228459, 0.022050527070837558, - 0.021667054779711814, - 0.021283581691949955, 0.020900107821652084, 0.020516633182916549, - 0.020133157789843505, - 0.019749681656531803, 0.019366204797080316, 0.018982727225589285, - 0.018599248956157190, - 0.018215770002884327, 0.017832290379869671, 0.017448810101212228, - 0.017065329181012358, - 0.016681847633368677, 0.016298365472381587, 0.015914882712149747, - 0.015531399366773606, - 0.015147915450352307, 0.014764430976985016, 0.014380945960772247, - 0.013997460415812761, - 0.013613974356207112, 0.013230487796054543, 0.012847000749454314, - 0.012463513230507034, - 0.012080025253311559, 0.011696536831968529, 0.011313047980577277, - 0.010929558713237145, - 0.010546069044048827, 0.010162578987111254, 0.009779088556525145, - 0.009395597766389905, - 0.009012106630804949, 0.008628615163871038, 0.008245123379687167, - 0.007861631292354124, - 0.007478138915970929, 0.007094646264638386, 0.006711153352455981, - 0.006327660193523208, - 0.005944166801940901, 0.005560673191808128, 0.005177179377225743, - 0.004793685372293270, - 0.004410191191110246, 0.004026696847777542, 0.003643202356394263, - 0.003259707731061291, - 0.002876212985878184, 0.002492718134944503, 0.002109223192361147, - 0.001725728172227238, - 0.001342233088643682, 0.000958737955710053, 0.000575242787525925, - 0.000191747598192208, - -}; - -/** - * @brief Initialization function for the floating-point DCT4/IDCT4. - * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure. - * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Floating-point normalizing factors are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingF32Table.gif - */ - -arm_status arm_dct4_init_f32( - arm_dct4_instance_f32 * S, - arm_rfft_instance_f32 * S_RFFT, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint16_t N, - uint16_t Nby2, - float32_t normalize) -{ - /* Initialize the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - float32_t *twiddlePtr[4] = - { (float32_t *) Weights_128, (float32_t *) Weights_512, - (float32_t *) Weights_2048, (float32_t *) Weights_8192 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - float32_t *pCosFactor[4] = - { (float32_t *) cos_factors_128, (float32_t *) cos_factors_512, - (float32_t *) cos_factors_2048, (float32_t *) cos_factors_8192 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 8192u: - S->pTwiddle = twiddlePtr[3]; - S->pCosFactor = pCosFactor[3]; - break; - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT */ - arm_rfft_init_f32(S->pRfft, S->pCfft, S->N, 0u, 1u); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c deleted file mode 100644 index c6452fe98a..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q15.c +++ /dev/null @@ -1,4276 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_q15.c -* -* Description: Initialization function of DCT-4 & IDCT4 Q15 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
    
-* for(i = 0; i< N; i++)    
-* {    
-*   weights[2*i]= cos(i*c);    
-*   weights[(2*i)+1]= -sin(i * c);    
-* } 
-* \par -* where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* Converted the output to q15 format by multiplying with 2^31 and saturated if required. -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const q15_t ALIGN4 WeightsQ15_128[256] = { - 0x7fff, 0x0, 0x7ffd, 0xfe6e, 0x7ff6, 0xfcdc, 0x7fe9, 0xfb4a, - 0x7fd8, 0xf9b9, 0x7fc2, 0xf827, 0x7fa7, 0xf696, 0x7f87, 0xf505, - 0x7f62, 0xf375, 0x7f38, 0xf1e5, 0x7f09, 0xf055, 0x7ed5, 0xeec7, - 0x7e9d, 0xed38, 0x7e5f, 0xebab, 0x7e1d, 0xea1e, 0x7dd6, 0xe893, - 0x7d8a, 0xe708, 0x7d39, 0xe57e, 0x7ce3, 0xe3f5, 0x7c89, 0xe26d, - 0x7c29, 0xe0e7, 0x7bc5, 0xdf61, 0x7b5d, 0xdddd, 0x7aef, 0xdc5a, - 0x7a7d, 0xdad8, 0x7a05, 0xd958, 0x798a, 0xd7da, 0x7909, 0xd65d, - 0x7884, 0xd4e1, 0x77fa, 0xd368, 0x776c, 0xd1ef, 0x76d9, 0xd079, - 0x7641, 0xcf05, 0x75a5, 0xcd92, 0x7504, 0xcc22, 0x745f, 0xcab3, - 0x73b5, 0xc946, 0x7307, 0xc7dc, 0x7255, 0xc674, 0x719e, 0xc50e, - 0x70e2, 0xc3aa, 0x7023, 0xc248, 0x6f5f, 0xc0e9, 0x6e96, 0xbf8d, - 0x6dca, 0xbe32, 0x6cf9, 0xbcdb, 0x6c24, 0xbb86, 0x6b4a, 0xba33, - 0x6a6d, 0xb8e4, 0x698c, 0xb797, 0x68a6, 0xb64c, 0x67bd, 0xb505, - 0x66cf, 0xb3c1, 0x65dd, 0xb27f, 0x64e8, 0xb141, 0x63ef, 0xb005, - 0x62f2, 0xaecd, 0x61f1, 0xad97, 0x60ec, 0xac65, 0x5fe3, 0xab36, - 0x5ed7, 0xaa0b, 0x5dc7, 0xa8e3, 0x5cb4, 0xa7be, 0x5b9d, 0xa69c, - 0x5a82, 0xa57e, 0x5964, 0xa463, 0x5842, 0xa34c, 0x571d, 0xa239, - 0x55f5, 0xa129, 0x54ca, 0xa01d, 0x539b, 0x9f14, 0x5269, 0x9e0f, - 0x5133, 0x9d0e, 0x4ffb, 0x9c11, 0x4ebf, 0x9b18, 0x4d81, 0x9a23, - 0x4c3f, 0x9931, 0x4afb, 0x9843, 0x49b4, 0x975a, 0x4869, 0x9674, - 0x471c, 0x9593, 0x45cd, 0x94b6, 0x447a, 0x93dc, 0x4325, 0x9307, - 0x41ce, 0x9236, 0x4073, 0x916a, 0x3f17, 0x90a1, 0x3db8, 0x8fdd, - 0x3c56, 0x8f1e, 0x3af2, 0x8e62, 0x398c, 0x8dab, 0x3824, 0x8cf9, - 0x36ba, 0x8c4b, 0x354d, 0x8ba1, 0x33de, 0x8afc, 0x326e, 0x8a5b, - 0x30fb, 0x89bf, 0x2f87, 0x8927, 0x2e11, 0x8894, 0x2c98, 0x8806, - 0x2b1f, 0x877c, 0x29a3, 0x86f7, 0x2826, 0x8676, 0x26a8, 0x85fb, - 0x2528, 0x8583, 0x23a6, 0x8511, 0x2223, 0x84a3, 0x209f, 0x843b, - 0x1f19, 0x83d7, 0x1d93, 0x8377, 0x1c0b, 0x831d, 0x1a82, 0x82c7, - 0x18f8, 0x8276, 0x176d, 0x822a, 0x15e2, 0x81e3, 0x1455, 0x81a1, - 0x12c8, 0x8163, 0x1139, 0x812b, 0xfab, 0x80f7, 0xe1b, 0x80c8, - 0xc8b, 0x809e, 0xafb, 0x8079, 0x96a, 0x8059, 0x7d9, 0x803e, - 0x647, 0x8028, 0x4b6, 0x8017, 0x324, 0x800a, 0x192, 0x8003, -}; - -static const q15_t ALIGN4 WeightsQ15_512[1024] = { - 0x7fff, 0x0, 0x7fff, 0xff9c, 0x7fff, 0xff37, 0x7ffe, 0xfed3, - 0x7ffd, 0xfe6e, 0x7ffc, 0xfe0a, 0x7ffa, 0xfda5, 0x7ff8, 0xfd41, - 0x7ff6, 0xfcdc, 0x7ff3, 0xfc78, 0x7ff0, 0xfc13, 0x7fed, 0xfbaf, - 0x7fe9, 0xfb4a, 0x7fe5, 0xfae6, 0x7fe1, 0xfa81, 0x7fdd, 0xfa1d, - 0x7fd8, 0xf9b9, 0x7fd3, 0xf954, 0x7fce, 0xf8f0, 0x7fc8, 0xf88b, - 0x7fc2, 0xf827, 0x7fbc, 0xf7c3, 0x7fb5, 0xf75e, 0x7fae, 0xf6fa, - 0x7fa7, 0xf696, 0x7f9f, 0xf632, 0x7f97, 0xf5cd, 0x7f8f, 0xf569, - 0x7f87, 0xf505, 0x7f7e, 0xf4a1, 0x7f75, 0xf43d, 0x7f6b, 0xf3d9, - 0x7f62, 0xf375, 0x7f58, 0xf311, 0x7f4d, 0xf2ad, 0x7f43, 0xf249, - 0x7f38, 0xf1e5, 0x7f2d, 0xf181, 0x7f21, 0xf11d, 0x7f15, 0xf0b9, - 0x7f09, 0xf055, 0x7efd, 0xeff2, 0x7ef0, 0xef8e, 0x7ee3, 0xef2a, - 0x7ed5, 0xeec7, 0x7ec8, 0xee63, 0x7eba, 0xedff, 0x7eab, 0xed9c, - 0x7e9d, 0xed38, 0x7e8e, 0xecd5, 0x7e7f, 0xec72, 0x7e6f, 0xec0e, - 0x7e5f, 0xebab, 0x7e4f, 0xeb48, 0x7e3f, 0xeae5, 0x7e2e, 0xea81, - 0x7e1d, 0xea1e, 0x7e0c, 0xe9bb, 0x7dfa, 0xe958, 0x7de8, 0xe8f6, - 0x7dd6, 0xe893, 0x7dc3, 0xe830, 0x7db0, 0xe7cd, 0x7d9d, 0xe76a, - 0x7d8a, 0xe708, 0x7d76, 0xe6a5, 0x7d62, 0xe643, 0x7d4e, 0xe5e0, - 0x7d39, 0xe57e, 0x7d24, 0xe51c, 0x7d0f, 0xe4b9, 0x7cf9, 0xe457, - 0x7ce3, 0xe3f5, 0x7ccd, 0xe393, 0x7cb7, 0xe331, 0x7ca0, 0xe2cf, - 0x7c89, 0xe26d, 0x7c71, 0xe20b, 0x7c5a, 0xe1aa, 0x7c42, 0xe148, - 0x7c29, 0xe0e7, 0x7c11, 0xe085, 0x7bf8, 0xe024, 0x7bdf, 0xdfc2, - 0x7bc5, 0xdf61, 0x7bac, 0xdf00, 0x7b92, 0xde9f, 0x7b77, 0xde3e, - 0x7b5d, 0xdddd, 0x7b42, 0xdd7c, 0x7b26, 0xdd1b, 0x7b0b, 0xdcbb, - 0x7aef, 0xdc5a, 0x7ad3, 0xdbf9, 0x7ab6, 0xdb99, 0x7a9a, 0xdb39, - 0x7a7d, 0xdad8, 0x7a5f, 0xda78, 0x7a42, 0xda18, 0x7a24, 0xd9b8, - 0x7a05, 0xd958, 0x79e7, 0xd8f9, 0x79c8, 0xd899, 0x79a9, 0xd839, - 0x798a, 0xd7da, 0x796a, 0xd77a, 0x794a, 0xd71b, 0x792a, 0xd6bc, - 0x7909, 0xd65d, 0x78e8, 0xd5fe, 0x78c7, 0xd59f, 0x78a6, 0xd540, - 0x7884, 0xd4e1, 0x7862, 0xd483, 0x7840, 0xd424, 0x781d, 0xd3c6, - 0x77fa, 0xd368, 0x77d7, 0xd309, 0x77b4, 0xd2ab, 0x7790, 0xd24d, - 0x776c, 0xd1ef, 0x7747, 0xd192, 0x7723, 0xd134, 0x76fe, 0xd0d7, - 0x76d9, 0xd079, 0x76b3, 0xd01c, 0x768e, 0xcfbf, 0x7668, 0xcf62, - 0x7641, 0xcf05, 0x761b, 0xcea8, 0x75f4, 0xce4b, 0x75cc, 0xcdef, - 0x75a5, 0xcd92, 0x757d, 0xcd36, 0x7555, 0xccda, 0x752d, 0xcc7e, - 0x7504, 0xcc22, 0x74db, 0xcbc6, 0x74b2, 0xcb6a, 0x7489, 0xcb0e, - 0x745f, 0xcab3, 0x7435, 0xca58, 0x740b, 0xc9fc, 0x73e0, 0xc9a1, - 0x73b5, 0xc946, 0x738a, 0xc8ec, 0x735f, 0xc891, 0x7333, 0xc836, - 0x7307, 0xc7dc, 0x72db, 0xc782, 0x72af, 0xc728, 0x7282, 0xc6ce, - 0x7255, 0xc674, 0x7227, 0xc61a, 0x71fa, 0xc5c0, 0x71cc, 0xc567, - 0x719e, 0xc50e, 0x716f, 0xc4b4, 0x7141, 0xc45b, 0x7112, 0xc403, - 0x70e2, 0xc3aa, 0x70b3, 0xc351, 0x7083, 0xc2f9, 0x7053, 0xc2a0, - 0x7023, 0xc248, 0x6ff2, 0xc1f0, 0x6fc1, 0xc198, 0x6f90, 0xc141, - 0x6f5f, 0xc0e9, 0x6f2d, 0xc092, 0x6efb, 0xc03b, 0x6ec9, 0xbfe3, - 0x6e96, 0xbf8d, 0x6e63, 0xbf36, 0x6e30, 0xbedf, 0x6dfd, 0xbe89, - 0x6dca, 0xbe32, 0x6d96, 0xbddc, 0x6d62, 0xbd86, 0x6d2d, 0xbd30, - 0x6cf9, 0xbcdb, 0x6cc4, 0xbc85, 0x6c8f, 0xbc30, 0x6c59, 0xbbdb, - 0x6c24, 0xbb86, 0x6bee, 0xbb31, 0x6bb8, 0xbadc, 0x6b81, 0xba88, - 0x6b4a, 0xba33, 0x6b13, 0xb9df, 0x6adc, 0xb98b, 0x6aa5, 0xb937, - 0x6a6d, 0xb8e4, 0x6a35, 0xb890, 0x69fd, 0xb83d, 0x69c4, 0xb7ea, - 0x698c, 0xb797, 0x6953, 0xb744, 0x6919, 0xb6f1, 0x68e0, 0xb69f, - 0x68a6, 0xb64c, 0x686c, 0xb5fa, 0x6832, 0xb5a8, 0x67f7, 0xb557, - 0x67bd, 0xb505, 0x6782, 0xb4b4, 0x6746, 0xb462, 0x670b, 0xb411, - 0x66cf, 0xb3c1, 0x6693, 0xb370, 0x6657, 0xb31f, 0x661a, 0xb2cf, - 0x65dd, 0xb27f, 0x65a0, 0xb22f, 0x6563, 0xb1df, 0x6526, 0xb190, - 0x64e8, 0xb141, 0x64aa, 0xb0f1, 0x646c, 0xb0a2, 0x642d, 0xb054, - 0x63ef, 0xb005, 0x63b0, 0xafb7, 0x6371, 0xaf69, 0x6331, 0xaf1b, - 0x62f2, 0xaecd, 0x62b2, 0xae7f, 0x6271, 0xae32, 0x6231, 0xade4, - 0x61f1, 0xad97, 0x61b0, 0xad4b, 0x616f, 0xacfe, 0x612d, 0xacb2, - 0x60ec, 0xac65, 0x60aa, 0xac19, 0x6068, 0xabcd, 0x6026, 0xab82, - 0x5fe3, 0xab36, 0x5fa0, 0xaaeb, 0x5f5e, 0xaaa0, 0x5f1a, 0xaa55, - 0x5ed7, 0xaa0b, 0x5e93, 0xa9c0, 0x5e50, 0xa976, 0x5e0b, 0xa92c, - 0x5dc7, 0xa8e3, 0x5d83, 0xa899, 0x5d3e, 0xa850, 0x5cf9, 0xa807, - 0x5cb4, 0xa7be, 0x5c6e, 0xa775, 0x5c29, 0xa72c, 0x5be3, 0xa6e4, - 0x5b9d, 0xa69c, 0x5b56, 0xa654, 0x5b10, 0xa60d, 0x5ac9, 0xa5c5, - 0x5a82, 0xa57e, 0x5a3b, 0xa537, 0x59f3, 0xa4f0, 0x59ac, 0xa4aa, - 0x5964, 0xa463, 0x591c, 0xa41d, 0x58d4, 0xa3d7, 0x588b, 0xa392, - 0x5842, 0xa34c, 0x57f9, 0xa307, 0x57b0, 0xa2c2, 0x5767, 0xa27d, - 0x571d, 0xa239, 0x56d4, 0xa1f5, 0x568a, 0xa1b0, 0x5640, 0xa16d, - 0x55f5, 0xa129, 0x55ab, 0xa0e6, 0x5560, 0xa0a2, 0x5515, 0xa060, - 0x54ca, 0xa01d, 0x547e, 0x9fda, 0x5433, 0x9f98, 0x53e7, 0x9f56, - 0x539b, 0x9f14, 0x534e, 0x9ed3, 0x5302, 0x9e91, 0x52b5, 0x9e50, - 0x5269, 0x9e0f, 0x521c, 0x9dcf, 0x51ce, 0x9d8f, 0x5181, 0x9d4e, - 0x5133, 0x9d0e, 0x50e5, 0x9ccf, 0x5097, 0x9c8f, 0x5049, 0x9c50, - 0x4ffb, 0x9c11, 0x4fac, 0x9bd3, 0x4f5e, 0x9b94, 0x4f0f, 0x9b56, - 0x4ebf, 0x9b18, 0x4e70, 0x9ada, 0x4e21, 0x9a9d, 0x4dd1, 0x9a60, - 0x4d81, 0x9a23, 0x4d31, 0x99e6, 0x4ce1, 0x99a9, 0x4c90, 0x996d, - 0x4c3f, 0x9931, 0x4bef, 0x98f5, 0x4b9e, 0x98ba, 0x4b4c, 0x987e, - 0x4afb, 0x9843, 0x4aa9, 0x9809, 0x4a58, 0x97ce, 0x4a06, 0x9794, - 0x49b4, 0x975a, 0x4961, 0x9720, 0x490f, 0x96e7, 0x48bc, 0x96ad, - 0x4869, 0x9674, 0x4816, 0x963c, 0x47c3, 0x9603, 0x4770, 0x95cb, - 0x471c, 0x9593, 0x46c9, 0x955b, 0x4675, 0x9524, 0x4621, 0x94ed, - 0x45cd, 0x94b6, 0x4578, 0x947f, 0x4524, 0x9448, 0x44cf, 0x9412, - 0x447a, 0x93dc, 0x4425, 0x93a7, 0x43d0, 0x9371, 0x437b, 0x933c, - 0x4325, 0x9307, 0x42d0, 0x92d3, 0x427a, 0x929e, 0x4224, 0x926a, - 0x41ce, 0x9236, 0x4177, 0x9203, 0x4121, 0x91d0, 0x40ca, 0x919d, - 0x4073, 0x916a, 0x401d, 0x9137, 0x3fc5, 0x9105, 0x3f6e, 0x90d3, - 0x3f17, 0x90a1, 0x3ebf, 0x9070, 0x3e68, 0x903f, 0x3e10, 0x900e, - 0x3db8, 0x8fdd, 0x3d60, 0x8fad, 0x3d07, 0x8f7d, 0x3caf, 0x8f4d, - 0x3c56, 0x8f1e, 0x3bfd, 0x8eee, 0x3ba5, 0x8ebf, 0x3b4c, 0x8e91, - 0x3af2, 0x8e62, 0x3a99, 0x8e34, 0x3a40, 0x8e06, 0x39e6, 0x8dd9, - 0x398c, 0x8dab, 0x3932, 0x8d7e, 0x38d8, 0x8d51, 0x387e, 0x8d25, - 0x3824, 0x8cf9, 0x37ca, 0x8ccd, 0x376f, 0x8ca1, 0x3714, 0x8c76, - 0x36ba, 0x8c4b, 0x365f, 0x8c20, 0x3604, 0x8bf5, 0x35a8, 0x8bcb, - 0x354d, 0x8ba1, 0x34f2, 0x8b77, 0x3496, 0x8b4e, 0x343a, 0x8b25, - 0x33de, 0x8afc, 0x3382, 0x8ad3, 0x3326, 0x8aab, 0x32ca, 0x8a83, - 0x326e, 0x8a5b, 0x3211, 0x8a34, 0x31b5, 0x8a0c, 0x3158, 0x89e5, - 0x30fb, 0x89bf, 0x309e, 0x8998, 0x3041, 0x8972, 0x2fe4, 0x894d, - 0x2f87, 0x8927, 0x2f29, 0x8902, 0x2ecc, 0x88dd, 0x2e6e, 0x88b9, - 0x2e11, 0x8894, 0x2db3, 0x8870, 0x2d55, 0x884c, 0x2cf7, 0x8829, - 0x2c98, 0x8806, 0x2c3a, 0x87e3, 0x2bdc, 0x87c0, 0x2b7d, 0x879e, - 0x2b1f, 0x877c, 0x2ac0, 0x875a, 0x2a61, 0x8739, 0x2a02, 0x8718, - 0x29a3, 0x86f7, 0x2944, 0x86d6, 0x28e5, 0x86b6, 0x2886, 0x8696, - 0x2826, 0x8676, 0x27c7, 0x8657, 0x2767, 0x8638, 0x2707, 0x8619, - 0x26a8, 0x85fb, 0x2648, 0x85dc, 0x25e8, 0x85be, 0x2588, 0x85a1, - 0x2528, 0x8583, 0x24c7, 0x8566, 0x2467, 0x854a, 0x2407, 0x852d, - 0x23a6, 0x8511, 0x2345, 0x84f5, 0x22e5, 0x84da, 0x2284, 0x84be, - 0x2223, 0x84a3, 0x21c2, 0x8489, 0x2161, 0x846e, 0x2100, 0x8454, - 0x209f, 0x843b, 0x203e, 0x8421, 0x1fdc, 0x8408, 0x1f7b, 0x83ef, - 0x1f19, 0x83d7, 0x1eb8, 0x83be, 0x1e56, 0x83a6, 0x1df5, 0x838f, - 0x1d93, 0x8377, 0x1d31, 0x8360, 0x1ccf, 0x8349, 0x1c6d, 0x8333, - 0x1c0b, 0x831d, 0x1ba9, 0x8307, 0x1b47, 0x82f1, 0x1ae4, 0x82dc, - 0x1a82, 0x82c7, 0x1a20, 0x82b2, 0x19bd, 0x829e, 0x195b, 0x828a, - 0x18f8, 0x8276, 0x1896, 0x8263, 0x1833, 0x8250, 0x17d0, 0x823d, - 0x176d, 0x822a, 0x170a, 0x8218, 0x16a8, 0x8206, 0x1645, 0x81f4, - 0x15e2, 0x81e3, 0x157f, 0x81d2, 0x151b, 0x81c1, 0x14b8, 0x81b1, - 0x1455, 0x81a1, 0x13f2, 0x8191, 0x138e, 0x8181, 0x132b, 0x8172, - 0x12c8, 0x8163, 0x1264, 0x8155, 0x1201, 0x8146, 0x119d, 0x8138, - 0x1139, 0x812b, 0x10d6, 0x811d, 0x1072, 0x8110, 0x100e, 0x8103, - 0xfab, 0x80f7, 0xf47, 0x80eb, 0xee3, 0x80df, 0xe7f, 0x80d3, - 0xe1b, 0x80c8, 0xdb7, 0x80bd, 0xd53, 0x80b3, 0xcef, 0x80a8, - 0xc8b, 0x809e, 0xc27, 0x8095, 0xbc3, 0x808b, 0xb5f, 0x8082, - 0xafb, 0x8079, 0xa97, 0x8071, 0xa33, 0x8069, 0x9ce, 0x8061, - 0x96a, 0x8059, 0x906, 0x8052, 0x8a2, 0x804b, 0x83d, 0x8044, - 0x7d9, 0x803e, 0x775, 0x8038, 0x710, 0x8032, 0x6ac, 0x802d, - 0x647, 0x8028, 0x5e3, 0x8023, 0x57f, 0x801f, 0x51a, 0x801b, - 0x4b6, 0x8017, 0x451, 0x8013, 0x3ed, 0x8010, 0x388, 0x800d, - 0x324, 0x800a, 0x2bf, 0x8008, 0x25b, 0x8006, 0x1f6, 0x8004, - 0x192, 0x8003, 0x12d, 0x8002, 0xc9, 0x8001, 0x64, 0x8001, -}; - -static const q15_t ALIGN4 WeightsQ15_2048[4096] = { - 0x7fff, 0x0, 0x7fff, 0xffe7, 0x7fff, 0xffce, 0x7fff, 0xffb5, - 0x7fff, 0xff9c, 0x7fff, 0xff83, 0x7fff, 0xff6a, 0x7fff, 0xff51, - 0x7fff, 0xff37, 0x7fff, 0xff1e, 0x7fff, 0xff05, 0x7ffe, 0xfeec, - 0x7ffe, 0xfed3, 0x7ffe, 0xfeba, 0x7ffe, 0xfea1, 0x7ffd, 0xfe88, - 0x7ffd, 0xfe6e, 0x7ffd, 0xfe55, 0x7ffc, 0xfe3c, 0x7ffc, 0xfe23, - 0x7ffc, 0xfe0a, 0x7ffb, 0xfdf1, 0x7ffb, 0xfdd8, 0x7ffa, 0xfdbe, - 0x7ffa, 0xfda5, 0x7ff9, 0xfd8c, 0x7ff9, 0xfd73, 0x7ff8, 0xfd5a, - 0x7ff8, 0xfd41, 0x7ff7, 0xfd28, 0x7ff7, 0xfd0f, 0x7ff6, 0xfcf5, - 0x7ff6, 0xfcdc, 0x7ff5, 0xfcc3, 0x7ff4, 0xfcaa, 0x7ff4, 0xfc91, - 0x7ff3, 0xfc78, 0x7ff2, 0xfc5f, 0x7ff2, 0xfc46, 0x7ff1, 0xfc2c, - 0x7ff0, 0xfc13, 0x7fef, 0xfbfa, 0x7fee, 0xfbe1, 0x7fee, 0xfbc8, - 0x7fed, 0xfbaf, 0x7fec, 0xfb96, 0x7feb, 0xfb7d, 0x7fea, 0xfb64, - 0x7fe9, 0xfb4a, 0x7fe8, 0xfb31, 0x7fe7, 0xfb18, 0x7fe6, 0xfaff, - 0x7fe5, 0xfae6, 0x7fe4, 0xfacd, 0x7fe3, 0xfab4, 0x7fe2, 0xfa9b, - 0x7fe1, 0xfa81, 0x7fe0, 0xfa68, 0x7fdf, 0xfa4f, 0x7fde, 0xfa36, - 0x7fdd, 0xfa1d, 0x7fdc, 0xfa04, 0x7fda, 0xf9eb, 0x7fd9, 0xf9d2, - 0x7fd8, 0xf9b9, 0x7fd7, 0xf9a0, 0x7fd6, 0xf986, 0x7fd4, 0xf96d, - 0x7fd3, 0xf954, 0x7fd2, 0xf93b, 0x7fd0, 0xf922, 0x7fcf, 0xf909, - 0x7fce, 0xf8f0, 0x7fcc, 0xf8d7, 0x7fcb, 0xf8be, 0x7fc9, 0xf8a5, - 0x7fc8, 0xf88b, 0x7fc6, 0xf872, 0x7fc5, 0xf859, 0x7fc3, 0xf840, - 0x7fc2, 0xf827, 0x7fc0, 0xf80e, 0x7fbf, 0xf7f5, 0x7fbd, 0xf7dc, - 0x7fbc, 0xf7c3, 0x7fba, 0xf7aa, 0x7fb8, 0xf791, 0x7fb7, 0xf778, - 0x7fb5, 0xf75e, 0x7fb3, 0xf745, 0x7fb1, 0xf72c, 0x7fb0, 0xf713, - 0x7fae, 0xf6fa, 0x7fac, 0xf6e1, 0x7faa, 0xf6c8, 0x7fa9, 0xf6af, - 0x7fa7, 0xf696, 0x7fa5, 0xf67d, 0x7fa3, 0xf664, 0x7fa1, 0xf64b, - 0x7f9f, 0xf632, 0x7f9d, 0xf619, 0x7f9b, 0xf600, 0x7f99, 0xf5e7, - 0x7f97, 0xf5cd, 0x7f95, 0xf5b4, 0x7f93, 0xf59b, 0x7f91, 0xf582, - 0x7f8f, 0xf569, 0x7f8d, 0xf550, 0x7f8b, 0xf537, 0x7f89, 0xf51e, - 0x7f87, 0xf505, 0x7f85, 0xf4ec, 0x7f82, 0xf4d3, 0x7f80, 0xf4ba, - 0x7f7e, 0xf4a1, 0x7f7c, 0xf488, 0x7f79, 0xf46f, 0x7f77, 0xf456, - 0x7f75, 0xf43d, 0x7f72, 0xf424, 0x7f70, 0xf40b, 0x7f6e, 0xf3f2, - 0x7f6b, 0xf3d9, 0x7f69, 0xf3c0, 0x7f67, 0xf3a7, 0x7f64, 0xf38e, - 0x7f62, 0xf375, 0x7f5f, 0xf35c, 0x7f5d, 0xf343, 0x7f5a, 0xf32a, - 0x7f58, 0xf311, 0x7f55, 0xf2f8, 0x7f53, 0xf2df, 0x7f50, 0xf2c6, - 0x7f4d, 0xf2ad, 0x7f4b, 0xf294, 0x7f48, 0xf27b, 0x7f45, 0xf262, - 0x7f43, 0xf249, 0x7f40, 0xf230, 0x7f3d, 0xf217, 0x7f3b, 0xf1fe, - 0x7f38, 0xf1e5, 0x7f35, 0xf1cc, 0x7f32, 0xf1b3, 0x7f2f, 0xf19a, - 0x7f2d, 0xf181, 0x7f2a, 0xf168, 0x7f27, 0xf14f, 0x7f24, 0xf136, - 0x7f21, 0xf11d, 0x7f1e, 0xf104, 0x7f1b, 0xf0eb, 0x7f18, 0xf0d2, - 0x7f15, 0xf0b9, 0x7f12, 0xf0a0, 0x7f0f, 0xf087, 0x7f0c, 0xf06e, - 0x7f09, 0xf055, 0x7f06, 0xf03c, 0x7f03, 0xf023, 0x7f00, 0xf00b, - 0x7efd, 0xeff2, 0x7ef9, 0xefd9, 0x7ef6, 0xefc0, 0x7ef3, 0xefa7, - 0x7ef0, 0xef8e, 0x7eed, 0xef75, 0x7ee9, 0xef5c, 0x7ee6, 0xef43, - 0x7ee3, 0xef2a, 0x7edf, 0xef11, 0x7edc, 0xeef8, 0x7ed9, 0xeedf, - 0x7ed5, 0xeec7, 0x7ed2, 0xeeae, 0x7ecf, 0xee95, 0x7ecb, 0xee7c, - 0x7ec8, 0xee63, 0x7ec4, 0xee4a, 0x7ec1, 0xee31, 0x7ebd, 0xee18, - 0x7eba, 0xedff, 0x7eb6, 0xede7, 0x7eb3, 0xedce, 0x7eaf, 0xedb5, - 0x7eab, 0xed9c, 0x7ea8, 0xed83, 0x7ea4, 0xed6a, 0x7ea1, 0xed51, - 0x7e9d, 0xed38, 0x7e99, 0xed20, 0x7e95, 0xed07, 0x7e92, 0xecee, - 0x7e8e, 0xecd5, 0x7e8a, 0xecbc, 0x7e86, 0xeca3, 0x7e83, 0xec8a, - 0x7e7f, 0xec72, 0x7e7b, 0xec59, 0x7e77, 0xec40, 0x7e73, 0xec27, - 0x7e6f, 0xec0e, 0x7e6b, 0xebf5, 0x7e67, 0xebdd, 0x7e63, 0xebc4, - 0x7e5f, 0xebab, 0x7e5b, 0xeb92, 0x7e57, 0xeb79, 0x7e53, 0xeb61, - 0x7e4f, 0xeb48, 0x7e4b, 0xeb2f, 0x7e47, 0xeb16, 0x7e43, 0xeafd, - 0x7e3f, 0xeae5, 0x7e3b, 0xeacc, 0x7e37, 0xeab3, 0x7e32, 0xea9a, - 0x7e2e, 0xea81, 0x7e2a, 0xea69, 0x7e26, 0xea50, 0x7e21, 0xea37, - 0x7e1d, 0xea1e, 0x7e19, 0xea06, 0x7e14, 0xe9ed, 0x7e10, 0xe9d4, - 0x7e0c, 0xe9bb, 0x7e07, 0xe9a3, 0x7e03, 0xe98a, 0x7dff, 0xe971, - 0x7dfa, 0xe958, 0x7df6, 0xe940, 0x7df1, 0xe927, 0x7ded, 0xe90e, - 0x7de8, 0xe8f6, 0x7de4, 0xe8dd, 0x7ddf, 0xe8c4, 0x7dda, 0xe8ab, - 0x7dd6, 0xe893, 0x7dd1, 0xe87a, 0x7dcd, 0xe861, 0x7dc8, 0xe849, - 0x7dc3, 0xe830, 0x7dbf, 0xe817, 0x7dba, 0xe7fe, 0x7db5, 0xe7e6, - 0x7db0, 0xe7cd, 0x7dac, 0xe7b4, 0x7da7, 0xe79c, 0x7da2, 0xe783, - 0x7d9d, 0xe76a, 0x7d98, 0xe752, 0x7d94, 0xe739, 0x7d8f, 0xe720, - 0x7d8a, 0xe708, 0x7d85, 0xe6ef, 0x7d80, 0xe6d6, 0x7d7b, 0xe6be, - 0x7d76, 0xe6a5, 0x7d71, 0xe68d, 0x7d6c, 0xe674, 0x7d67, 0xe65b, - 0x7d62, 0xe643, 0x7d5d, 0xe62a, 0x7d58, 0xe611, 0x7d53, 0xe5f9, - 0x7d4e, 0xe5e0, 0x7d49, 0xe5c8, 0x7d43, 0xe5af, 0x7d3e, 0xe596, - 0x7d39, 0xe57e, 0x7d34, 0xe565, 0x7d2f, 0xe54d, 0x7d29, 0xe534, - 0x7d24, 0xe51c, 0x7d1f, 0xe503, 0x7d19, 0xe4ea, 0x7d14, 0xe4d2, - 0x7d0f, 0xe4b9, 0x7d09, 0xe4a1, 0x7d04, 0xe488, 0x7cff, 0xe470, - 0x7cf9, 0xe457, 0x7cf4, 0xe43f, 0x7cee, 0xe426, 0x7ce9, 0xe40e, - 0x7ce3, 0xe3f5, 0x7cde, 0xe3dc, 0x7cd8, 0xe3c4, 0x7cd3, 0xe3ab, - 0x7ccd, 0xe393, 0x7cc8, 0xe37a, 0x7cc2, 0xe362, 0x7cbc, 0xe349, - 0x7cb7, 0xe331, 0x7cb1, 0xe318, 0x7cab, 0xe300, 0x7ca6, 0xe2e8, - 0x7ca0, 0xe2cf, 0x7c9a, 0xe2b7, 0x7c94, 0xe29e, 0x7c8f, 0xe286, - 0x7c89, 0xe26d, 0x7c83, 0xe255, 0x7c7d, 0xe23c, 0x7c77, 0xe224, - 0x7c71, 0xe20b, 0x7c6c, 0xe1f3, 0x7c66, 0xe1db, 0x7c60, 0xe1c2, - 0x7c5a, 0xe1aa, 0x7c54, 0xe191, 0x7c4e, 0xe179, 0x7c48, 0xe160, - 0x7c42, 0xe148, 0x7c3c, 0xe130, 0x7c36, 0xe117, 0x7c30, 0xe0ff, - 0x7c29, 0xe0e7, 0x7c23, 0xe0ce, 0x7c1d, 0xe0b6, 0x7c17, 0xe09d, - 0x7c11, 0xe085, 0x7c0b, 0xe06d, 0x7c05, 0xe054, 0x7bfe, 0xe03c, - 0x7bf8, 0xe024, 0x7bf2, 0xe00b, 0x7beb, 0xdff3, 0x7be5, 0xdfdb, - 0x7bdf, 0xdfc2, 0x7bd9, 0xdfaa, 0x7bd2, 0xdf92, 0x7bcc, 0xdf79, - 0x7bc5, 0xdf61, 0x7bbf, 0xdf49, 0x7bb9, 0xdf30, 0x7bb2, 0xdf18, - 0x7bac, 0xdf00, 0x7ba5, 0xdee8, 0x7b9f, 0xdecf, 0x7b98, 0xdeb7, - 0x7b92, 0xde9f, 0x7b8b, 0xde87, 0x7b84, 0xde6e, 0x7b7e, 0xde56, - 0x7b77, 0xde3e, 0x7b71, 0xde26, 0x7b6a, 0xde0d, 0x7b63, 0xddf5, - 0x7b5d, 0xdddd, 0x7b56, 0xddc5, 0x7b4f, 0xddac, 0x7b48, 0xdd94, - 0x7b42, 0xdd7c, 0x7b3b, 0xdd64, 0x7b34, 0xdd4c, 0x7b2d, 0xdd33, - 0x7b26, 0xdd1b, 0x7b1f, 0xdd03, 0x7b19, 0xdceb, 0x7b12, 0xdcd3, - 0x7b0b, 0xdcbb, 0x7b04, 0xdca2, 0x7afd, 0xdc8a, 0x7af6, 0xdc72, - 0x7aef, 0xdc5a, 0x7ae8, 0xdc42, 0x7ae1, 0xdc2a, 0x7ada, 0xdc12, - 0x7ad3, 0xdbf9, 0x7acc, 0xdbe1, 0x7ac5, 0xdbc9, 0x7abd, 0xdbb1, - 0x7ab6, 0xdb99, 0x7aaf, 0xdb81, 0x7aa8, 0xdb69, 0x7aa1, 0xdb51, - 0x7a9a, 0xdb39, 0x7a92, 0xdb21, 0x7a8b, 0xdb09, 0x7a84, 0xdaf1, - 0x7a7d, 0xdad8, 0x7a75, 0xdac0, 0x7a6e, 0xdaa8, 0x7a67, 0xda90, - 0x7a5f, 0xda78, 0x7a58, 0xda60, 0x7a50, 0xda48, 0x7a49, 0xda30, - 0x7a42, 0xda18, 0x7a3a, 0xda00, 0x7a33, 0xd9e8, 0x7a2b, 0xd9d0, - 0x7a24, 0xd9b8, 0x7a1c, 0xd9a0, 0x7a15, 0xd988, 0x7a0d, 0xd970, - 0x7a05, 0xd958, 0x79fe, 0xd940, 0x79f6, 0xd928, 0x79ef, 0xd911, - 0x79e7, 0xd8f9, 0x79df, 0xd8e1, 0x79d8, 0xd8c9, 0x79d0, 0xd8b1, - 0x79c8, 0xd899, 0x79c0, 0xd881, 0x79b9, 0xd869, 0x79b1, 0xd851, - 0x79a9, 0xd839, 0x79a1, 0xd821, 0x7999, 0xd80a, 0x7992, 0xd7f2, - 0x798a, 0xd7da, 0x7982, 0xd7c2, 0x797a, 0xd7aa, 0x7972, 0xd792, - 0x796a, 0xd77a, 0x7962, 0xd763, 0x795a, 0xd74b, 0x7952, 0xd733, - 0x794a, 0xd71b, 0x7942, 0xd703, 0x793a, 0xd6eb, 0x7932, 0xd6d4, - 0x792a, 0xd6bc, 0x7922, 0xd6a4, 0x7919, 0xd68c, 0x7911, 0xd675, - 0x7909, 0xd65d, 0x7901, 0xd645, 0x78f9, 0xd62d, 0x78f1, 0xd615, - 0x78e8, 0xd5fe, 0x78e0, 0xd5e6, 0x78d8, 0xd5ce, 0x78cf, 0xd5b7, - 0x78c7, 0xd59f, 0x78bf, 0xd587, 0x78b6, 0xd56f, 0x78ae, 0xd558, - 0x78a6, 0xd540, 0x789d, 0xd528, 0x7895, 0xd511, 0x788c, 0xd4f9, - 0x7884, 0xd4e1, 0x787c, 0xd4ca, 0x7873, 0xd4b2, 0x786b, 0xd49a, - 0x7862, 0xd483, 0x7859, 0xd46b, 0x7851, 0xd453, 0x7848, 0xd43c, - 0x7840, 0xd424, 0x7837, 0xd40d, 0x782e, 0xd3f5, 0x7826, 0xd3dd, - 0x781d, 0xd3c6, 0x7814, 0xd3ae, 0x780c, 0xd397, 0x7803, 0xd37f, - 0x77fa, 0xd368, 0x77f1, 0xd350, 0x77e9, 0xd338, 0x77e0, 0xd321, - 0x77d7, 0xd309, 0x77ce, 0xd2f2, 0x77c5, 0xd2da, 0x77bc, 0xd2c3, - 0x77b4, 0xd2ab, 0x77ab, 0xd294, 0x77a2, 0xd27c, 0x7799, 0xd265, - 0x7790, 0xd24d, 0x7787, 0xd236, 0x777e, 0xd21e, 0x7775, 0xd207, - 0x776c, 0xd1ef, 0x7763, 0xd1d8, 0x775a, 0xd1c1, 0x7751, 0xd1a9, - 0x7747, 0xd192, 0x773e, 0xd17a, 0x7735, 0xd163, 0x772c, 0xd14b, - 0x7723, 0xd134, 0x771a, 0xd11d, 0x7710, 0xd105, 0x7707, 0xd0ee, - 0x76fe, 0xd0d7, 0x76f5, 0xd0bf, 0x76eb, 0xd0a8, 0x76e2, 0xd091, - 0x76d9, 0xd079, 0x76cf, 0xd062, 0x76c6, 0xd04b, 0x76bd, 0xd033, - 0x76b3, 0xd01c, 0x76aa, 0xd005, 0x76a0, 0xcfed, 0x7697, 0xcfd6, - 0x768e, 0xcfbf, 0x7684, 0xcfa7, 0x767b, 0xcf90, 0x7671, 0xcf79, - 0x7668, 0xcf62, 0x765e, 0xcf4a, 0x7654, 0xcf33, 0x764b, 0xcf1c, - 0x7641, 0xcf05, 0x7638, 0xceee, 0x762e, 0xced6, 0x7624, 0xcebf, - 0x761b, 0xcea8, 0x7611, 0xce91, 0x7607, 0xce7a, 0x75fd, 0xce62, - 0x75f4, 0xce4b, 0x75ea, 0xce34, 0x75e0, 0xce1d, 0x75d6, 0xce06, - 0x75cc, 0xcdef, 0x75c3, 0xcdd8, 0x75b9, 0xcdc0, 0x75af, 0xcda9, - 0x75a5, 0xcd92, 0x759b, 0xcd7b, 0x7591, 0xcd64, 0x7587, 0xcd4d, - 0x757d, 0xcd36, 0x7573, 0xcd1f, 0x7569, 0xcd08, 0x755f, 0xccf1, - 0x7555, 0xccda, 0x754b, 0xccc3, 0x7541, 0xccac, 0x7537, 0xcc95, - 0x752d, 0xcc7e, 0x7523, 0xcc67, 0x7519, 0xcc50, 0x750f, 0xcc39, - 0x7504, 0xcc22, 0x74fa, 0xcc0b, 0x74f0, 0xcbf4, 0x74e6, 0xcbdd, - 0x74db, 0xcbc6, 0x74d1, 0xcbaf, 0x74c7, 0xcb98, 0x74bd, 0xcb81, - 0x74b2, 0xcb6a, 0x74a8, 0xcb53, 0x749e, 0xcb3c, 0x7493, 0xcb25, - 0x7489, 0xcb0e, 0x747e, 0xcaf8, 0x7474, 0xcae1, 0x746a, 0xcaca, - 0x745f, 0xcab3, 0x7455, 0xca9c, 0x744a, 0xca85, 0x7440, 0xca6e, - 0x7435, 0xca58, 0x742b, 0xca41, 0x7420, 0xca2a, 0x7415, 0xca13, - 0x740b, 0xc9fc, 0x7400, 0xc9e6, 0x73f6, 0xc9cf, 0x73eb, 0xc9b8, - 0x73e0, 0xc9a1, 0x73d6, 0xc98b, 0x73cb, 0xc974, 0x73c0, 0xc95d, - 0x73b5, 0xc946, 0x73ab, 0xc930, 0x73a0, 0xc919, 0x7395, 0xc902, - 0x738a, 0xc8ec, 0x737f, 0xc8d5, 0x7375, 0xc8be, 0x736a, 0xc8a8, - 0x735f, 0xc891, 0x7354, 0xc87a, 0x7349, 0xc864, 0x733e, 0xc84d, - 0x7333, 0xc836, 0x7328, 0xc820, 0x731d, 0xc809, 0x7312, 0xc7f3, - 0x7307, 0xc7dc, 0x72fc, 0xc7c5, 0x72f1, 0xc7af, 0x72e6, 0xc798, - 0x72db, 0xc782, 0x72d0, 0xc76b, 0x72c5, 0xc755, 0x72ba, 0xc73e, - 0x72af, 0xc728, 0x72a3, 0xc711, 0x7298, 0xc6fa, 0x728d, 0xc6e4, - 0x7282, 0xc6ce, 0x7276, 0xc6b7, 0x726b, 0xc6a1, 0x7260, 0xc68a, - 0x7255, 0xc674, 0x7249, 0xc65d, 0x723e, 0xc647, 0x7233, 0xc630, - 0x7227, 0xc61a, 0x721c, 0xc603, 0x7211, 0xc5ed, 0x7205, 0xc5d7, - 0x71fa, 0xc5c0, 0x71ee, 0xc5aa, 0x71e3, 0xc594, 0x71d7, 0xc57d, - 0x71cc, 0xc567, 0x71c0, 0xc551, 0x71b5, 0xc53a, 0x71a9, 0xc524, - 0x719e, 0xc50e, 0x7192, 0xc4f7, 0x7186, 0xc4e1, 0x717b, 0xc4cb, - 0x716f, 0xc4b4, 0x7164, 0xc49e, 0x7158, 0xc488, 0x714c, 0xc472, - 0x7141, 0xc45b, 0x7135, 0xc445, 0x7129, 0xc42f, 0x711d, 0xc419, - 0x7112, 0xc403, 0x7106, 0xc3ec, 0x70fa, 0xc3d6, 0x70ee, 0xc3c0, - 0x70e2, 0xc3aa, 0x70d6, 0xc394, 0x70cb, 0xc37d, 0x70bf, 0xc367, - 0x70b3, 0xc351, 0x70a7, 0xc33b, 0x709b, 0xc325, 0x708f, 0xc30f, - 0x7083, 0xc2f9, 0x7077, 0xc2e3, 0x706b, 0xc2cd, 0x705f, 0xc2b7, - 0x7053, 0xc2a0, 0x7047, 0xc28a, 0x703b, 0xc274, 0x702f, 0xc25e, - 0x7023, 0xc248, 0x7016, 0xc232, 0x700a, 0xc21c, 0x6ffe, 0xc206, - 0x6ff2, 0xc1f0, 0x6fe6, 0xc1da, 0x6fda, 0xc1c4, 0x6fcd, 0xc1ae, - 0x6fc1, 0xc198, 0x6fb5, 0xc183, 0x6fa9, 0xc16d, 0x6f9c, 0xc157, - 0x6f90, 0xc141, 0x6f84, 0xc12b, 0x6f77, 0xc115, 0x6f6b, 0xc0ff, - 0x6f5f, 0xc0e9, 0x6f52, 0xc0d3, 0x6f46, 0xc0bd, 0x6f39, 0xc0a8, - 0x6f2d, 0xc092, 0x6f20, 0xc07c, 0x6f14, 0xc066, 0x6f07, 0xc050, - 0x6efb, 0xc03b, 0x6eee, 0xc025, 0x6ee2, 0xc00f, 0x6ed5, 0xbff9, - 0x6ec9, 0xbfe3, 0x6ebc, 0xbfce, 0x6eaf, 0xbfb8, 0x6ea3, 0xbfa2, - 0x6e96, 0xbf8d, 0x6e89, 0xbf77, 0x6e7d, 0xbf61, 0x6e70, 0xbf4b, - 0x6e63, 0xbf36, 0x6e57, 0xbf20, 0x6e4a, 0xbf0a, 0x6e3d, 0xbef5, - 0x6e30, 0xbedf, 0x6e24, 0xbeca, 0x6e17, 0xbeb4, 0x6e0a, 0xbe9e, - 0x6dfd, 0xbe89, 0x6df0, 0xbe73, 0x6de3, 0xbe5e, 0x6dd6, 0xbe48, - 0x6dca, 0xbe32, 0x6dbd, 0xbe1d, 0x6db0, 0xbe07, 0x6da3, 0xbdf2, - 0x6d96, 0xbddc, 0x6d89, 0xbdc7, 0x6d7c, 0xbdb1, 0x6d6f, 0xbd9c, - 0x6d62, 0xbd86, 0x6d55, 0xbd71, 0x6d48, 0xbd5b, 0x6d3a, 0xbd46, - 0x6d2d, 0xbd30, 0x6d20, 0xbd1b, 0x6d13, 0xbd06, 0x6d06, 0xbcf0, - 0x6cf9, 0xbcdb, 0x6cec, 0xbcc5, 0x6cde, 0xbcb0, 0x6cd1, 0xbc9b, - 0x6cc4, 0xbc85, 0x6cb7, 0xbc70, 0x6ca9, 0xbc5b, 0x6c9c, 0xbc45, - 0x6c8f, 0xbc30, 0x6c81, 0xbc1b, 0x6c74, 0xbc05, 0x6c67, 0xbbf0, - 0x6c59, 0xbbdb, 0x6c4c, 0xbbc5, 0x6c3f, 0xbbb0, 0x6c31, 0xbb9b, - 0x6c24, 0xbb86, 0x6c16, 0xbb70, 0x6c09, 0xbb5b, 0x6bfb, 0xbb46, - 0x6bee, 0xbb31, 0x6be0, 0xbb1c, 0x6bd3, 0xbb06, 0x6bc5, 0xbaf1, - 0x6bb8, 0xbadc, 0x6baa, 0xbac7, 0x6b9c, 0xbab2, 0x6b8f, 0xba9d, - 0x6b81, 0xba88, 0x6b73, 0xba73, 0x6b66, 0xba5d, 0x6b58, 0xba48, - 0x6b4a, 0xba33, 0x6b3d, 0xba1e, 0x6b2f, 0xba09, 0x6b21, 0xb9f4, - 0x6b13, 0xb9df, 0x6b06, 0xb9ca, 0x6af8, 0xb9b5, 0x6aea, 0xb9a0, - 0x6adc, 0xb98b, 0x6ace, 0xb976, 0x6ac1, 0xb961, 0x6ab3, 0xb94c, - 0x6aa5, 0xb937, 0x6a97, 0xb922, 0x6a89, 0xb90d, 0x6a7b, 0xb8f8, - 0x6a6d, 0xb8e4, 0x6a5f, 0xb8cf, 0x6a51, 0xb8ba, 0x6a43, 0xb8a5, - 0x6a35, 0xb890, 0x6a27, 0xb87b, 0x6a19, 0xb866, 0x6a0b, 0xb852, - 0x69fd, 0xb83d, 0x69ef, 0xb828, 0x69e1, 0xb813, 0x69d3, 0xb7fe, - 0x69c4, 0xb7ea, 0x69b6, 0xb7d5, 0x69a8, 0xb7c0, 0x699a, 0xb7ab, - 0x698c, 0xb797, 0x697d, 0xb782, 0x696f, 0xb76d, 0x6961, 0xb758, - 0x6953, 0xb744, 0x6944, 0xb72f, 0x6936, 0xb71a, 0x6928, 0xb706, - 0x6919, 0xb6f1, 0x690b, 0xb6dd, 0x68fd, 0xb6c8, 0x68ee, 0xb6b3, - 0x68e0, 0xb69f, 0x68d1, 0xb68a, 0x68c3, 0xb676, 0x68b5, 0xb661, - 0x68a6, 0xb64c, 0x6898, 0xb638, 0x6889, 0xb623, 0x687b, 0xb60f, - 0x686c, 0xb5fa, 0x685e, 0xb5e6, 0x684f, 0xb5d1, 0x6840, 0xb5bd, - 0x6832, 0xb5a8, 0x6823, 0xb594, 0x6815, 0xb57f, 0x6806, 0xb56b, - 0x67f7, 0xb557, 0x67e9, 0xb542, 0x67da, 0xb52e, 0x67cb, 0xb519, - 0x67bd, 0xb505, 0x67ae, 0xb4f1, 0x679f, 0xb4dc, 0x6790, 0xb4c8, - 0x6782, 0xb4b4, 0x6773, 0xb49f, 0x6764, 0xb48b, 0x6755, 0xb477, - 0x6746, 0xb462, 0x6737, 0xb44e, 0x6729, 0xb43a, 0x671a, 0xb426, - 0x670b, 0xb411, 0x66fc, 0xb3fd, 0x66ed, 0xb3e9, 0x66de, 0xb3d5, - 0x66cf, 0xb3c1, 0x66c0, 0xb3ac, 0x66b1, 0xb398, 0x66a2, 0xb384, - 0x6693, 0xb370, 0x6684, 0xb35c, 0x6675, 0xb348, 0x6666, 0xb334, - 0x6657, 0xb31f, 0x6648, 0xb30b, 0x6639, 0xb2f7, 0x6629, 0xb2e3, - 0x661a, 0xb2cf, 0x660b, 0xb2bb, 0x65fc, 0xb2a7, 0x65ed, 0xb293, - 0x65dd, 0xb27f, 0x65ce, 0xb26b, 0x65bf, 0xb257, 0x65b0, 0xb243, - 0x65a0, 0xb22f, 0x6591, 0xb21b, 0x6582, 0xb207, 0x6573, 0xb1f3, - 0x6563, 0xb1df, 0x6554, 0xb1cc, 0x6545, 0xb1b8, 0x6535, 0xb1a4, - 0x6526, 0xb190, 0x6516, 0xb17c, 0x6507, 0xb168, 0x64f7, 0xb154, - 0x64e8, 0xb141, 0x64d9, 0xb12d, 0x64c9, 0xb119, 0x64ba, 0xb105, - 0x64aa, 0xb0f1, 0x649b, 0xb0de, 0x648b, 0xb0ca, 0x647b, 0xb0b6, - 0x646c, 0xb0a2, 0x645c, 0xb08f, 0x644d, 0xb07b, 0x643d, 0xb067, - 0x642d, 0xb054, 0x641e, 0xb040, 0x640e, 0xb02c, 0x63fe, 0xb019, - 0x63ef, 0xb005, 0x63df, 0xaff1, 0x63cf, 0xafde, 0x63c0, 0xafca, - 0x63b0, 0xafb7, 0x63a0, 0xafa3, 0x6390, 0xaf90, 0x6380, 0xaf7c, - 0x6371, 0xaf69, 0x6361, 0xaf55, 0x6351, 0xaf41, 0x6341, 0xaf2e, - 0x6331, 0xaf1b, 0x6321, 0xaf07, 0x6311, 0xaef4, 0x6301, 0xaee0, - 0x62f2, 0xaecd, 0x62e2, 0xaeb9, 0x62d2, 0xaea6, 0x62c2, 0xae92, - 0x62b2, 0xae7f, 0x62a2, 0xae6c, 0x6292, 0xae58, 0x6282, 0xae45, - 0x6271, 0xae32, 0x6261, 0xae1e, 0x6251, 0xae0b, 0x6241, 0xadf8, - 0x6231, 0xade4, 0x6221, 0xadd1, 0x6211, 0xadbe, 0x6201, 0xadab, - 0x61f1, 0xad97, 0x61e0, 0xad84, 0x61d0, 0xad71, 0x61c0, 0xad5e, - 0x61b0, 0xad4b, 0x619f, 0xad37, 0x618f, 0xad24, 0x617f, 0xad11, - 0x616f, 0xacfe, 0x615e, 0xaceb, 0x614e, 0xacd8, 0x613e, 0xacc5, - 0x612d, 0xacb2, 0x611d, 0xac9e, 0x610d, 0xac8b, 0x60fc, 0xac78, - 0x60ec, 0xac65, 0x60db, 0xac52, 0x60cb, 0xac3f, 0x60ba, 0xac2c, - 0x60aa, 0xac19, 0x6099, 0xac06, 0x6089, 0xabf3, 0x6078, 0xabe0, - 0x6068, 0xabcd, 0x6057, 0xabbb, 0x6047, 0xaba8, 0x6036, 0xab95, - 0x6026, 0xab82, 0x6015, 0xab6f, 0x6004, 0xab5c, 0x5ff4, 0xab49, - 0x5fe3, 0xab36, 0x5fd3, 0xab24, 0x5fc2, 0xab11, 0x5fb1, 0xaafe, - 0x5fa0, 0xaaeb, 0x5f90, 0xaad8, 0x5f7f, 0xaac6, 0x5f6e, 0xaab3, - 0x5f5e, 0xaaa0, 0x5f4d, 0xaa8e, 0x5f3c, 0xaa7b, 0x5f2b, 0xaa68, - 0x5f1a, 0xaa55, 0x5f0a, 0xaa43, 0x5ef9, 0xaa30, 0x5ee8, 0xaa1d, - 0x5ed7, 0xaa0b, 0x5ec6, 0xa9f8, 0x5eb5, 0xa9e6, 0x5ea4, 0xa9d3, - 0x5e93, 0xa9c0, 0x5e82, 0xa9ae, 0x5e71, 0xa99b, 0x5e60, 0xa989, - 0x5e50, 0xa976, 0x5e3f, 0xa964, 0x5e2d, 0xa951, 0x5e1c, 0xa93f, - 0x5e0b, 0xa92c, 0x5dfa, 0xa91a, 0x5de9, 0xa907, 0x5dd8, 0xa8f5, - 0x5dc7, 0xa8e3, 0x5db6, 0xa8d0, 0x5da5, 0xa8be, 0x5d94, 0xa8ab, - 0x5d83, 0xa899, 0x5d71, 0xa887, 0x5d60, 0xa874, 0x5d4f, 0xa862, - 0x5d3e, 0xa850, 0x5d2d, 0xa83d, 0x5d1b, 0xa82b, 0x5d0a, 0xa819, - 0x5cf9, 0xa807, 0x5ce8, 0xa7f4, 0x5cd6, 0xa7e2, 0x5cc5, 0xa7d0, - 0x5cb4, 0xa7be, 0x5ca2, 0xa7ab, 0x5c91, 0xa799, 0x5c80, 0xa787, - 0x5c6e, 0xa775, 0x5c5d, 0xa763, 0x5c4b, 0xa751, 0x5c3a, 0xa73f, - 0x5c29, 0xa72c, 0x5c17, 0xa71a, 0x5c06, 0xa708, 0x5bf4, 0xa6f6, - 0x5be3, 0xa6e4, 0x5bd1, 0xa6d2, 0x5bc0, 0xa6c0, 0x5bae, 0xa6ae, - 0x5b9d, 0xa69c, 0x5b8b, 0xa68a, 0x5b79, 0xa678, 0x5b68, 0xa666, - 0x5b56, 0xa654, 0x5b45, 0xa642, 0x5b33, 0xa630, 0x5b21, 0xa61f, - 0x5b10, 0xa60d, 0x5afe, 0xa5fb, 0x5aec, 0xa5e9, 0x5adb, 0xa5d7, - 0x5ac9, 0xa5c5, 0x5ab7, 0xa5b3, 0x5aa5, 0xa5a2, 0x5a94, 0xa590, - 0x5a82, 0xa57e, 0x5a70, 0xa56c, 0x5a5e, 0xa55b, 0x5a4d, 0xa549, - 0x5a3b, 0xa537, 0x5a29, 0xa525, 0x5a17, 0xa514, 0x5a05, 0xa502, - 0x59f3, 0xa4f0, 0x59e1, 0xa4df, 0x59d0, 0xa4cd, 0x59be, 0xa4bb, - 0x59ac, 0xa4aa, 0x599a, 0xa498, 0x5988, 0xa487, 0x5976, 0xa475, - 0x5964, 0xa463, 0x5952, 0xa452, 0x5940, 0xa440, 0x592e, 0xa42f, - 0x591c, 0xa41d, 0x590a, 0xa40c, 0x58f8, 0xa3fa, 0x58e6, 0xa3e9, - 0x58d4, 0xa3d7, 0x58c1, 0xa3c6, 0x58af, 0xa3b5, 0x589d, 0xa3a3, - 0x588b, 0xa392, 0x5879, 0xa380, 0x5867, 0xa36f, 0x5855, 0xa35e, - 0x5842, 0xa34c, 0x5830, 0xa33b, 0x581e, 0xa32a, 0x580c, 0xa318, - 0x57f9, 0xa307, 0x57e7, 0xa2f6, 0x57d5, 0xa2e5, 0x57c3, 0xa2d3, - 0x57b0, 0xa2c2, 0x579e, 0xa2b1, 0x578c, 0xa2a0, 0x5779, 0xa28f, - 0x5767, 0xa27d, 0x5755, 0xa26c, 0x5742, 0xa25b, 0x5730, 0xa24a, - 0x571d, 0xa239, 0x570b, 0xa228, 0x56f9, 0xa217, 0x56e6, 0xa206, - 0x56d4, 0xa1f5, 0x56c1, 0xa1e4, 0x56af, 0xa1d3, 0x569c, 0xa1c1, - 0x568a, 0xa1b0, 0x5677, 0xa1a0, 0x5665, 0xa18f, 0x5652, 0xa17e, - 0x5640, 0xa16d, 0x562d, 0xa15c, 0x561a, 0xa14b, 0x5608, 0xa13a, - 0x55f5, 0xa129, 0x55e3, 0xa118, 0x55d0, 0xa107, 0x55bd, 0xa0f6, - 0x55ab, 0xa0e6, 0x5598, 0xa0d5, 0x5585, 0xa0c4, 0x5572, 0xa0b3, - 0x5560, 0xa0a2, 0x554d, 0xa092, 0x553a, 0xa081, 0x5528, 0xa070, - 0x5515, 0xa060, 0x5502, 0xa04f, 0x54ef, 0xa03e, 0x54dc, 0xa02d, - 0x54ca, 0xa01d, 0x54b7, 0xa00c, 0x54a4, 0x9ffc, 0x5491, 0x9feb, - 0x547e, 0x9fda, 0x546b, 0x9fca, 0x5458, 0x9fb9, 0x5445, 0x9fa9, - 0x5433, 0x9f98, 0x5420, 0x9f88, 0x540d, 0x9f77, 0x53fa, 0x9f67, - 0x53e7, 0x9f56, 0x53d4, 0x9f46, 0x53c1, 0x9f35, 0x53ae, 0x9f25, - 0x539b, 0x9f14, 0x5388, 0x9f04, 0x5375, 0x9ef3, 0x5362, 0x9ee3, - 0x534e, 0x9ed3, 0x533b, 0x9ec2, 0x5328, 0x9eb2, 0x5315, 0x9ea2, - 0x5302, 0x9e91, 0x52ef, 0x9e81, 0x52dc, 0x9e71, 0x52c9, 0x9e61, - 0x52b5, 0x9e50, 0x52a2, 0x9e40, 0x528f, 0x9e30, 0x527c, 0x9e20, - 0x5269, 0x9e0f, 0x5255, 0x9dff, 0x5242, 0x9def, 0x522f, 0x9ddf, - 0x521c, 0x9dcf, 0x5208, 0x9dbf, 0x51f5, 0x9daf, 0x51e2, 0x9d9f, - 0x51ce, 0x9d8f, 0x51bb, 0x9d7e, 0x51a8, 0x9d6e, 0x5194, 0x9d5e, - 0x5181, 0x9d4e, 0x516e, 0x9d3e, 0x515a, 0x9d2e, 0x5147, 0x9d1e, - 0x5133, 0x9d0e, 0x5120, 0x9cff, 0x510c, 0x9cef, 0x50f9, 0x9cdf, - 0x50e5, 0x9ccf, 0x50d2, 0x9cbf, 0x50bf, 0x9caf, 0x50ab, 0x9c9f, - 0x5097, 0x9c8f, 0x5084, 0x9c80, 0x5070, 0x9c70, 0x505d, 0x9c60, - 0x5049, 0x9c50, 0x5036, 0x9c40, 0x5022, 0x9c31, 0x500f, 0x9c21, - 0x4ffb, 0x9c11, 0x4fe7, 0x9c02, 0x4fd4, 0x9bf2, 0x4fc0, 0x9be2, - 0x4fac, 0x9bd3, 0x4f99, 0x9bc3, 0x4f85, 0x9bb3, 0x4f71, 0x9ba4, - 0x4f5e, 0x9b94, 0x4f4a, 0x9b85, 0x4f36, 0x9b75, 0x4f22, 0x9b65, - 0x4f0f, 0x9b56, 0x4efb, 0x9b46, 0x4ee7, 0x9b37, 0x4ed3, 0x9b27, - 0x4ebf, 0x9b18, 0x4eac, 0x9b09, 0x4e98, 0x9af9, 0x4e84, 0x9aea, - 0x4e70, 0x9ada, 0x4e5c, 0x9acb, 0x4e48, 0x9abb, 0x4e34, 0x9aac, - 0x4e21, 0x9a9d, 0x4e0d, 0x9a8d, 0x4df9, 0x9a7e, 0x4de5, 0x9a6f, - 0x4dd1, 0x9a60, 0x4dbd, 0x9a50, 0x4da9, 0x9a41, 0x4d95, 0x9a32, - 0x4d81, 0x9a23, 0x4d6d, 0x9a13, 0x4d59, 0x9a04, 0x4d45, 0x99f5, - 0x4d31, 0x99e6, 0x4d1d, 0x99d7, 0x4d09, 0x99c7, 0x4cf5, 0x99b8, - 0x4ce1, 0x99a9, 0x4ccc, 0x999a, 0x4cb8, 0x998b, 0x4ca4, 0x997c, - 0x4c90, 0x996d, 0x4c7c, 0x995e, 0x4c68, 0x994f, 0x4c54, 0x9940, - 0x4c3f, 0x9931, 0x4c2b, 0x9922, 0x4c17, 0x9913, 0x4c03, 0x9904, - 0x4bef, 0x98f5, 0x4bda, 0x98e6, 0x4bc6, 0x98d7, 0x4bb2, 0x98c9, - 0x4b9e, 0x98ba, 0x4b89, 0x98ab, 0x4b75, 0x989c, 0x4b61, 0x988d, - 0x4b4c, 0x987e, 0x4b38, 0x9870, 0x4b24, 0x9861, 0x4b0f, 0x9852, - 0x4afb, 0x9843, 0x4ae7, 0x9835, 0x4ad2, 0x9826, 0x4abe, 0x9817, - 0x4aa9, 0x9809, 0x4a95, 0x97fa, 0x4a81, 0x97eb, 0x4a6c, 0x97dd, - 0x4a58, 0x97ce, 0x4a43, 0x97c0, 0x4a2f, 0x97b1, 0x4a1a, 0x97a2, - 0x4a06, 0x9794, 0x49f1, 0x9785, 0x49dd, 0x9777, 0x49c8, 0x9768, - 0x49b4, 0x975a, 0x499f, 0x974b, 0x498a, 0x973d, 0x4976, 0x972f, - 0x4961, 0x9720, 0x494d, 0x9712, 0x4938, 0x9703, 0x4923, 0x96f5, - 0x490f, 0x96e7, 0x48fa, 0x96d8, 0x48e6, 0x96ca, 0x48d1, 0x96bc, - 0x48bc, 0x96ad, 0x48a8, 0x969f, 0x4893, 0x9691, 0x487e, 0x9683, - 0x4869, 0x9674, 0x4855, 0x9666, 0x4840, 0x9658, 0x482b, 0x964a, - 0x4816, 0x963c, 0x4802, 0x962d, 0x47ed, 0x961f, 0x47d8, 0x9611, - 0x47c3, 0x9603, 0x47ae, 0x95f5, 0x479a, 0x95e7, 0x4785, 0x95d9, - 0x4770, 0x95cb, 0x475b, 0x95bd, 0x4746, 0x95af, 0x4731, 0x95a1, - 0x471c, 0x9593, 0x4708, 0x9585, 0x46f3, 0x9577, 0x46de, 0x9569, - 0x46c9, 0x955b, 0x46b4, 0x954d, 0x469f, 0x953f, 0x468a, 0x9532, - 0x4675, 0x9524, 0x4660, 0x9516, 0x464b, 0x9508, 0x4636, 0x94fa, - 0x4621, 0x94ed, 0x460c, 0x94df, 0x45f7, 0x94d1, 0x45e2, 0x94c3, - 0x45cd, 0x94b6, 0x45b8, 0x94a8, 0x45a3, 0x949a, 0x458d, 0x948d, - 0x4578, 0x947f, 0x4563, 0x9471, 0x454e, 0x9464, 0x4539, 0x9456, - 0x4524, 0x9448, 0x450f, 0x943b, 0x44fa, 0x942d, 0x44e4, 0x9420, - 0x44cf, 0x9412, 0x44ba, 0x9405, 0x44a5, 0x93f7, 0x4490, 0x93ea, - 0x447a, 0x93dc, 0x4465, 0x93cf, 0x4450, 0x93c1, 0x443b, 0x93b4, - 0x4425, 0x93a7, 0x4410, 0x9399, 0x43fb, 0x938c, 0x43e5, 0x937f, - 0x43d0, 0x9371, 0x43bb, 0x9364, 0x43a5, 0x9357, 0x4390, 0x9349, - 0x437b, 0x933c, 0x4365, 0x932f, 0x4350, 0x9322, 0x433b, 0x9314, - 0x4325, 0x9307, 0x4310, 0x92fa, 0x42fa, 0x92ed, 0x42e5, 0x92e0, - 0x42d0, 0x92d3, 0x42ba, 0x92c6, 0x42a5, 0x92b8, 0x428f, 0x92ab, - 0x427a, 0x929e, 0x4264, 0x9291, 0x424f, 0x9284, 0x4239, 0x9277, - 0x4224, 0x926a, 0x420e, 0x925d, 0x41f9, 0x9250, 0x41e3, 0x9243, - 0x41ce, 0x9236, 0x41b8, 0x922a, 0x41a2, 0x921d, 0x418d, 0x9210, - 0x4177, 0x9203, 0x4162, 0x91f6, 0x414c, 0x91e9, 0x4136, 0x91dc, - 0x4121, 0x91d0, 0x410b, 0x91c3, 0x40f6, 0x91b6, 0x40e0, 0x91a9, - 0x40ca, 0x919d, 0x40b5, 0x9190, 0x409f, 0x9183, 0x4089, 0x9177, - 0x4073, 0x916a, 0x405e, 0x915d, 0x4048, 0x9151, 0x4032, 0x9144, - 0x401d, 0x9137, 0x4007, 0x912b, 0x3ff1, 0x911e, 0x3fdb, 0x9112, - 0x3fc5, 0x9105, 0x3fb0, 0x90f9, 0x3f9a, 0x90ec, 0x3f84, 0x90e0, - 0x3f6e, 0x90d3, 0x3f58, 0x90c7, 0x3f43, 0x90ba, 0x3f2d, 0x90ae, - 0x3f17, 0x90a1, 0x3f01, 0x9095, 0x3eeb, 0x9089, 0x3ed5, 0x907c, - 0x3ebf, 0x9070, 0x3ea9, 0x9064, 0x3e93, 0x9057, 0x3e7d, 0x904b, - 0x3e68, 0x903f, 0x3e52, 0x9033, 0x3e3c, 0x9026, 0x3e26, 0x901a, - 0x3e10, 0x900e, 0x3dfa, 0x9002, 0x3de4, 0x8ff6, 0x3dce, 0x8fea, - 0x3db8, 0x8fdd, 0x3da2, 0x8fd1, 0x3d8c, 0x8fc5, 0x3d76, 0x8fb9, - 0x3d60, 0x8fad, 0x3d49, 0x8fa1, 0x3d33, 0x8f95, 0x3d1d, 0x8f89, - 0x3d07, 0x8f7d, 0x3cf1, 0x8f71, 0x3cdb, 0x8f65, 0x3cc5, 0x8f59, - 0x3caf, 0x8f4d, 0x3c99, 0x8f41, 0x3c83, 0x8f35, 0x3c6c, 0x8f2a, - 0x3c56, 0x8f1e, 0x3c40, 0x8f12, 0x3c2a, 0x8f06, 0x3c14, 0x8efa, - 0x3bfd, 0x8eee, 0x3be7, 0x8ee3, 0x3bd1, 0x8ed7, 0x3bbb, 0x8ecb, - 0x3ba5, 0x8ebf, 0x3b8e, 0x8eb4, 0x3b78, 0x8ea8, 0x3b62, 0x8e9c, - 0x3b4c, 0x8e91, 0x3b35, 0x8e85, 0x3b1f, 0x8e7a, 0x3b09, 0x8e6e, - 0x3af2, 0x8e62, 0x3adc, 0x8e57, 0x3ac6, 0x8e4b, 0x3aaf, 0x8e40, - 0x3a99, 0x8e34, 0x3a83, 0x8e29, 0x3a6c, 0x8e1d, 0x3a56, 0x8e12, - 0x3a40, 0x8e06, 0x3a29, 0x8dfb, 0x3a13, 0x8def, 0x39fd, 0x8de4, - 0x39e6, 0x8dd9, 0x39d0, 0x8dcd, 0x39b9, 0x8dc2, 0x39a3, 0x8db7, - 0x398c, 0x8dab, 0x3976, 0x8da0, 0x395f, 0x8d95, 0x3949, 0x8d8a, - 0x3932, 0x8d7e, 0x391c, 0x8d73, 0x3906, 0x8d68, 0x38ef, 0x8d5d, - 0x38d8, 0x8d51, 0x38c2, 0x8d46, 0x38ab, 0x8d3b, 0x3895, 0x8d30, - 0x387e, 0x8d25, 0x3868, 0x8d1a, 0x3851, 0x8d0f, 0x383b, 0x8d04, - 0x3824, 0x8cf9, 0x380d, 0x8cee, 0x37f7, 0x8ce3, 0x37e0, 0x8cd8, - 0x37ca, 0x8ccd, 0x37b3, 0x8cc2, 0x379c, 0x8cb7, 0x3786, 0x8cac, - 0x376f, 0x8ca1, 0x3758, 0x8c96, 0x3742, 0x8c8b, 0x372b, 0x8c81, - 0x3714, 0x8c76, 0x36fe, 0x8c6b, 0x36e7, 0x8c60, 0x36d0, 0x8c55, - 0x36ba, 0x8c4b, 0x36a3, 0x8c40, 0x368c, 0x8c35, 0x3675, 0x8c2a, - 0x365f, 0x8c20, 0x3648, 0x8c15, 0x3631, 0x8c0a, 0x361a, 0x8c00, - 0x3604, 0x8bf5, 0x35ed, 0x8beb, 0x35d6, 0x8be0, 0x35bf, 0x8bd5, - 0x35a8, 0x8bcb, 0x3592, 0x8bc0, 0x357b, 0x8bb6, 0x3564, 0x8bab, - 0x354d, 0x8ba1, 0x3536, 0x8b96, 0x351f, 0x8b8c, 0x3508, 0x8b82, - 0x34f2, 0x8b77, 0x34db, 0x8b6d, 0x34c4, 0x8b62, 0x34ad, 0x8b58, - 0x3496, 0x8b4e, 0x347f, 0x8b43, 0x3468, 0x8b39, 0x3451, 0x8b2f, - 0x343a, 0x8b25, 0x3423, 0x8b1a, 0x340c, 0x8b10, 0x33f5, 0x8b06, - 0x33de, 0x8afc, 0x33c7, 0x8af1, 0x33b0, 0x8ae7, 0x3399, 0x8add, - 0x3382, 0x8ad3, 0x336b, 0x8ac9, 0x3354, 0x8abf, 0x333d, 0x8ab5, - 0x3326, 0x8aab, 0x330f, 0x8aa1, 0x32f8, 0x8a97, 0x32e1, 0x8a8d, - 0x32ca, 0x8a83, 0x32b3, 0x8a79, 0x329c, 0x8a6f, 0x3285, 0x8a65, - 0x326e, 0x8a5b, 0x3257, 0x8a51, 0x3240, 0x8a47, 0x3228, 0x8a3d, - 0x3211, 0x8a34, 0x31fa, 0x8a2a, 0x31e3, 0x8a20, 0x31cc, 0x8a16, - 0x31b5, 0x8a0c, 0x319e, 0x8a03, 0x3186, 0x89f9, 0x316f, 0x89ef, - 0x3158, 0x89e5, 0x3141, 0x89dc, 0x312a, 0x89d2, 0x3112, 0x89c8, - 0x30fb, 0x89bf, 0x30e4, 0x89b5, 0x30cd, 0x89ac, 0x30b6, 0x89a2, - 0x309e, 0x8998, 0x3087, 0x898f, 0x3070, 0x8985, 0x3059, 0x897c, - 0x3041, 0x8972, 0x302a, 0x8969, 0x3013, 0x8960, 0x2ffb, 0x8956, - 0x2fe4, 0x894d, 0x2fcd, 0x8943, 0x2fb5, 0x893a, 0x2f9e, 0x8931, - 0x2f87, 0x8927, 0x2f6f, 0x891e, 0x2f58, 0x8915, 0x2f41, 0x890b, - 0x2f29, 0x8902, 0x2f12, 0x88f9, 0x2efb, 0x88f0, 0x2ee3, 0x88e6, - 0x2ecc, 0x88dd, 0x2eb5, 0x88d4, 0x2e9d, 0x88cb, 0x2e86, 0x88c2, - 0x2e6e, 0x88b9, 0x2e57, 0x88af, 0x2e3f, 0x88a6, 0x2e28, 0x889d, - 0x2e11, 0x8894, 0x2df9, 0x888b, 0x2de2, 0x8882, 0x2dca, 0x8879, - 0x2db3, 0x8870, 0x2d9b, 0x8867, 0x2d84, 0x885e, 0x2d6c, 0x8855, - 0x2d55, 0x884c, 0x2d3d, 0x8844, 0x2d26, 0x883b, 0x2d0e, 0x8832, - 0x2cf7, 0x8829, 0x2cdf, 0x8820, 0x2cc8, 0x8817, 0x2cb0, 0x880f, - 0x2c98, 0x8806, 0x2c81, 0x87fd, 0x2c69, 0x87f4, 0x2c52, 0x87ec, - 0x2c3a, 0x87e3, 0x2c23, 0x87da, 0x2c0b, 0x87d2, 0x2bf3, 0x87c9, - 0x2bdc, 0x87c0, 0x2bc4, 0x87b8, 0x2bad, 0x87af, 0x2b95, 0x87a7, - 0x2b7d, 0x879e, 0x2b66, 0x8795, 0x2b4e, 0x878d, 0x2b36, 0x8784, - 0x2b1f, 0x877c, 0x2b07, 0x8774, 0x2aef, 0x876b, 0x2ad8, 0x8763, - 0x2ac0, 0x875a, 0x2aa8, 0x8752, 0x2a91, 0x874a, 0x2a79, 0x8741, - 0x2a61, 0x8739, 0x2a49, 0x8731, 0x2a32, 0x8728, 0x2a1a, 0x8720, - 0x2a02, 0x8718, 0x29eb, 0x870f, 0x29d3, 0x8707, 0x29bb, 0x86ff, - 0x29a3, 0x86f7, 0x298b, 0x86ef, 0x2974, 0x86e7, 0x295c, 0x86de, - 0x2944, 0x86d6, 0x292c, 0x86ce, 0x2915, 0x86c6, 0x28fd, 0x86be, - 0x28e5, 0x86b6, 0x28cd, 0x86ae, 0x28b5, 0x86a6, 0x289d, 0x869e, - 0x2886, 0x8696, 0x286e, 0x868e, 0x2856, 0x8686, 0x283e, 0x867e, - 0x2826, 0x8676, 0x280e, 0x866e, 0x27f6, 0x8667, 0x27df, 0x865f, - 0x27c7, 0x8657, 0x27af, 0x864f, 0x2797, 0x8647, 0x277f, 0x8640, - 0x2767, 0x8638, 0x274f, 0x8630, 0x2737, 0x8628, 0x271f, 0x8621, - 0x2707, 0x8619, 0x26ef, 0x8611, 0x26d8, 0x860a, 0x26c0, 0x8602, - 0x26a8, 0x85fb, 0x2690, 0x85f3, 0x2678, 0x85eb, 0x2660, 0x85e4, - 0x2648, 0x85dc, 0x2630, 0x85d5, 0x2618, 0x85cd, 0x2600, 0x85c6, - 0x25e8, 0x85be, 0x25d0, 0x85b7, 0x25b8, 0x85b0, 0x25a0, 0x85a8, - 0x2588, 0x85a1, 0x2570, 0x8599, 0x2558, 0x8592, 0x2540, 0x858b, - 0x2528, 0x8583, 0x250f, 0x857c, 0x24f7, 0x8575, 0x24df, 0x856e, - 0x24c7, 0x8566, 0x24af, 0x855f, 0x2497, 0x8558, 0x247f, 0x8551, - 0x2467, 0x854a, 0x244f, 0x8543, 0x2437, 0x853b, 0x241f, 0x8534, - 0x2407, 0x852d, 0x23ee, 0x8526, 0x23d6, 0x851f, 0x23be, 0x8518, - 0x23a6, 0x8511, 0x238e, 0x850a, 0x2376, 0x8503, 0x235e, 0x84fc, - 0x2345, 0x84f5, 0x232d, 0x84ee, 0x2315, 0x84e7, 0x22fd, 0x84e1, - 0x22e5, 0x84da, 0x22cd, 0x84d3, 0x22b4, 0x84cc, 0x229c, 0x84c5, - 0x2284, 0x84be, 0x226c, 0x84b8, 0x2254, 0x84b1, 0x223b, 0x84aa, - 0x2223, 0x84a3, 0x220b, 0x849d, 0x21f3, 0x8496, 0x21da, 0x848f, - 0x21c2, 0x8489, 0x21aa, 0x8482, 0x2192, 0x847c, 0x2179, 0x8475, - 0x2161, 0x846e, 0x2149, 0x8468, 0x2131, 0x8461, 0x2118, 0x845b, - 0x2100, 0x8454, 0x20e8, 0x844e, 0x20d0, 0x8447, 0x20b7, 0x8441, - 0x209f, 0x843b, 0x2087, 0x8434, 0x206e, 0x842e, 0x2056, 0x8427, - 0x203e, 0x8421, 0x2025, 0x841b, 0x200d, 0x8415, 0x1ff5, 0x840e, - 0x1fdc, 0x8408, 0x1fc4, 0x8402, 0x1fac, 0x83fb, 0x1f93, 0x83f5, - 0x1f7b, 0x83ef, 0x1f63, 0x83e9, 0x1f4a, 0x83e3, 0x1f32, 0x83dd, - 0x1f19, 0x83d7, 0x1f01, 0x83d0, 0x1ee9, 0x83ca, 0x1ed0, 0x83c4, - 0x1eb8, 0x83be, 0x1ea0, 0x83b8, 0x1e87, 0x83b2, 0x1e6f, 0x83ac, - 0x1e56, 0x83a6, 0x1e3e, 0x83a0, 0x1e25, 0x839a, 0x1e0d, 0x8394, - 0x1df5, 0x838f, 0x1ddc, 0x8389, 0x1dc4, 0x8383, 0x1dab, 0x837d, - 0x1d93, 0x8377, 0x1d7a, 0x8371, 0x1d62, 0x836c, 0x1d49, 0x8366, - 0x1d31, 0x8360, 0x1d18, 0x835a, 0x1d00, 0x8355, 0x1ce8, 0x834f, - 0x1ccf, 0x8349, 0x1cb7, 0x8344, 0x1c9e, 0x833e, 0x1c86, 0x8338, - 0x1c6d, 0x8333, 0x1c55, 0x832d, 0x1c3c, 0x8328, 0x1c24, 0x8322, - 0x1c0b, 0x831d, 0x1bf2, 0x8317, 0x1bda, 0x8312, 0x1bc1, 0x830c, - 0x1ba9, 0x8307, 0x1b90, 0x8301, 0x1b78, 0x82fc, 0x1b5f, 0x82f7, - 0x1b47, 0x82f1, 0x1b2e, 0x82ec, 0x1b16, 0x82e7, 0x1afd, 0x82e1, - 0x1ae4, 0x82dc, 0x1acc, 0x82d7, 0x1ab3, 0x82d1, 0x1a9b, 0x82cc, - 0x1a82, 0x82c7, 0x1a6a, 0x82c2, 0x1a51, 0x82bd, 0x1a38, 0x82b7, - 0x1a20, 0x82b2, 0x1a07, 0x82ad, 0x19ef, 0x82a8, 0x19d6, 0x82a3, - 0x19bd, 0x829e, 0x19a5, 0x8299, 0x198c, 0x8294, 0x1973, 0x828f, - 0x195b, 0x828a, 0x1942, 0x8285, 0x192a, 0x8280, 0x1911, 0x827b, - 0x18f8, 0x8276, 0x18e0, 0x8271, 0x18c7, 0x826c, 0x18ae, 0x8268, - 0x1896, 0x8263, 0x187d, 0x825e, 0x1864, 0x8259, 0x184c, 0x8254, - 0x1833, 0x8250, 0x181a, 0x824b, 0x1802, 0x8246, 0x17e9, 0x8241, - 0x17d0, 0x823d, 0x17b7, 0x8238, 0x179f, 0x8233, 0x1786, 0x822f, - 0x176d, 0x822a, 0x1755, 0x8226, 0x173c, 0x8221, 0x1723, 0x821c, - 0x170a, 0x8218, 0x16f2, 0x8213, 0x16d9, 0x820f, 0x16c0, 0x820a, - 0x16a8, 0x8206, 0x168f, 0x8201, 0x1676, 0x81fd, 0x165d, 0x81f9, - 0x1645, 0x81f4, 0x162c, 0x81f0, 0x1613, 0x81ec, 0x15fa, 0x81e7, - 0x15e2, 0x81e3, 0x15c9, 0x81df, 0x15b0, 0x81da, 0x1597, 0x81d6, - 0x157f, 0x81d2, 0x1566, 0x81ce, 0x154d, 0x81c9, 0x1534, 0x81c5, - 0x151b, 0x81c1, 0x1503, 0x81bd, 0x14ea, 0x81b9, 0x14d1, 0x81b5, - 0x14b8, 0x81b1, 0x149f, 0x81ad, 0x1487, 0x81a9, 0x146e, 0x81a5, - 0x1455, 0x81a1, 0x143c, 0x819d, 0x1423, 0x8199, 0x140b, 0x8195, - 0x13f2, 0x8191, 0x13d9, 0x818d, 0x13c0, 0x8189, 0x13a7, 0x8185, - 0x138e, 0x8181, 0x1376, 0x817d, 0x135d, 0x817a, 0x1344, 0x8176, - 0x132b, 0x8172, 0x1312, 0x816e, 0x12f9, 0x816b, 0x12e0, 0x8167, - 0x12c8, 0x8163, 0x12af, 0x815f, 0x1296, 0x815c, 0x127d, 0x8158, - 0x1264, 0x8155, 0x124b, 0x8151, 0x1232, 0x814d, 0x1219, 0x814a, - 0x1201, 0x8146, 0x11e8, 0x8143, 0x11cf, 0x813f, 0x11b6, 0x813c, - 0x119d, 0x8138, 0x1184, 0x8135, 0x116b, 0x8131, 0x1152, 0x812e, - 0x1139, 0x812b, 0x1121, 0x8127, 0x1108, 0x8124, 0x10ef, 0x8121, - 0x10d6, 0x811d, 0x10bd, 0x811a, 0x10a4, 0x8117, 0x108b, 0x8113, - 0x1072, 0x8110, 0x1059, 0x810d, 0x1040, 0x810a, 0x1027, 0x8107, - 0x100e, 0x8103, 0xff5, 0x8100, 0xfdd, 0x80fd, 0xfc4, 0x80fa, - 0xfab, 0x80f7, 0xf92, 0x80f4, 0xf79, 0x80f1, 0xf60, 0x80ee, - 0xf47, 0x80eb, 0xf2e, 0x80e8, 0xf15, 0x80e5, 0xefc, 0x80e2, - 0xee3, 0x80df, 0xeca, 0x80dc, 0xeb1, 0x80d9, 0xe98, 0x80d6, - 0xe7f, 0x80d3, 0xe66, 0x80d1, 0xe4d, 0x80ce, 0xe34, 0x80cb, - 0xe1b, 0x80c8, 0xe02, 0x80c5, 0xde9, 0x80c3, 0xdd0, 0x80c0, - 0xdb7, 0x80bd, 0xd9e, 0x80bb, 0xd85, 0x80b8, 0xd6c, 0x80b5, - 0xd53, 0x80b3, 0xd3a, 0x80b0, 0xd21, 0x80ad, 0xd08, 0x80ab, - 0xcef, 0x80a8, 0xcd6, 0x80a6, 0xcbd, 0x80a3, 0xca4, 0x80a1, - 0xc8b, 0x809e, 0xc72, 0x809c, 0xc59, 0x8099, 0xc40, 0x8097, - 0xc27, 0x8095, 0xc0e, 0x8092, 0xbf5, 0x8090, 0xbdc, 0x808e, - 0xbc3, 0x808b, 0xbaa, 0x8089, 0xb91, 0x8087, 0xb78, 0x8084, - 0xb5f, 0x8082, 0xb46, 0x8080, 0xb2d, 0x807e, 0xb14, 0x807b, - 0xafb, 0x8079, 0xae2, 0x8077, 0xac9, 0x8075, 0xab0, 0x8073, - 0xa97, 0x8071, 0xa7e, 0x806f, 0xa65, 0x806d, 0xa4c, 0x806b, - 0xa33, 0x8069, 0xa19, 0x8067, 0xa00, 0x8065, 0x9e7, 0x8063, - 0x9ce, 0x8061, 0x9b5, 0x805f, 0x99c, 0x805d, 0x983, 0x805b, - 0x96a, 0x8059, 0x951, 0x8057, 0x938, 0x8056, 0x91f, 0x8054, - 0x906, 0x8052, 0x8ed, 0x8050, 0x8d4, 0x804f, 0x8bb, 0x804d, - 0x8a2, 0x804b, 0x888, 0x8049, 0x86f, 0x8048, 0x856, 0x8046, - 0x83d, 0x8044, 0x824, 0x8043, 0x80b, 0x8041, 0x7f2, 0x8040, - 0x7d9, 0x803e, 0x7c0, 0x803d, 0x7a7, 0x803b, 0x78e, 0x803a, - 0x775, 0x8038, 0x75b, 0x8037, 0x742, 0x8035, 0x729, 0x8034, - 0x710, 0x8032, 0x6f7, 0x8031, 0x6de, 0x8030, 0x6c5, 0x802e, - 0x6ac, 0x802d, 0x693, 0x802c, 0x67a, 0x802a, 0x660, 0x8029, - 0x647, 0x8028, 0x62e, 0x8027, 0x615, 0x8026, 0x5fc, 0x8024, - 0x5e3, 0x8023, 0x5ca, 0x8022, 0x5b1, 0x8021, 0x598, 0x8020, - 0x57f, 0x801f, 0x565, 0x801e, 0x54c, 0x801d, 0x533, 0x801c, - 0x51a, 0x801b, 0x501, 0x801a, 0x4e8, 0x8019, 0x4cf, 0x8018, - 0x4b6, 0x8017, 0x49c, 0x8016, 0x483, 0x8015, 0x46a, 0x8014, - 0x451, 0x8013, 0x438, 0x8012, 0x41f, 0x8012, 0x406, 0x8011, - 0x3ed, 0x8010, 0x3d4, 0x800f, 0x3ba, 0x800e, 0x3a1, 0x800e, - 0x388, 0x800d, 0x36f, 0x800c, 0x356, 0x800c, 0x33d, 0x800b, - 0x324, 0x800a, 0x30b, 0x800a, 0x2f1, 0x8009, 0x2d8, 0x8009, - 0x2bf, 0x8008, 0x2a6, 0x8008, 0x28d, 0x8007, 0x274, 0x8007, - 0x25b, 0x8006, 0x242, 0x8006, 0x228, 0x8005, 0x20f, 0x8005, - 0x1f6, 0x8004, 0x1dd, 0x8004, 0x1c4, 0x8004, 0x1ab, 0x8003, - 0x192, 0x8003, 0x178, 0x8003, 0x15f, 0x8002, 0x146, 0x8002, - 0x12d, 0x8002, 0x114, 0x8002, 0xfb, 0x8001, 0xe2, 0x8001, - 0xc9, 0x8001, 0xaf, 0x8001, 0x96, 0x8001, 0x7d, 0x8001, - 0x64, 0x8001, 0x4b, 0x8001, 0x32, 0x8001, 0x19, 0x8001, -}; - -static const q15_t ALIGN4 WeightsQ15_8192[16384] = { - 0x7fff, 0x0, 0x7fff, 0xfffa, 0x7fff, 0xfff4, 0x7fff, 0xffee, - 0x7fff, 0xffe7, 0x7fff, 0xffe1, 0x7fff, 0xffdb, 0x7fff, 0xffd5, - 0x7fff, 0xffce, 0x7fff, 0xffc8, 0x7fff, 0xffc2, 0x7fff, 0xffbb, - 0x7fff, 0xffb5, 0x7fff, 0xffaf, 0x7fff, 0xffa9, 0x7fff, 0xffa2, - 0x7fff, 0xff9c, 0x7fff, 0xff96, 0x7fff, 0xff8f, 0x7fff, 0xff89, - 0x7fff, 0xff83, 0x7fff, 0xff7d, 0x7fff, 0xff76, 0x7fff, 0xff70, - 0x7fff, 0xff6a, 0x7fff, 0xff63, 0x7fff, 0xff5d, 0x7fff, 0xff57, - 0x7fff, 0xff51, 0x7fff, 0xff4a, 0x7fff, 0xff44, 0x7fff, 0xff3e, - 0x7fff, 0xff37, 0x7fff, 0xff31, 0x7fff, 0xff2b, 0x7fff, 0xff25, - 0x7fff, 0xff1e, 0x7fff, 0xff18, 0x7fff, 0xff12, 0x7fff, 0xff0b, - 0x7fff, 0xff05, 0x7ffe, 0xfeff, 0x7ffe, 0xfef9, 0x7ffe, 0xfef2, - 0x7ffe, 0xfeec, 0x7ffe, 0xfee6, 0x7ffe, 0xfedf, 0x7ffe, 0xfed9, - 0x7ffe, 0xfed3, 0x7ffe, 0xfecd, 0x7ffe, 0xfec6, 0x7ffe, 0xfec0, - 0x7ffe, 0xfeba, 0x7ffe, 0xfeb3, 0x7ffe, 0xfead, 0x7ffe, 0xfea7, - 0x7ffe, 0xfea1, 0x7ffe, 0xfe9a, 0x7ffd, 0xfe94, 0x7ffd, 0xfe8e, - 0x7ffd, 0xfe88, 0x7ffd, 0xfe81, 0x7ffd, 0xfe7b, 0x7ffd, 0xfe75, - 0x7ffd, 0xfe6e, 0x7ffd, 0xfe68, 0x7ffd, 0xfe62, 0x7ffd, 0xfe5c, - 0x7ffd, 0xfe55, 0x7ffd, 0xfe4f, 0x7ffd, 0xfe49, 0x7ffc, 0xfe42, - 0x7ffc, 0xfe3c, 0x7ffc, 0xfe36, 0x7ffc, 0xfe30, 0x7ffc, 0xfe29, - 0x7ffc, 0xfe23, 0x7ffc, 0xfe1d, 0x7ffc, 0xfe16, 0x7ffc, 0xfe10, - 0x7ffc, 0xfe0a, 0x7ffc, 0xfe04, 0x7ffb, 0xfdfd, 0x7ffb, 0xfdf7, - 0x7ffb, 0xfdf1, 0x7ffb, 0xfdea, 0x7ffb, 0xfde4, 0x7ffb, 0xfdde, - 0x7ffb, 0xfdd8, 0x7ffb, 0xfdd1, 0x7ffb, 0xfdcb, 0x7ffb, 0xfdc5, - 0x7ffa, 0xfdbe, 0x7ffa, 0xfdb8, 0x7ffa, 0xfdb2, 0x7ffa, 0xfdac, - 0x7ffa, 0xfda5, 0x7ffa, 0xfd9f, 0x7ffa, 0xfd99, 0x7ffa, 0xfd93, - 0x7ff9, 0xfd8c, 0x7ff9, 0xfd86, 0x7ff9, 0xfd80, 0x7ff9, 0xfd79, - 0x7ff9, 0xfd73, 0x7ff9, 0xfd6d, 0x7ff9, 0xfd67, 0x7ff9, 0xfd60, - 0x7ff8, 0xfd5a, 0x7ff8, 0xfd54, 0x7ff8, 0xfd4d, 0x7ff8, 0xfd47, - 0x7ff8, 0xfd41, 0x7ff8, 0xfd3b, 0x7ff8, 0xfd34, 0x7ff8, 0xfd2e, - 0x7ff7, 0xfd28, 0x7ff7, 0xfd21, 0x7ff7, 0xfd1b, 0x7ff7, 0xfd15, - 0x7ff7, 0xfd0f, 0x7ff7, 0xfd08, 0x7ff7, 0xfd02, 0x7ff6, 0xfcfc, - 0x7ff6, 0xfcf5, 0x7ff6, 0xfcef, 0x7ff6, 0xfce9, 0x7ff6, 0xfce3, - 0x7ff6, 0xfcdc, 0x7ff5, 0xfcd6, 0x7ff5, 0xfcd0, 0x7ff5, 0xfcc9, - 0x7ff5, 0xfcc3, 0x7ff5, 0xfcbd, 0x7ff5, 0xfcb7, 0x7ff5, 0xfcb0, - 0x7ff4, 0xfcaa, 0x7ff4, 0xfca4, 0x7ff4, 0xfc9e, 0x7ff4, 0xfc97, - 0x7ff4, 0xfc91, 0x7ff4, 0xfc8b, 0x7ff3, 0xfc84, 0x7ff3, 0xfc7e, - 0x7ff3, 0xfc78, 0x7ff3, 0xfc72, 0x7ff3, 0xfc6b, 0x7ff2, 0xfc65, - 0x7ff2, 0xfc5f, 0x7ff2, 0xfc58, 0x7ff2, 0xfc52, 0x7ff2, 0xfc4c, - 0x7ff2, 0xfc46, 0x7ff1, 0xfc3f, 0x7ff1, 0xfc39, 0x7ff1, 0xfc33, - 0x7ff1, 0xfc2c, 0x7ff1, 0xfc26, 0x7ff0, 0xfc20, 0x7ff0, 0xfc1a, - 0x7ff0, 0xfc13, 0x7ff0, 0xfc0d, 0x7ff0, 0xfc07, 0x7fef, 0xfc01, - 0x7fef, 0xfbfa, 0x7fef, 0xfbf4, 0x7fef, 0xfbee, 0x7fef, 0xfbe7, - 0x7fee, 0xfbe1, 0x7fee, 0xfbdb, 0x7fee, 0xfbd5, 0x7fee, 0xfbce, - 0x7fee, 0xfbc8, 0x7fed, 0xfbc2, 0x7fed, 0xfbbb, 0x7fed, 0xfbb5, - 0x7fed, 0xfbaf, 0x7fed, 0xfba9, 0x7fec, 0xfba2, 0x7fec, 0xfb9c, - 0x7fec, 0xfb96, 0x7fec, 0xfb8f, 0x7fec, 0xfb89, 0x7feb, 0xfb83, - 0x7feb, 0xfb7d, 0x7feb, 0xfb76, 0x7feb, 0xfb70, 0x7fea, 0xfb6a, - 0x7fea, 0xfb64, 0x7fea, 0xfb5d, 0x7fea, 0xfb57, 0x7fea, 0xfb51, - 0x7fe9, 0xfb4a, 0x7fe9, 0xfb44, 0x7fe9, 0xfb3e, 0x7fe9, 0xfb38, - 0x7fe8, 0xfb31, 0x7fe8, 0xfb2b, 0x7fe8, 0xfb25, 0x7fe8, 0xfb1e, - 0x7fe7, 0xfb18, 0x7fe7, 0xfb12, 0x7fe7, 0xfb0c, 0x7fe7, 0xfb05, - 0x7fe6, 0xfaff, 0x7fe6, 0xfaf9, 0x7fe6, 0xfaf3, 0x7fe6, 0xfaec, - 0x7fe5, 0xfae6, 0x7fe5, 0xfae0, 0x7fe5, 0xfad9, 0x7fe5, 0xfad3, - 0x7fe4, 0xfacd, 0x7fe4, 0xfac7, 0x7fe4, 0xfac0, 0x7fe4, 0xfaba, - 0x7fe3, 0xfab4, 0x7fe3, 0xfaad, 0x7fe3, 0xfaa7, 0x7fe3, 0xfaa1, - 0x7fe2, 0xfa9b, 0x7fe2, 0xfa94, 0x7fe2, 0xfa8e, 0x7fe2, 0xfa88, - 0x7fe1, 0xfa81, 0x7fe1, 0xfa7b, 0x7fe1, 0xfa75, 0x7fe0, 0xfa6f, - 0x7fe0, 0xfa68, 0x7fe0, 0xfa62, 0x7fe0, 0xfa5c, 0x7fdf, 0xfa56, - 0x7fdf, 0xfa4f, 0x7fdf, 0xfa49, 0x7fdf, 0xfa43, 0x7fde, 0xfa3c, - 0x7fde, 0xfa36, 0x7fde, 0xfa30, 0x7fdd, 0xfa2a, 0x7fdd, 0xfa23, - 0x7fdd, 0xfa1d, 0x7fdd, 0xfa17, 0x7fdc, 0xfa11, 0x7fdc, 0xfa0a, - 0x7fdc, 0xfa04, 0x7fdb, 0xf9fe, 0x7fdb, 0xf9f7, 0x7fdb, 0xf9f1, - 0x7fda, 0xf9eb, 0x7fda, 0xf9e5, 0x7fda, 0xf9de, 0x7fda, 0xf9d8, - 0x7fd9, 0xf9d2, 0x7fd9, 0xf9cb, 0x7fd9, 0xf9c5, 0x7fd8, 0xf9bf, - 0x7fd8, 0xf9b9, 0x7fd8, 0xf9b2, 0x7fd7, 0xf9ac, 0x7fd7, 0xf9a6, - 0x7fd7, 0xf9a0, 0x7fd6, 0xf999, 0x7fd6, 0xf993, 0x7fd6, 0xf98d, - 0x7fd6, 0xf986, 0x7fd5, 0xf980, 0x7fd5, 0xf97a, 0x7fd5, 0xf974, - 0x7fd4, 0xf96d, 0x7fd4, 0xf967, 0x7fd4, 0xf961, 0x7fd3, 0xf95b, - 0x7fd3, 0xf954, 0x7fd3, 0xf94e, 0x7fd2, 0xf948, 0x7fd2, 0xf941, - 0x7fd2, 0xf93b, 0x7fd1, 0xf935, 0x7fd1, 0xf92f, 0x7fd1, 0xf928, - 0x7fd0, 0xf922, 0x7fd0, 0xf91c, 0x7fd0, 0xf916, 0x7fcf, 0xf90f, - 0x7fcf, 0xf909, 0x7fcf, 0xf903, 0x7fce, 0xf8fc, 0x7fce, 0xf8f6, - 0x7fce, 0xf8f0, 0x7fcd, 0xf8ea, 0x7fcd, 0xf8e3, 0x7fcd, 0xf8dd, - 0x7fcc, 0xf8d7, 0x7fcc, 0xf8d0, 0x7fcb, 0xf8ca, 0x7fcb, 0xf8c4, - 0x7fcb, 0xf8be, 0x7fca, 0xf8b7, 0x7fca, 0xf8b1, 0x7fca, 0xf8ab, - 0x7fc9, 0xf8a5, 0x7fc9, 0xf89e, 0x7fc9, 0xf898, 0x7fc8, 0xf892, - 0x7fc8, 0xf88b, 0x7fc7, 0xf885, 0x7fc7, 0xf87f, 0x7fc7, 0xf879, - 0x7fc6, 0xf872, 0x7fc6, 0xf86c, 0x7fc6, 0xf866, 0x7fc5, 0xf860, - 0x7fc5, 0xf859, 0x7fc5, 0xf853, 0x7fc4, 0xf84d, 0x7fc4, 0xf846, - 0x7fc3, 0xf840, 0x7fc3, 0xf83a, 0x7fc3, 0xf834, 0x7fc2, 0xf82d, - 0x7fc2, 0xf827, 0x7fc1, 0xf821, 0x7fc1, 0xf81b, 0x7fc1, 0xf814, - 0x7fc0, 0xf80e, 0x7fc0, 0xf808, 0x7fc0, 0xf802, 0x7fbf, 0xf7fb, - 0x7fbf, 0xf7f5, 0x7fbe, 0xf7ef, 0x7fbe, 0xf7e8, 0x7fbe, 0xf7e2, - 0x7fbd, 0xf7dc, 0x7fbd, 0xf7d6, 0x7fbc, 0xf7cf, 0x7fbc, 0xf7c9, - 0x7fbc, 0xf7c3, 0x7fbb, 0xf7bd, 0x7fbb, 0xf7b6, 0x7fba, 0xf7b0, - 0x7fba, 0xf7aa, 0x7fb9, 0xf7a3, 0x7fb9, 0xf79d, 0x7fb9, 0xf797, - 0x7fb8, 0xf791, 0x7fb8, 0xf78a, 0x7fb7, 0xf784, 0x7fb7, 0xf77e, - 0x7fb7, 0xf778, 0x7fb6, 0xf771, 0x7fb6, 0xf76b, 0x7fb5, 0xf765, - 0x7fb5, 0xf75e, 0x7fb4, 0xf758, 0x7fb4, 0xf752, 0x7fb4, 0xf74c, - 0x7fb3, 0xf745, 0x7fb3, 0xf73f, 0x7fb2, 0xf739, 0x7fb2, 0xf733, - 0x7fb1, 0xf72c, 0x7fb1, 0xf726, 0x7fb1, 0xf720, 0x7fb0, 0xf71a, - 0x7fb0, 0xf713, 0x7faf, 0xf70d, 0x7faf, 0xf707, 0x7fae, 0xf700, - 0x7fae, 0xf6fa, 0x7fae, 0xf6f4, 0x7fad, 0xf6ee, 0x7fad, 0xf6e7, - 0x7fac, 0xf6e1, 0x7fac, 0xf6db, 0x7fab, 0xf6d5, 0x7fab, 0xf6ce, - 0x7faa, 0xf6c8, 0x7faa, 0xf6c2, 0x7fa9, 0xf6bc, 0x7fa9, 0xf6b5, - 0x7fa9, 0xf6af, 0x7fa8, 0xf6a9, 0x7fa8, 0xf6a2, 0x7fa7, 0xf69c, - 0x7fa7, 0xf696, 0x7fa6, 0xf690, 0x7fa6, 0xf689, 0x7fa5, 0xf683, - 0x7fa5, 0xf67d, 0x7fa4, 0xf677, 0x7fa4, 0xf670, 0x7fa3, 0xf66a, - 0x7fa3, 0xf664, 0x7fa3, 0xf65e, 0x7fa2, 0xf657, 0x7fa2, 0xf651, - 0x7fa1, 0xf64b, 0x7fa1, 0xf644, 0x7fa0, 0xf63e, 0x7fa0, 0xf638, - 0x7f9f, 0xf632, 0x7f9f, 0xf62b, 0x7f9e, 0xf625, 0x7f9e, 0xf61f, - 0x7f9d, 0xf619, 0x7f9d, 0xf612, 0x7f9c, 0xf60c, 0x7f9c, 0xf606, - 0x7f9b, 0xf600, 0x7f9b, 0xf5f9, 0x7f9a, 0xf5f3, 0x7f9a, 0xf5ed, - 0x7f99, 0xf5e7, 0x7f99, 0xf5e0, 0x7f98, 0xf5da, 0x7f98, 0xf5d4, - 0x7f97, 0xf5cd, 0x7f97, 0xf5c7, 0x7f96, 0xf5c1, 0x7f96, 0xf5bb, - 0x7f95, 0xf5b4, 0x7f95, 0xf5ae, 0x7f94, 0xf5a8, 0x7f94, 0xf5a2, - 0x7f93, 0xf59b, 0x7f93, 0xf595, 0x7f92, 0xf58f, 0x7f92, 0xf589, - 0x7f91, 0xf582, 0x7f91, 0xf57c, 0x7f90, 0xf576, 0x7f90, 0xf570, - 0x7f8f, 0xf569, 0x7f8f, 0xf563, 0x7f8e, 0xf55d, 0x7f8e, 0xf556, - 0x7f8d, 0xf550, 0x7f8d, 0xf54a, 0x7f8c, 0xf544, 0x7f8b, 0xf53d, - 0x7f8b, 0xf537, 0x7f8a, 0xf531, 0x7f8a, 0xf52b, 0x7f89, 0xf524, - 0x7f89, 0xf51e, 0x7f88, 0xf518, 0x7f88, 0xf512, 0x7f87, 0xf50b, - 0x7f87, 0xf505, 0x7f86, 0xf4ff, 0x7f86, 0xf4f9, 0x7f85, 0xf4f2, - 0x7f85, 0xf4ec, 0x7f84, 0xf4e6, 0x7f83, 0xf4e0, 0x7f83, 0xf4d9, - 0x7f82, 0xf4d3, 0x7f82, 0xf4cd, 0x7f81, 0xf4c6, 0x7f81, 0xf4c0, - 0x7f80, 0xf4ba, 0x7f80, 0xf4b4, 0x7f7f, 0xf4ad, 0x7f7e, 0xf4a7, - 0x7f7e, 0xf4a1, 0x7f7d, 0xf49b, 0x7f7d, 0xf494, 0x7f7c, 0xf48e, - 0x7f7c, 0xf488, 0x7f7b, 0xf482, 0x7f7b, 0xf47b, 0x7f7a, 0xf475, - 0x7f79, 0xf46f, 0x7f79, 0xf469, 0x7f78, 0xf462, 0x7f78, 0xf45c, - 0x7f77, 0xf456, 0x7f77, 0xf450, 0x7f76, 0xf449, 0x7f75, 0xf443, - 0x7f75, 0xf43d, 0x7f74, 0xf437, 0x7f74, 0xf430, 0x7f73, 0xf42a, - 0x7f72, 0xf424, 0x7f72, 0xf41e, 0x7f71, 0xf417, 0x7f71, 0xf411, - 0x7f70, 0xf40b, 0x7f70, 0xf405, 0x7f6f, 0xf3fe, 0x7f6e, 0xf3f8, - 0x7f6e, 0xf3f2, 0x7f6d, 0xf3ec, 0x7f6d, 0xf3e5, 0x7f6c, 0xf3df, - 0x7f6b, 0xf3d9, 0x7f6b, 0xf3d2, 0x7f6a, 0xf3cc, 0x7f6a, 0xf3c6, - 0x7f69, 0xf3c0, 0x7f68, 0xf3b9, 0x7f68, 0xf3b3, 0x7f67, 0xf3ad, - 0x7f67, 0xf3a7, 0x7f66, 0xf3a0, 0x7f65, 0xf39a, 0x7f65, 0xf394, - 0x7f64, 0xf38e, 0x7f64, 0xf387, 0x7f63, 0xf381, 0x7f62, 0xf37b, - 0x7f62, 0xf375, 0x7f61, 0xf36e, 0x7f60, 0xf368, 0x7f60, 0xf362, - 0x7f5f, 0xf35c, 0x7f5f, 0xf355, 0x7f5e, 0xf34f, 0x7f5d, 0xf349, - 0x7f5d, 0xf343, 0x7f5c, 0xf33c, 0x7f5b, 0xf336, 0x7f5b, 0xf330, - 0x7f5a, 0xf32a, 0x7f5a, 0xf323, 0x7f59, 0xf31d, 0x7f58, 0xf317, - 0x7f58, 0xf311, 0x7f57, 0xf30a, 0x7f56, 0xf304, 0x7f56, 0xf2fe, - 0x7f55, 0xf2f8, 0x7f55, 0xf2f1, 0x7f54, 0xf2eb, 0x7f53, 0xf2e5, - 0x7f53, 0xf2df, 0x7f52, 0xf2d8, 0x7f51, 0xf2d2, 0x7f51, 0xf2cc, - 0x7f50, 0xf2c6, 0x7f4f, 0xf2bf, 0x7f4f, 0xf2b9, 0x7f4e, 0xf2b3, - 0x7f4d, 0xf2ad, 0x7f4d, 0xf2a6, 0x7f4c, 0xf2a0, 0x7f4b, 0xf29a, - 0x7f4b, 0xf294, 0x7f4a, 0xf28d, 0x7f49, 0xf287, 0x7f49, 0xf281, - 0x7f48, 0xf27b, 0x7f47, 0xf274, 0x7f47, 0xf26e, 0x7f46, 0xf268, - 0x7f45, 0xf262, 0x7f45, 0xf25b, 0x7f44, 0xf255, 0x7f43, 0xf24f, - 0x7f43, 0xf249, 0x7f42, 0xf242, 0x7f41, 0xf23c, 0x7f41, 0xf236, - 0x7f40, 0xf230, 0x7f3f, 0xf229, 0x7f3f, 0xf223, 0x7f3e, 0xf21d, - 0x7f3d, 0xf217, 0x7f3d, 0xf210, 0x7f3c, 0xf20a, 0x7f3b, 0xf204, - 0x7f3b, 0xf1fe, 0x7f3a, 0xf1f7, 0x7f39, 0xf1f1, 0x7f39, 0xf1eb, - 0x7f38, 0xf1e5, 0x7f37, 0xf1de, 0x7f36, 0xf1d8, 0x7f36, 0xf1d2, - 0x7f35, 0xf1cc, 0x7f34, 0xf1c6, 0x7f34, 0xf1bf, 0x7f33, 0xf1b9, - 0x7f32, 0xf1b3, 0x7f32, 0xf1ad, 0x7f31, 0xf1a6, 0x7f30, 0xf1a0, - 0x7f2f, 0xf19a, 0x7f2f, 0xf194, 0x7f2e, 0xf18d, 0x7f2d, 0xf187, - 0x7f2d, 0xf181, 0x7f2c, 0xf17b, 0x7f2b, 0xf174, 0x7f2a, 0xf16e, - 0x7f2a, 0xf168, 0x7f29, 0xf162, 0x7f28, 0xf15b, 0x7f28, 0xf155, - 0x7f27, 0xf14f, 0x7f26, 0xf149, 0x7f25, 0xf142, 0x7f25, 0xf13c, - 0x7f24, 0xf136, 0x7f23, 0xf130, 0x7f23, 0xf129, 0x7f22, 0xf123, - 0x7f21, 0xf11d, 0x7f20, 0xf117, 0x7f20, 0xf110, 0x7f1f, 0xf10a, - 0x7f1e, 0xf104, 0x7f1d, 0xf0fe, 0x7f1d, 0xf0f8, 0x7f1c, 0xf0f1, - 0x7f1b, 0xf0eb, 0x7f1a, 0xf0e5, 0x7f1a, 0xf0df, 0x7f19, 0xf0d8, - 0x7f18, 0xf0d2, 0x7f17, 0xf0cc, 0x7f17, 0xf0c6, 0x7f16, 0xf0bf, - 0x7f15, 0xf0b9, 0x7f14, 0xf0b3, 0x7f14, 0xf0ad, 0x7f13, 0xf0a6, - 0x7f12, 0xf0a0, 0x7f11, 0xf09a, 0x7f11, 0xf094, 0x7f10, 0xf08d, - 0x7f0f, 0xf087, 0x7f0e, 0xf081, 0x7f0e, 0xf07b, 0x7f0d, 0xf075, - 0x7f0c, 0xf06e, 0x7f0b, 0xf068, 0x7f0b, 0xf062, 0x7f0a, 0xf05c, - 0x7f09, 0xf055, 0x7f08, 0xf04f, 0x7f08, 0xf049, 0x7f07, 0xf043, - 0x7f06, 0xf03c, 0x7f05, 0xf036, 0x7f04, 0xf030, 0x7f04, 0xf02a, - 0x7f03, 0xf023, 0x7f02, 0xf01d, 0x7f01, 0xf017, 0x7f01, 0xf011, - 0x7f00, 0xf00b, 0x7eff, 0xf004, 0x7efe, 0xeffe, 0x7efd, 0xeff8, - 0x7efd, 0xeff2, 0x7efc, 0xefeb, 0x7efb, 0xefe5, 0x7efa, 0xefdf, - 0x7ef9, 0xefd9, 0x7ef9, 0xefd2, 0x7ef8, 0xefcc, 0x7ef7, 0xefc6, - 0x7ef6, 0xefc0, 0x7ef5, 0xefb9, 0x7ef5, 0xefb3, 0x7ef4, 0xefad, - 0x7ef3, 0xefa7, 0x7ef2, 0xefa1, 0x7ef1, 0xef9a, 0x7ef1, 0xef94, - 0x7ef0, 0xef8e, 0x7eef, 0xef88, 0x7eee, 0xef81, 0x7eed, 0xef7b, - 0x7eed, 0xef75, 0x7eec, 0xef6f, 0x7eeb, 0xef68, 0x7eea, 0xef62, - 0x7ee9, 0xef5c, 0x7ee9, 0xef56, 0x7ee8, 0xef50, 0x7ee7, 0xef49, - 0x7ee6, 0xef43, 0x7ee5, 0xef3d, 0x7ee4, 0xef37, 0x7ee4, 0xef30, - 0x7ee3, 0xef2a, 0x7ee2, 0xef24, 0x7ee1, 0xef1e, 0x7ee0, 0xef18, - 0x7edf, 0xef11, 0x7edf, 0xef0b, 0x7ede, 0xef05, 0x7edd, 0xeeff, - 0x7edc, 0xeef8, 0x7edb, 0xeef2, 0x7eda, 0xeeec, 0x7eda, 0xeee6, - 0x7ed9, 0xeedf, 0x7ed8, 0xeed9, 0x7ed7, 0xeed3, 0x7ed6, 0xeecd, - 0x7ed5, 0xeec7, 0x7ed5, 0xeec0, 0x7ed4, 0xeeba, 0x7ed3, 0xeeb4, - 0x7ed2, 0xeeae, 0x7ed1, 0xeea7, 0x7ed0, 0xeea1, 0x7ecf, 0xee9b, - 0x7ecf, 0xee95, 0x7ece, 0xee8f, 0x7ecd, 0xee88, 0x7ecc, 0xee82, - 0x7ecb, 0xee7c, 0x7eca, 0xee76, 0x7ec9, 0xee6f, 0x7ec9, 0xee69, - 0x7ec8, 0xee63, 0x7ec7, 0xee5d, 0x7ec6, 0xee57, 0x7ec5, 0xee50, - 0x7ec4, 0xee4a, 0x7ec3, 0xee44, 0x7ec3, 0xee3e, 0x7ec2, 0xee37, - 0x7ec1, 0xee31, 0x7ec0, 0xee2b, 0x7ebf, 0xee25, 0x7ebe, 0xee1f, - 0x7ebd, 0xee18, 0x7ebc, 0xee12, 0x7ebb, 0xee0c, 0x7ebb, 0xee06, - 0x7eba, 0xedff, 0x7eb9, 0xedf9, 0x7eb8, 0xedf3, 0x7eb7, 0xeded, - 0x7eb6, 0xede7, 0x7eb5, 0xede0, 0x7eb4, 0xedda, 0x7eb4, 0xedd4, - 0x7eb3, 0xedce, 0x7eb2, 0xedc7, 0x7eb1, 0xedc1, 0x7eb0, 0xedbb, - 0x7eaf, 0xedb5, 0x7eae, 0xedaf, 0x7ead, 0xeda8, 0x7eac, 0xeda2, - 0x7eab, 0xed9c, 0x7eab, 0xed96, 0x7eaa, 0xed8f, 0x7ea9, 0xed89, - 0x7ea8, 0xed83, 0x7ea7, 0xed7d, 0x7ea6, 0xed77, 0x7ea5, 0xed70, - 0x7ea4, 0xed6a, 0x7ea3, 0xed64, 0x7ea2, 0xed5e, 0x7ea1, 0xed58, - 0x7ea1, 0xed51, 0x7ea0, 0xed4b, 0x7e9f, 0xed45, 0x7e9e, 0xed3f, - 0x7e9d, 0xed38, 0x7e9c, 0xed32, 0x7e9b, 0xed2c, 0x7e9a, 0xed26, - 0x7e99, 0xed20, 0x7e98, 0xed19, 0x7e97, 0xed13, 0x7e96, 0xed0d, - 0x7e95, 0xed07, 0x7e94, 0xed01, 0x7e94, 0xecfa, 0x7e93, 0xecf4, - 0x7e92, 0xecee, 0x7e91, 0xece8, 0x7e90, 0xece1, 0x7e8f, 0xecdb, - 0x7e8e, 0xecd5, 0x7e8d, 0xeccf, 0x7e8c, 0xecc9, 0x7e8b, 0xecc2, - 0x7e8a, 0xecbc, 0x7e89, 0xecb6, 0x7e88, 0xecb0, 0x7e87, 0xecaa, - 0x7e86, 0xeca3, 0x7e85, 0xec9d, 0x7e84, 0xec97, 0x7e84, 0xec91, - 0x7e83, 0xec8a, 0x7e82, 0xec84, 0x7e81, 0xec7e, 0x7e80, 0xec78, - 0x7e7f, 0xec72, 0x7e7e, 0xec6b, 0x7e7d, 0xec65, 0x7e7c, 0xec5f, - 0x7e7b, 0xec59, 0x7e7a, 0xec53, 0x7e79, 0xec4c, 0x7e78, 0xec46, - 0x7e77, 0xec40, 0x7e76, 0xec3a, 0x7e75, 0xec34, 0x7e74, 0xec2d, - 0x7e73, 0xec27, 0x7e72, 0xec21, 0x7e71, 0xec1b, 0x7e70, 0xec15, - 0x7e6f, 0xec0e, 0x7e6e, 0xec08, 0x7e6d, 0xec02, 0x7e6c, 0xebfc, - 0x7e6b, 0xebf5, 0x7e6a, 0xebef, 0x7e69, 0xebe9, 0x7e68, 0xebe3, - 0x7e67, 0xebdd, 0x7e66, 0xebd6, 0x7e65, 0xebd0, 0x7e64, 0xebca, - 0x7e63, 0xebc4, 0x7e62, 0xebbe, 0x7e61, 0xebb7, 0x7e60, 0xebb1, - 0x7e5f, 0xebab, 0x7e5e, 0xeba5, 0x7e5d, 0xeb9f, 0x7e5c, 0xeb98, - 0x7e5b, 0xeb92, 0x7e5a, 0xeb8c, 0x7e59, 0xeb86, 0x7e58, 0xeb80, - 0x7e57, 0xeb79, 0x7e56, 0xeb73, 0x7e55, 0xeb6d, 0x7e54, 0xeb67, - 0x7e53, 0xeb61, 0x7e52, 0xeb5a, 0x7e51, 0xeb54, 0x7e50, 0xeb4e, - 0x7e4f, 0xeb48, 0x7e4e, 0xeb42, 0x7e4d, 0xeb3b, 0x7e4c, 0xeb35, - 0x7e4b, 0xeb2f, 0x7e4a, 0xeb29, 0x7e49, 0xeb23, 0x7e48, 0xeb1c, - 0x7e47, 0xeb16, 0x7e46, 0xeb10, 0x7e45, 0xeb0a, 0x7e44, 0xeb04, - 0x7e43, 0xeafd, 0x7e42, 0xeaf7, 0x7e41, 0xeaf1, 0x7e40, 0xeaeb, - 0x7e3f, 0xeae5, 0x7e3e, 0xeade, 0x7e3d, 0xead8, 0x7e3c, 0xead2, - 0x7e3b, 0xeacc, 0x7e3a, 0xeac6, 0x7e39, 0xeabf, 0x7e38, 0xeab9, - 0x7e37, 0xeab3, 0x7e35, 0xeaad, 0x7e34, 0xeaa7, 0x7e33, 0xeaa0, - 0x7e32, 0xea9a, 0x7e31, 0xea94, 0x7e30, 0xea8e, 0x7e2f, 0xea88, - 0x7e2e, 0xea81, 0x7e2d, 0xea7b, 0x7e2c, 0xea75, 0x7e2b, 0xea6f, - 0x7e2a, 0xea69, 0x7e29, 0xea63, 0x7e28, 0xea5c, 0x7e27, 0xea56, - 0x7e26, 0xea50, 0x7e25, 0xea4a, 0x7e24, 0xea44, 0x7e22, 0xea3d, - 0x7e21, 0xea37, 0x7e20, 0xea31, 0x7e1f, 0xea2b, 0x7e1e, 0xea25, - 0x7e1d, 0xea1e, 0x7e1c, 0xea18, 0x7e1b, 0xea12, 0x7e1a, 0xea0c, - 0x7e19, 0xea06, 0x7e18, 0xe9ff, 0x7e17, 0xe9f9, 0x7e16, 0xe9f3, - 0x7e14, 0xe9ed, 0x7e13, 0xe9e7, 0x7e12, 0xe9e1, 0x7e11, 0xe9da, - 0x7e10, 0xe9d4, 0x7e0f, 0xe9ce, 0x7e0e, 0xe9c8, 0x7e0d, 0xe9c2, - 0x7e0c, 0xe9bb, 0x7e0b, 0xe9b5, 0x7e0a, 0xe9af, 0x7e08, 0xe9a9, - 0x7e07, 0xe9a3, 0x7e06, 0xe99c, 0x7e05, 0xe996, 0x7e04, 0xe990, - 0x7e03, 0xe98a, 0x7e02, 0xe984, 0x7e01, 0xe97e, 0x7e00, 0xe977, - 0x7dff, 0xe971, 0x7dfd, 0xe96b, 0x7dfc, 0xe965, 0x7dfb, 0xe95f, - 0x7dfa, 0xe958, 0x7df9, 0xe952, 0x7df8, 0xe94c, 0x7df7, 0xe946, - 0x7df6, 0xe940, 0x7df5, 0xe93a, 0x7df3, 0xe933, 0x7df2, 0xe92d, - 0x7df1, 0xe927, 0x7df0, 0xe921, 0x7def, 0xe91b, 0x7dee, 0xe914, - 0x7ded, 0xe90e, 0x7dec, 0xe908, 0x7dea, 0xe902, 0x7de9, 0xe8fc, - 0x7de8, 0xe8f6, 0x7de7, 0xe8ef, 0x7de6, 0xe8e9, 0x7de5, 0xe8e3, - 0x7de4, 0xe8dd, 0x7de2, 0xe8d7, 0x7de1, 0xe8d0, 0x7de0, 0xe8ca, - 0x7ddf, 0xe8c4, 0x7dde, 0xe8be, 0x7ddd, 0xe8b8, 0x7ddc, 0xe8b2, - 0x7dda, 0xe8ab, 0x7dd9, 0xe8a5, 0x7dd8, 0xe89f, 0x7dd7, 0xe899, - 0x7dd6, 0xe893, 0x7dd5, 0xe88c, 0x7dd4, 0xe886, 0x7dd2, 0xe880, - 0x7dd1, 0xe87a, 0x7dd0, 0xe874, 0x7dcf, 0xe86e, 0x7dce, 0xe867, - 0x7dcd, 0xe861, 0x7dcc, 0xe85b, 0x7dca, 0xe855, 0x7dc9, 0xe84f, - 0x7dc8, 0xe849, 0x7dc7, 0xe842, 0x7dc6, 0xe83c, 0x7dc5, 0xe836, - 0x7dc3, 0xe830, 0x7dc2, 0xe82a, 0x7dc1, 0xe823, 0x7dc0, 0xe81d, - 0x7dbf, 0xe817, 0x7dbd, 0xe811, 0x7dbc, 0xe80b, 0x7dbb, 0xe805, - 0x7dba, 0xe7fe, 0x7db9, 0xe7f8, 0x7db8, 0xe7f2, 0x7db6, 0xe7ec, - 0x7db5, 0xe7e6, 0x7db4, 0xe7e0, 0x7db3, 0xe7d9, 0x7db2, 0xe7d3, - 0x7db0, 0xe7cd, 0x7daf, 0xe7c7, 0x7dae, 0xe7c1, 0x7dad, 0xe7bb, - 0x7dac, 0xe7b4, 0x7dab, 0xe7ae, 0x7da9, 0xe7a8, 0x7da8, 0xe7a2, - 0x7da7, 0xe79c, 0x7da6, 0xe796, 0x7da5, 0xe78f, 0x7da3, 0xe789, - 0x7da2, 0xe783, 0x7da1, 0xe77d, 0x7da0, 0xe777, 0x7d9f, 0xe771, - 0x7d9d, 0xe76a, 0x7d9c, 0xe764, 0x7d9b, 0xe75e, 0x7d9a, 0xe758, - 0x7d98, 0xe752, 0x7d97, 0xe74c, 0x7d96, 0xe745, 0x7d95, 0xe73f, - 0x7d94, 0xe739, 0x7d92, 0xe733, 0x7d91, 0xe72d, 0x7d90, 0xe727, - 0x7d8f, 0xe720, 0x7d8e, 0xe71a, 0x7d8c, 0xe714, 0x7d8b, 0xe70e, - 0x7d8a, 0xe708, 0x7d89, 0xe702, 0x7d87, 0xe6fb, 0x7d86, 0xe6f5, - 0x7d85, 0xe6ef, 0x7d84, 0xe6e9, 0x7d82, 0xe6e3, 0x7d81, 0xe6dd, - 0x7d80, 0xe6d6, 0x7d7f, 0xe6d0, 0x7d7e, 0xe6ca, 0x7d7c, 0xe6c4, - 0x7d7b, 0xe6be, 0x7d7a, 0xe6b8, 0x7d79, 0xe6b2, 0x7d77, 0xe6ab, - 0x7d76, 0xe6a5, 0x7d75, 0xe69f, 0x7d74, 0xe699, 0x7d72, 0xe693, - 0x7d71, 0xe68d, 0x7d70, 0xe686, 0x7d6f, 0xe680, 0x7d6d, 0xe67a, - 0x7d6c, 0xe674, 0x7d6b, 0xe66e, 0x7d6a, 0xe668, 0x7d68, 0xe661, - 0x7d67, 0xe65b, 0x7d66, 0xe655, 0x7d65, 0xe64f, 0x7d63, 0xe649, - 0x7d62, 0xe643, 0x7d61, 0xe63d, 0x7d60, 0xe636, 0x7d5e, 0xe630, - 0x7d5d, 0xe62a, 0x7d5c, 0xe624, 0x7d5a, 0xe61e, 0x7d59, 0xe618, - 0x7d58, 0xe611, 0x7d57, 0xe60b, 0x7d55, 0xe605, 0x7d54, 0xe5ff, - 0x7d53, 0xe5f9, 0x7d52, 0xe5f3, 0x7d50, 0xe5ed, 0x7d4f, 0xe5e6, - 0x7d4e, 0xe5e0, 0x7d4c, 0xe5da, 0x7d4b, 0xe5d4, 0x7d4a, 0xe5ce, - 0x7d49, 0xe5c8, 0x7d47, 0xe5c2, 0x7d46, 0xe5bb, 0x7d45, 0xe5b5, - 0x7d43, 0xe5af, 0x7d42, 0xe5a9, 0x7d41, 0xe5a3, 0x7d3f, 0xe59d, - 0x7d3e, 0xe596, 0x7d3d, 0xe590, 0x7d3c, 0xe58a, 0x7d3a, 0xe584, - 0x7d39, 0xe57e, 0x7d38, 0xe578, 0x7d36, 0xe572, 0x7d35, 0xe56b, - 0x7d34, 0xe565, 0x7d32, 0xe55f, 0x7d31, 0xe559, 0x7d30, 0xe553, - 0x7d2f, 0xe54d, 0x7d2d, 0xe547, 0x7d2c, 0xe540, 0x7d2b, 0xe53a, - 0x7d29, 0xe534, 0x7d28, 0xe52e, 0x7d27, 0xe528, 0x7d25, 0xe522, - 0x7d24, 0xe51c, 0x7d23, 0xe515, 0x7d21, 0xe50f, 0x7d20, 0xe509, - 0x7d1f, 0xe503, 0x7d1d, 0xe4fd, 0x7d1c, 0xe4f7, 0x7d1b, 0xe4f1, - 0x7d19, 0xe4ea, 0x7d18, 0xe4e4, 0x7d17, 0xe4de, 0x7d15, 0xe4d8, - 0x7d14, 0xe4d2, 0x7d13, 0xe4cc, 0x7d11, 0xe4c6, 0x7d10, 0xe4bf, - 0x7d0f, 0xe4b9, 0x7d0d, 0xe4b3, 0x7d0c, 0xe4ad, 0x7d0b, 0xe4a7, - 0x7d09, 0xe4a1, 0x7d08, 0xe49b, 0x7d07, 0xe494, 0x7d05, 0xe48e, - 0x7d04, 0xe488, 0x7d03, 0xe482, 0x7d01, 0xe47c, 0x7d00, 0xe476, - 0x7cff, 0xe470, 0x7cfd, 0xe46a, 0x7cfc, 0xe463, 0x7cfb, 0xe45d, - 0x7cf9, 0xe457, 0x7cf8, 0xe451, 0x7cf6, 0xe44b, 0x7cf5, 0xe445, - 0x7cf4, 0xe43f, 0x7cf2, 0xe438, 0x7cf1, 0xe432, 0x7cf0, 0xe42c, - 0x7cee, 0xe426, 0x7ced, 0xe420, 0x7cec, 0xe41a, 0x7cea, 0xe414, - 0x7ce9, 0xe40e, 0x7ce7, 0xe407, 0x7ce6, 0xe401, 0x7ce5, 0xe3fb, - 0x7ce3, 0xe3f5, 0x7ce2, 0xe3ef, 0x7ce1, 0xe3e9, 0x7cdf, 0xe3e3, - 0x7cde, 0xe3dc, 0x7cdc, 0xe3d6, 0x7cdb, 0xe3d0, 0x7cda, 0xe3ca, - 0x7cd8, 0xe3c4, 0x7cd7, 0xe3be, 0x7cd5, 0xe3b8, 0x7cd4, 0xe3b2, - 0x7cd3, 0xe3ab, 0x7cd1, 0xe3a5, 0x7cd0, 0xe39f, 0x7ccf, 0xe399, - 0x7ccd, 0xe393, 0x7ccc, 0xe38d, 0x7cca, 0xe387, 0x7cc9, 0xe381, - 0x7cc8, 0xe37a, 0x7cc6, 0xe374, 0x7cc5, 0xe36e, 0x7cc3, 0xe368, - 0x7cc2, 0xe362, 0x7cc1, 0xe35c, 0x7cbf, 0xe356, 0x7cbe, 0xe350, - 0x7cbc, 0xe349, 0x7cbb, 0xe343, 0x7cb9, 0xe33d, 0x7cb8, 0xe337, - 0x7cb7, 0xe331, 0x7cb5, 0xe32b, 0x7cb4, 0xe325, 0x7cb2, 0xe31f, - 0x7cb1, 0xe318, 0x7cb0, 0xe312, 0x7cae, 0xe30c, 0x7cad, 0xe306, - 0x7cab, 0xe300, 0x7caa, 0xe2fa, 0x7ca8, 0xe2f4, 0x7ca7, 0xe2ee, - 0x7ca6, 0xe2e8, 0x7ca4, 0xe2e1, 0x7ca3, 0xe2db, 0x7ca1, 0xe2d5, - 0x7ca0, 0xe2cf, 0x7c9e, 0xe2c9, 0x7c9d, 0xe2c3, 0x7c9c, 0xe2bd, - 0x7c9a, 0xe2b7, 0x7c99, 0xe2b0, 0x7c97, 0xe2aa, 0x7c96, 0xe2a4, - 0x7c94, 0xe29e, 0x7c93, 0xe298, 0x7c91, 0xe292, 0x7c90, 0xe28c, - 0x7c8f, 0xe286, 0x7c8d, 0xe280, 0x7c8c, 0xe279, 0x7c8a, 0xe273, - 0x7c89, 0xe26d, 0x7c87, 0xe267, 0x7c86, 0xe261, 0x7c84, 0xe25b, - 0x7c83, 0xe255, 0x7c82, 0xe24f, 0x7c80, 0xe249, 0x7c7f, 0xe242, - 0x7c7d, 0xe23c, 0x7c7c, 0xe236, 0x7c7a, 0xe230, 0x7c79, 0xe22a, - 0x7c77, 0xe224, 0x7c76, 0xe21e, 0x7c74, 0xe218, 0x7c73, 0xe212, - 0x7c71, 0xe20b, 0x7c70, 0xe205, 0x7c6e, 0xe1ff, 0x7c6d, 0xe1f9, - 0x7c6c, 0xe1f3, 0x7c6a, 0xe1ed, 0x7c69, 0xe1e7, 0x7c67, 0xe1e1, - 0x7c66, 0xe1db, 0x7c64, 0xe1d4, 0x7c63, 0xe1ce, 0x7c61, 0xe1c8, - 0x7c60, 0xe1c2, 0x7c5e, 0xe1bc, 0x7c5d, 0xe1b6, 0x7c5b, 0xe1b0, - 0x7c5a, 0xe1aa, 0x7c58, 0xe1a4, 0x7c57, 0xe19e, 0x7c55, 0xe197, - 0x7c54, 0xe191, 0x7c52, 0xe18b, 0x7c51, 0xe185, 0x7c4f, 0xe17f, - 0x7c4e, 0xe179, 0x7c4c, 0xe173, 0x7c4b, 0xe16d, 0x7c49, 0xe167, - 0x7c48, 0xe160, 0x7c46, 0xe15a, 0x7c45, 0xe154, 0x7c43, 0xe14e, - 0x7c42, 0xe148, 0x7c40, 0xe142, 0x7c3f, 0xe13c, 0x7c3d, 0xe136, - 0x7c3c, 0xe130, 0x7c3a, 0xe12a, 0x7c39, 0xe123, 0x7c37, 0xe11d, - 0x7c36, 0xe117, 0x7c34, 0xe111, 0x7c33, 0xe10b, 0x7c31, 0xe105, - 0x7c30, 0xe0ff, 0x7c2e, 0xe0f9, 0x7c2d, 0xe0f3, 0x7c2b, 0xe0ed, - 0x7c29, 0xe0e7, 0x7c28, 0xe0e0, 0x7c26, 0xe0da, 0x7c25, 0xe0d4, - 0x7c23, 0xe0ce, 0x7c22, 0xe0c8, 0x7c20, 0xe0c2, 0x7c1f, 0xe0bc, - 0x7c1d, 0xe0b6, 0x7c1c, 0xe0b0, 0x7c1a, 0xe0aa, 0x7c19, 0xe0a3, - 0x7c17, 0xe09d, 0x7c16, 0xe097, 0x7c14, 0xe091, 0x7c12, 0xe08b, - 0x7c11, 0xe085, 0x7c0f, 0xe07f, 0x7c0e, 0xe079, 0x7c0c, 0xe073, - 0x7c0b, 0xe06d, 0x7c09, 0xe067, 0x7c08, 0xe061, 0x7c06, 0xe05a, - 0x7c05, 0xe054, 0x7c03, 0xe04e, 0x7c01, 0xe048, 0x7c00, 0xe042, - 0x7bfe, 0xe03c, 0x7bfd, 0xe036, 0x7bfb, 0xe030, 0x7bfa, 0xe02a, - 0x7bf8, 0xe024, 0x7bf6, 0xe01e, 0x7bf5, 0xe017, 0x7bf3, 0xe011, - 0x7bf2, 0xe00b, 0x7bf0, 0xe005, 0x7bef, 0xdfff, 0x7bed, 0xdff9, - 0x7beb, 0xdff3, 0x7bea, 0xdfed, 0x7be8, 0xdfe7, 0x7be7, 0xdfe1, - 0x7be5, 0xdfdb, 0x7be4, 0xdfd5, 0x7be2, 0xdfce, 0x7be0, 0xdfc8, - 0x7bdf, 0xdfc2, 0x7bdd, 0xdfbc, 0x7bdc, 0xdfb6, 0x7bda, 0xdfb0, - 0x7bd9, 0xdfaa, 0x7bd7, 0xdfa4, 0x7bd5, 0xdf9e, 0x7bd4, 0xdf98, - 0x7bd2, 0xdf92, 0x7bd1, 0xdf8c, 0x7bcf, 0xdf86, 0x7bcd, 0xdf7f, - 0x7bcc, 0xdf79, 0x7bca, 0xdf73, 0x7bc9, 0xdf6d, 0x7bc7, 0xdf67, - 0x7bc5, 0xdf61, 0x7bc4, 0xdf5b, 0x7bc2, 0xdf55, 0x7bc1, 0xdf4f, - 0x7bbf, 0xdf49, 0x7bbd, 0xdf43, 0x7bbc, 0xdf3d, 0x7bba, 0xdf37, - 0x7bb9, 0xdf30, 0x7bb7, 0xdf2a, 0x7bb5, 0xdf24, 0x7bb4, 0xdf1e, - 0x7bb2, 0xdf18, 0x7bb0, 0xdf12, 0x7baf, 0xdf0c, 0x7bad, 0xdf06, - 0x7bac, 0xdf00, 0x7baa, 0xdefa, 0x7ba8, 0xdef4, 0x7ba7, 0xdeee, - 0x7ba5, 0xdee8, 0x7ba3, 0xdee2, 0x7ba2, 0xdedb, 0x7ba0, 0xded5, - 0x7b9f, 0xdecf, 0x7b9d, 0xdec9, 0x7b9b, 0xdec3, 0x7b9a, 0xdebd, - 0x7b98, 0xdeb7, 0x7b96, 0xdeb1, 0x7b95, 0xdeab, 0x7b93, 0xdea5, - 0x7b92, 0xde9f, 0x7b90, 0xde99, 0x7b8e, 0xde93, 0x7b8d, 0xde8d, - 0x7b8b, 0xde87, 0x7b89, 0xde80, 0x7b88, 0xde7a, 0x7b86, 0xde74, - 0x7b84, 0xde6e, 0x7b83, 0xde68, 0x7b81, 0xde62, 0x7b7f, 0xde5c, - 0x7b7e, 0xde56, 0x7b7c, 0xde50, 0x7b7a, 0xde4a, 0x7b79, 0xde44, - 0x7b77, 0xde3e, 0x7b76, 0xde38, 0x7b74, 0xde32, 0x7b72, 0xde2c, - 0x7b71, 0xde26, 0x7b6f, 0xde1f, 0x7b6d, 0xde19, 0x7b6c, 0xde13, - 0x7b6a, 0xde0d, 0x7b68, 0xde07, 0x7b67, 0xde01, 0x7b65, 0xddfb, - 0x7b63, 0xddf5, 0x7b62, 0xddef, 0x7b60, 0xdde9, 0x7b5e, 0xdde3, - 0x7b5d, 0xdddd, 0x7b5b, 0xddd7, 0x7b59, 0xddd1, 0x7b57, 0xddcb, - 0x7b56, 0xddc5, 0x7b54, 0xddbf, 0x7b52, 0xddb9, 0x7b51, 0xddb2, - 0x7b4f, 0xddac, 0x7b4d, 0xdda6, 0x7b4c, 0xdda0, 0x7b4a, 0xdd9a, - 0x7b48, 0xdd94, 0x7b47, 0xdd8e, 0x7b45, 0xdd88, 0x7b43, 0xdd82, - 0x7b42, 0xdd7c, 0x7b40, 0xdd76, 0x7b3e, 0xdd70, 0x7b3c, 0xdd6a, - 0x7b3b, 0xdd64, 0x7b39, 0xdd5e, 0x7b37, 0xdd58, 0x7b36, 0xdd52, - 0x7b34, 0xdd4c, 0x7b32, 0xdd46, 0x7b31, 0xdd40, 0x7b2f, 0xdd39, - 0x7b2d, 0xdd33, 0x7b2b, 0xdd2d, 0x7b2a, 0xdd27, 0x7b28, 0xdd21, - 0x7b26, 0xdd1b, 0x7b25, 0xdd15, 0x7b23, 0xdd0f, 0x7b21, 0xdd09, - 0x7b1f, 0xdd03, 0x7b1e, 0xdcfd, 0x7b1c, 0xdcf7, 0x7b1a, 0xdcf1, - 0x7b19, 0xdceb, 0x7b17, 0xdce5, 0x7b15, 0xdcdf, 0x7b13, 0xdcd9, - 0x7b12, 0xdcd3, 0x7b10, 0xdccd, 0x7b0e, 0xdcc7, 0x7b0c, 0xdcc1, - 0x7b0b, 0xdcbb, 0x7b09, 0xdcb5, 0x7b07, 0xdcae, 0x7b06, 0xdca8, - 0x7b04, 0xdca2, 0x7b02, 0xdc9c, 0x7b00, 0xdc96, 0x7aff, 0xdc90, - 0x7afd, 0xdc8a, 0x7afb, 0xdc84, 0x7af9, 0xdc7e, 0x7af8, 0xdc78, - 0x7af6, 0xdc72, 0x7af4, 0xdc6c, 0x7af2, 0xdc66, 0x7af1, 0xdc60, - 0x7aef, 0xdc5a, 0x7aed, 0xdc54, 0x7aeb, 0xdc4e, 0x7aea, 0xdc48, - 0x7ae8, 0xdc42, 0x7ae6, 0xdc3c, 0x7ae4, 0xdc36, 0x7ae3, 0xdc30, - 0x7ae1, 0xdc2a, 0x7adf, 0xdc24, 0x7add, 0xdc1e, 0x7adc, 0xdc18, - 0x7ada, 0xdc12, 0x7ad8, 0xdc0c, 0x7ad6, 0xdc06, 0x7ad5, 0xdbff, - 0x7ad3, 0xdbf9, 0x7ad1, 0xdbf3, 0x7acf, 0xdbed, 0x7acd, 0xdbe7, - 0x7acc, 0xdbe1, 0x7aca, 0xdbdb, 0x7ac8, 0xdbd5, 0x7ac6, 0xdbcf, - 0x7ac5, 0xdbc9, 0x7ac3, 0xdbc3, 0x7ac1, 0xdbbd, 0x7abf, 0xdbb7, - 0x7abd, 0xdbb1, 0x7abc, 0xdbab, 0x7aba, 0xdba5, 0x7ab8, 0xdb9f, - 0x7ab6, 0xdb99, 0x7ab5, 0xdb93, 0x7ab3, 0xdb8d, 0x7ab1, 0xdb87, - 0x7aaf, 0xdb81, 0x7aad, 0xdb7b, 0x7aac, 0xdb75, 0x7aaa, 0xdb6f, - 0x7aa8, 0xdb69, 0x7aa6, 0xdb63, 0x7aa4, 0xdb5d, 0x7aa3, 0xdb57, - 0x7aa1, 0xdb51, 0x7a9f, 0xdb4b, 0x7a9d, 0xdb45, 0x7a9b, 0xdb3f, - 0x7a9a, 0xdb39, 0x7a98, 0xdb33, 0x7a96, 0xdb2d, 0x7a94, 0xdb27, - 0x7a92, 0xdb21, 0x7a91, 0xdb1b, 0x7a8f, 0xdb15, 0x7a8d, 0xdb0f, - 0x7a8b, 0xdb09, 0x7a89, 0xdb03, 0x7a87, 0xdafd, 0x7a86, 0xdaf7, - 0x7a84, 0xdaf1, 0x7a82, 0xdaea, 0x7a80, 0xdae4, 0x7a7e, 0xdade, - 0x7a7d, 0xdad8, 0x7a7b, 0xdad2, 0x7a79, 0xdacc, 0x7a77, 0xdac6, - 0x7a75, 0xdac0, 0x7a73, 0xdaba, 0x7a72, 0xdab4, 0x7a70, 0xdaae, - 0x7a6e, 0xdaa8, 0x7a6c, 0xdaa2, 0x7a6a, 0xda9c, 0x7a68, 0xda96, - 0x7a67, 0xda90, 0x7a65, 0xda8a, 0x7a63, 0xda84, 0x7a61, 0xda7e, - 0x7a5f, 0xda78, 0x7a5d, 0xda72, 0x7a5c, 0xda6c, 0x7a5a, 0xda66, - 0x7a58, 0xda60, 0x7a56, 0xda5a, 0x7a54, 0xda54, 0x7a52, 0xda4e, - 0x7a50, 0xda48, 0x7a4f, 0xda42, 0x7a4d, 0xda3c, 0x7a4b, 0xda36, - 0x7a49, 0xda30, 0x7a47, 0xda2a, 0x7a45, 0xda24, 0x7a43, 0xda1e, - 0x7a42, 0xda18, 0x7a40, 0xda12, 0x7a3e, 0xda0c, 0x7a3c, 0xda06, - 0x7a3a, 0xda00, 0x7a38, 0xd9fa, 0x7a36, 0xd9f4, 0x7a35, 0xd9ee, - 0x7a33, 0xd9e8, 0x7a31, 0xd9e2, 0x7a2f, 0xd9dc, 0x7a2d, 0xd9d6, - 0x7a2b, 0xd9d0, 0x7a29, 0xd9ca, 0x7a27, 0xd9c4, 0x7a26, 0xd9be, - 0x7a24, 0xd9b8, 0x7a22, 0xd9b2, 0x7a20, 0xd9ac, 0x7a1e, 0xd9a6, - 0x7a1c, 0xd9a0, 0x7a1a, 0xd99a, 0x7a18, 0xd994, 0x7a16, 0xd98e, - 0x7a15, 0xd988, 0x7a13, 0xd982, 0x7a11, 0xd97c, 0x7a0f, 0xd976, - 0x7a0d, 0xd970, 0x7a0b, 0xd96a, 0x7a09, 0xd964, 0x7a07, 0xd95e, - 0x7a05, 0xd958, 0x7a04, 0xd952, 0x7a02, 0xd94c, 0x7a00, 0xd946, - 0x79fe, 0xd940, 0x79fc, 0xd93a, 0x79fa, 0xd934, 0x79f8, 0xd92e, - 0x79f6, 0xd928, 0x79f4, 0xd922, 0x79f2, 0xd91c, 0x79f0, 0xd917, - 0x79ef, 0xd911, 0x79ed, 0xd90b, 0x79eb, 0xd905, 0x79e9, 0xd8ff, - 0x79e7, 0xd8f9, 0x79e5, 0xd8f3, 0x79e3, 0xd8ed, 0x79e1, 0xd8e7, - 0x79df, 0xd8e1, 0x79dd, 0xd8db, 0x79db, 0xd8d5, 0x79d9, 0xd8cf, - 0x79d8, 0xd8c9, 0x79d6, 0xd8c3, 0x79d4, 0xd8bd, 0x79d2, 0xd8b7, - 0x79d0, 0xd8b1, 0x79ce, 0xd8ab, 0x79cc, 0xd8a5, 0x79ca, 0xd89f, - 0x79c8, 0xd899, 0x79c6, 0xd893, 0x79c4, 0xd88d, 0x79c2, 0xd887, - 0x79c0, 0xd881, 0x79be, 0xd87b, 0x79bc, 0xd875, 0x79bb, 0xd86f, - 0x79b9, 0xd869, 0x79b7, 0xd863, 0x79b5, 0xd85d, 0x79b3, 0xd857, - 0x79b1, 0xd851, 0x79af, 0xd84b, 0x79ad, 0xd845, 0x79ab, 0xd83f, - 0x79a9, 0xd839, 0x79a7, 0xd833, 0x79a5, 0xd82d, 0x79a3, 0xd827, - 0x79a1, 0xd821, 0x799f, 0xd81b, 0x799d, 0xd815, 0x799b, 0xd80f, - 0x7999, 0xd80a, 0x7997, 0xd804, 0x7995, 0xd7fe, 0x7993, 0xd7f8, - 0x7992, 0xd7f2, 0x7990, 0xd7ec, 0x798e, 0xd7e6, 0x798c, 0xd7e0, - 0x798a, 0xd7da, 0x7988, 0xd7d4, 0x7986, 0xd7ce, 0x7984, 0xd7c8, - 0x7982, 0xd7c2, 0x7980, 0xd7bc, 0x797e, 0xd7b6, 0x797c, 0xd7b0, - 0x797a, 0xd7aa, 0x7978, 0xd7a4, 0x7976, 0xd79e, 0x7974, 0xd798, - 0x7972, 0xd792, 0x7970, 0xd78c, 0x796e, 0xd786, 0x796c, 0xd780, - 0x796a, 0xd77a, 0x7968, 0xd774, 0x7966, 0xd76e, 0x7964, 0xd768, - 0x7962, 0xd763, 0x7960, 0xd75d, 0x795e, 0xd757, 0x795c, 0xd751, - 0x795a, 0xd74b, 0x7958, 0xd745, 0x7956, 0xd73f, 0x7954, 0xd739, - 0x7952, 0xd733, 0x7950, 0xd72d, 0x794e, 0xd727, 0x794c, 0xd721, - 0x794a, 0xd71b, 0x7948, 0xd715, 0x7946, 0xd70f, 0x7944, 0xd709, - 0x7942, 0xd703, 0x7940, 0xd6fd, 0x793e, 0xd6f7, 0x793c, 0xd6f1, - 0x793a, 0xd6eb, 0x7938, 0xd6e5, 0x7936, 0xd6e0, 0x7934, 0xd6da, - 0x7932, 0xd6d4, 0x7930, 0xd6ce, 0x792e, 0xd6c8, 0x792c, 0xd6c2, - 0x792a, 0xd6bc, 0x7928, 0xd6b6, 0x7926, 0xd6b0, 0x7924, 0xd6aa, - 0x7922, 0xd6a4, 0x7920, 0xd69e, 0x791e, 0xd698, 0x791c, 0xd692, - 0x7919, 0xd68c, 0x7917, 0xd686, 0x7915, 0xd680, 0x7913, 0xd67a, - 0x7911, 0xd675, 0x790f, 0xd66f, 0x790d, 0xd669, 0x790b, 0xd663, - 0x7909, 0xd65d, 0x7907, 0xd657, 0x7905, 0xd651, 0x7903, 0xd64b, - 0x7901, 0xd645, 0x78ff, 0xd63f, 0x78fd, 0xd639, 0x78fb, 0xd633, - 0x78f9, 0xd62d, 0x78f7, 0xd627, 0x78f5, 0xd621, 0x78f3, 0xd61b, - 0x78f1, 0xd615, 0x78ee, 0xd610, 0x78ec, 0xd60a, 0x78ea, 0xd604, - 0x78e8, 0xd5fe, 0x78e6, 0xd5f8, 0x78e4, 0xd5f2, 0x78e2, 0xd5ec, - 0x78e0, 0xd5e6, 0x78de, 0xd5e0, 0x78dc, 0xd5da, 0x78da, 0xd5d4, - 0x78d8, 0xd5ce, 0x78d6, 0xd5c8, 0x78d4, 0xd5c2, 0x78d2, 0xd5bc, - 0x78cf, 0xd5b7, 0x78cd, 0xd5b1, 0x78cb, 0xd5ab, 0x78c9, 0xd5a5, - 0x78c7, 0xd59f, 0x78c5, 0xd599, 0x78c3, 0xd593, 0x78c1, 0xd58d, - 0x78bf, 0xd587, 0x78bd, 0xd581, 0x78bb, 0xd57b, 0x78b9, 0xd575, - 0x78b6, 0xd56f, 0x78b4, 0xd569, 0x78b2, 0xd564, 0x78b0, 0xd55e, - 0x78ae, 0xd558, 0x78ac, 0xd552, 0x78aa, 0xd54c, 0x78a8, 0xd546, - 0x78a6, 0xd540, 0x78a4, 0xd53a, 0x78a2, 0xd534, 0x789f, 0xd52e, - 0x789d, 0xd528, 0x789b, 0xd522, 0x7899, 0xd51c, 0x7897, 0xd517, - 0x7895, 0xd511, 0x7893, 0xd50b, 0x7891, 0xd505, 0x788f, 0xd4ff, - 0x788c, 0xd4f9, 0x788a, 0xd4f3, 0x7888, 0xd4ed, 0x7886, 0xd4e7, - 0x7884, 0xd4e1, 0x7882, 0xd4db, 0x7880, 0xd4d5, 0x787e, 0xd4d0, - 0x787c, 0xd4ca, 0x7879, 0xd4c4, 0x7877, 0xd4be, 0x7875, 0xd4b8, - 0x7873, 0xd4b2, 0x7871, 0xd4ac, 0x786f, 0xd4a6, 0x786d, 0xd4a0, - 0x786b, 0xd49a, 0x7868, 0xd494, 0x7866, 0xd48f, 0x7864, 0xd489, - 0x7862, 0xd483, 0x7860, 0xd47d, 0x785e, 0xd477, 0x785c, 0xd471, - 0x7859, 0xd46b, 0x7857, 0xd465, 0x7855, 0xd45f, 0x7853, 0xd459, - 0x7851, 0xd453, 0x784f, 0xd44e, 0x784d, 0xd448, 0x784a, 0xd442, - 0x7848, 0xd43c, 0x7846, 0xd436, 0x7844, 0xd430, 0x7842, 0xd42a, - 0x7840, 0xd424, 0x783e, 0xd41e, 0x783b, 0xd418, 0x7839, 0xd412, - 0x7837, 0xd40d, 0x7835, 0xd407, 0x7833, 0xd401, 0x7831, 0xd3fb, - 0x782e, 0xd3f5, 0x782c, 0xd3ef, 0x782a, 0xd3e9, 0x7828, 0xd3e3, - 0x7826, 0xd3dd, 0x7824, 0xd3d7, 0x7821, 0xd3d2, 0x781f, 0xd3cc, - 0x781d, 0xd3c6, 0x781b, 0xd3c0, 0x7819, 0xd3ba, 0x7817, 0xd3b4, - 0x7814, 0xd3ae, 0x7812, 0xd3a8, 0x7810, 0xd3a2, 0x780e, 0xd39d, - 0x780c, 0xd397, 0x780a, 0xd391, 0x7807, 0xd38b, 0x7805, 0xd385, - 0x7803, 0xd37f, 0x7801, 0xd379, 0x77ff, 0xd373, 0x77fc, 0xd36d, - 0x77fa, 0xd368, 0x77f8, 0xd362, 0x77f6, 0xd35c, 0x77f4, 0xd356, - 0x77f1, 0xd350, 0x77ef, 0xd34a, 0x77ed, 0xd344, 0x77eb, 0xd33e, - 0x77e9, 0xd338, 0x77e6, 0xd333, 0x77e4, 0xd32d, 0x77e2, 0xd327, - 0x77e0, 0xd321, 0x77de, 0xd31b, 0x77db, 0xd315, 0x77d9, 0xd30f, - 0x77d7, 0xd309, 0x77d5, 0xd303, 0x77d3, 0xd2fe, 0x77d0, 0xd2f8, - 0x77ce, 0xd2f2, 0x77cc, 0xd2ec, 0x77ca, 0xd2e6, 0x77c8, 0xd2e0, - 0x77c5, 0xd2da, 0x77c3, 0xd2d4, 0x77c1, 0xd2cf, 0x77bf, 0xd2c9, - 0x77bc, 0xd2c3, 0x77ba, 0xd2bd, 0x77b8, 0xd2b7, 0x77b6, 0xd2b1, - 0x77b4, 0xd2ab, 0x77b1, 0xd2a5, 0x77af, 0xd2a0, 0x77ad, 0xd29a, - 0x77ab, 0xd294, 0x77a8, 0xd28e, 0x77a6, 0xd288, 0x77a4, 0xd282, - 0x77a2, 0xd27c, 0x77a0, 0xd276, 0x779d, 0xd271, 0x779b, 0xd26b, - 0x7799, 0xd265, 0x7797, 0xd25f, 0x7794, 0xd259, 0x7792, 0xd253, - 0x7790, 0xd24d, 0x778e, 0xd247, 0x778b, 0xd242, 0x7789, 0xd23c, - 0x7787, 0xd236, 0x7785, 0xd230, 0x7782, 0xd22a, 0x7780, 0xd224, - 0x777e, 0xd21e, 0x777c, 0xd219, 0x7779, 0xd213, 0x7777, 0xd20d, - 0x7775, 0xd207, 0x7773, 0xd201, 0x7770, 0xd1fb, 0x776e, 0xd1f5, - 0x776c, 0xd1ef, 0x776a, 0xd1ea, 0x7767, 0xd1e4, 0x7765, 0xd1de, - 0x7763, 0xd1d8, 0x7760, 0xd1d2, 0x775e, 0xd1cc, 0x775c, 0xd1c6, - 0x775a, 0xd1c1, 0x7757, 0xd1bb, 0x7755, 0xd1b5, 0x7753, 0xd1af, - 0x7751, 0xd1a9, 0x774e, 0xd1a3, 0x774c, 0xd19d, 0x774a, 0xd198, - 0x7747, 0xd192, 0x7745, 0xd18c, 0x7743, 0xd186, 0x7741, 0xd180, - 0x773e, 0xd17a, 0x773c, 0xd174, 0x773a, 0xd16f, 0x7738, 0xd169, - 0x7735, 0xd163, 0x7733, 0xd15d, 0x7731, 0xd157, 0x772e, 0xd151, - 0x772c, 0xd14b, 0x772a, 0xd146, 0x7727, 0xd140, 0x7725, 0xd13a, - 0x7723, 0xd134, 0x7721, 0xd12e, 0x771e, 0xd128, 0x771c, 0xd123, - 0x771a, 0xd11d, 0x7717, 0xd117, 0x7715, 0xd111, 0x7713, 0xd10b, - 0x7710, 0xd105, 0x770e, 0xd0ff, 0x770c, 0xd0fa, 0x770a, 0xd0f4, - 0x7707, 0xd0ee, 0x7705, 0xd0e8, 0x7703, 0xd0e2, 0x7700, 0xd0dc, - 0x76fe, 0xd0d7, 0x76fc, 0xd0d1, 0x76f9, 0xd0cb, 0x76f7, 0xd0c5, - 0x76f5, 0xd0bf, 0x76f2, 0xd0b9, 0x76f0, 0xd0b4, 0x76ee, 0xd0ae, - 0x76eb, 0xd0a8, 0x76e9, 0xd0a2, 0x76e7, 0xd09c, 0x76e4, 0xd096, - 0x76e2, 0xd091, 0x76e0, 0xd08b, 0x76dd, 0xd085, 0x76db, 0xd07f, - 0x76d9, 0xd079, 0x76d6, 0xd073, 0x76d4, 0xd06e, 0x76d2, 0xd068, - 0x76cf, 0xd062, 0x76cd, 0xd05c, 0x76cb, 0xd056, 0x76c8, 0xd050, - 0x76c6, 0xd04b, 0x76c4, 0xd045, 0x76c1, 0xd03f, 0x76bf, 0xd039, - 0x76bd, 0xd033, 0x76ba, 0xd02d, 0x76b8, 0xd028, 0x76b6, 0xd022, - 0x76b3, 0xd01c, 0x76b1, 0xd016, 0x76af, 0xd010, 0x76ac, 0xd00a, - 0x76aa, 0xd005, 0x76a8, 0xcfff, 0x76a5, 0xcff9, 0x76a3, 0xcff3, - 0x76a0, 0xcfed, 0x769e, 0xcfe7, 0x769c, 0xcfe2, 0x7699, 0xcfdc, - 0x7697, 0xcfd6, 0x7695, 0xcfd0, 0x7692, 0xcfca, 0x7690, 0xcfc5, - 0x768e, 0xcfbf, 0x768b, 0xcfb9, 0x7689, 0xcfb3, 0x7686, 0xcfad, - 0x7684, 0xcfa7, 0x7682, 0xcfa2, 0x767f, 0xcf9c, 0x767d, 0xcf96, - 0x767b, 0xcf90, 0x7678, 0xcf8a, 0x7676, 0xcf85, 0x7673, 0xcf7f, - 0x7671, 0xcf79, 0x766f, 0xcf73, 0x766c, 0xcf6d, 0x766a, 0xcf67, - 0x7668, 0xcf62, 0x7665, 0xcf5c, 0x7663, 0xcf56, 0x7660, 0xcf50, - 0x765e, 0xcf4a, 0x765c, 0xcf45, 0x7659, 0xcf3f, 0x7657, 0xcf39, - 0x7654, 0xcf33, 0x7652, 0xcf2d, 0x7650, 0xcf28, 0x764d, 0xcf22, - 0x764b, 0xcf1c, 0x7648, 0xcf16, 0x7646, 0xcf10, 0x7644, 0xcf0b, - 0x7641, 0xcf05, 0x763f, 0xceff, 0x763c, 0xcef9, 0x763a, 0xcef3, - 0x7638, 0xceee, 0x7635, 0xcee8, 0x7633, 0xcee2, 0x7630, 0xcedc, - 0x762e, 0xced6, 0x762b, 0xced1, 0x7629, 0xcecb, 0x7627, 0xcec5, - 0x7624, 0xcebf, 0x7622, 0xceb9, 0x761f, 0xceb4, 0x761d, 0xceae, - 0x761b, 0xcea8, 0x7618, 0xcea2, 0x7616, 0xce9c, 0x7613, 0xce97, - 0x7611, 0xce91, 0x760e, 0xce8b, 0x760c, 0xce85, 0x760a, 0xce7f, - 0x7607, 0xce7a, 0x7605, 0xce74, 0x7602, 0xce6e, 0x7600, 0xce68, - 0x75fd, 0xce62, 0x75fb, 0xce5d, 0x75f9, 0xce57, 0x75f6, 0xce51, - 0x75f4, 0xce4b, 0x75f1, 0xce45, 0x75ef, 0xce40, 0x75ec, 0xce3a, - 0x75ea, 0xce34, 0x75e7, 0xce2e, 0x75e5, 0xce28, 0x75e3, 0xce23, - 0x75e0, 0xce1d, 0x75de, 0xce17, 0x75db, 0xce11, 0x75d9, 0xce0c, - 0x75d6, 0xce06, 0x75d4, 0xce00, 0x75d1, 0xcdfa, 0x75cf, 0xcdf4, - 0x75cc, 0xcdef, 0x75ca, 0xcde9, 0x75c8, 0xcde3, 0x75c5, 0xcddd, - 0x75c3, 0xcdd8, 0x75c0, 0xcdd2, 0x75be, 0xcdcc, 0x75bb, 0xcdc6, - 0x75b9, 0xcdc0, 0x75b6, 0xcdbb, 0x75b4, 0xcdb5, 0x75b1, 0xcdaf, - 0x75af, 0xcda9, 0x75ac, 0xcda3, 0x75aa, 0xcd9e, 0x75a7, 0xcd98, - 0x75a5, 0xcd92, 0x75a3, 0xcd8c, 0x75a0, 0xcd87, 0x759e, 0xcd81, - 0x759b, 0xcd7b, 0x7599, 0xcd75, 0x7596, 0xcd70, 0x7594, 0xcd6a, - 0x7591, 0xcd64, 0x758f, 0xcd5e, 0x758c, 0xcd58, 0x758a, 0xcd53, - 0x7587, 0xcd4d, 0x7585, 0xcd47, 0x7582, 0xcd41, 0x7580, 0xcd3c, - 0x757d, 0xcd36, 0x757b, 0xcd30, 0x7578, 0xcd2a, 0x7576, 0xcd25, - 0x7573, 0xcd1f, 0x7571, 0xcd19, 0x756e, 0xcd13, 0x756c, 0xcd0d, - 0x7569, 0xcd08, 0x7567, 0xcd02, 0x7564, 0xccfc, 0x7562, 0xccf6, - 0x755f, 0xccf1, 0x755d, 0xcceb, 0x755a, 0xcce5, 0x7558, 0xccdf, - 0x7555, 0xccda, 0x7553, 0xccd4, 0x7550, 0xccce, 0x754e, 0xccc8, - 0x754b, 0xccc3, 0x7549, 0xccbd, 0x7546, 0xccb7, 0x7544, 0xccb1, - 0x7541, 0xccac, 0x753f, 0xcca6, 0x753c, 0xcca0, 0x753a, 0xcc9a, - 0x7537, 0xcc95, 0x7535, 0xcc8f, 0x7532, 0xcc89, 0x752f, 0xcc83, - 0x752d, 0xcc7e, 0x752a, 0xcc78, 0x7528, 0xcc72, 0x7525, 0xcc6c, - 0x7523, 0xcc67, 0x7520, 0xcc61, 0x751e, 0xcc5b, 0x751b, 0xcc55, - 0x7519, 0xcc50, 0x7516, 0xcc4a, 0x7514, 0xcc44, 0x7511, 0xcc3e, - 0x750f, 0xcc39, 0x750c, 0xcc33, 0x7509, 0xcc2d, 0x7507, 0xcc27, - 0x7504, 0xcc22, 0x7502, 0xcc1c, 0x74ff, 0xcc16, 0x74fd, 0xcc10, - 0x74fa, 0xcc0b, 0x74f8, 0xcc05, 0x74f5, 0xcbff, 0x74f2, 0xcbf9, - 0x74f0, 0xcbf4, 0x74ed, 0xcbee, 0x74eb, 0xcbe8, 0x74e8, 0xcbe2, - 0x74e6, 0xcbdd, 0x74e3, 0xcbd7, 0x74e1, 0xcbd1, 0x74de, 0xcbcb, - 0x74db, 0xcbc6, 0x74d9, 0xcbc0, 0x74d6, 0xcbba, 0x74d4, 0xcbb5, - 0x74d1, 0xcbaf, 0x74cf, 0xcba9, 0x74cc, 0xcba3, 0x74c9, 0xcb9e, - 0x74c7, 0xcb98, 0x74c4, 0xcb92, 0x74c2, 0xcb8c, 0x74bf, 0xcb87, - 0x74bd, 0xcb81, 0x74ba, 0xcb7b, 0x74b7, 0xcb75, 0x74b5, 0xcb70, - 0x74b2, 0xcb6a, 0x74b0, 0xcb64, 0x74ad, 0xcb5f, 0x74ab, 0xcb59, - 0x74a8, 0xcb53, 0x74a5, 0xcb4d, 0x74a3, 0xcb48, 0x74a0, 0xcb42, - 0x749e, 0xcb3c, 0x749b, 0xcb36, 0x7498, 0xcb31, 0x7496, 0xcb2b, - 0x7493, 0xcb25, 0x7491, 0xcb20, 0x748e, 0xcb1a, 0x748b, 0xcb14, - 0x7489, 0xcb0e, 0x7486, 0xcb09, 0x7484, 0xcb03, 0x7481, 0xcafd, - 0x747e, 0xcaf8, 0x747c, 0xcaf2, 0x7479, 0xcaec, 0x7477, 0xcae6, - 0x7474, 0xcae1, 0x7471, 0xcadb, 0x746f, 0xcad5, 0x746c, 0xcad0, - 0x746a, 0xcaca, 0x7467, 0xcac4, 0x7464, 0xcabe, 0x7462, 0xcab9, - 0x745f, 0xcab3, 0x745c, 0xcaad, 0x745a, 0xcaa8, 0x7457, 0xcaa2, - 0x7455, 0xca9c, 0x7452, 0xca96, 0x744f, 0xca91, 0x744d, 0xca8b, - 0x744a, 0xca85, 0x7448, 0xca80, 0x7445, 0xca7a, 0x7442, 0xca74, - 0x7440, 0xca6e, 0x743d, 0xca69, 0x743a, 0xca63, 0x7438, 0xca5d, - 0x7435, 0xca58, 0x7432, 0xca52, 0x7430, 0xca4c, 0x742d, 0xca46, - 0x742b, 0xca41, 0x7428, 0xca3b, 0x7425, 0xca35, 0x7423, 0xca30, - 0x7420, 0xca2a, 0x741d, 0xca24, 0x741b, 0xca1f, 0x7418, 0xca19, - 0x7415, 0xca13, 0x7413, 0xca0d, 0x7410, 0xca08, 0x740d, 0xca02, - 0x740b, 0xc9fc, 0x7408, 0xc9f7, 0x7406, 0xc9f1, 0x7403, 0xc9eb, - 0x7400, 0xc9e6, 0x73fe, 0xc9e0, 0x73fb, 0xc9da, 0x73f8, 0xc9d5, - 0x73f6, 0xc9cf, 0x73f3, 0xc9c9, 0x73f0, 0xc9c3, 0x73ee, 0xc9be, - 0x73eb, 0xc9b8, 0x73e8, 0xc9b2, 0x73e6, 0xc9ad, 0x73e3, 0xc9a7, - 0x73e0, 0xc9a1, 0x73de, 0xc99c, 0x73db, 0xc996, 0x73d8, 0xc990, - 0x73d6, 0xc98b, 0x73d3, 0xc985, 0x73d0, 0xc97f, 0x73ce, 0xc97a, - 0x73cb, 0xc974, 0x73c8, 0xc96e, 0x73c6, 0xc968, 0x73c3, 0xc963, - 0x73c0, 0xc95d, 0x73bd, 0xc957, 0x73bb, 0xc952, 0x73b8, 0xc94c, - 0x73b5, 0xc946, 0x73b3, 0xc941, 0x73b0, 0xc93b, 0x73ad, 0xc935, - 0x73ab, 0xc930, 0x73a8, 0xc92a, 0x73a5, 0xc924, 0x73a3, 0xc91f, - 0x73a0, 0xc919, 0x739d, 0xc913, 0x739b, 0xc90e, 0x7398, 0xc908, - 0x7395, 0xc902, 0x7392, 0xc8fd, 0x7390, 0xc8f7, 0x738d, 0xc8f1, - 0x738a, 0xc8ec, 0x7388, 0xc8e6, 0x7385, 0xc8e0, 0x7382, 0xc8db, - 0x737f, 0xc8d5, 0x737d, 0xc8cf, 0x737a, 0xc8ca, 0x7377, 0xc8c4, - 0x7375, 0xc8be, 0x7372, 0xc8b9, 0x736f, 0xc8b3, 0x736c, 0xc8ad, - 0x736a, 0xc8a8, 0x7367, 0xc8a2, 0x7364, 0xc89c, 0x7362, 0xc897, - 0x735f, 0xc891, 0x735c, 0xc88b, 0x7359, 0xc886, 0x7357, 0xc880, - 0x7354, 0xc87a, 0x7351, 0xc875, 0x734f, 0xc86f, 0x734c, 0xc869, - 0x7349, 0xc864, 0x7346, 0xc85e, 0x7344, 0xc858, 0x7341, 0xc853, - 0x733e, 0xc84d, 0x733b, 0xc847, 0x7339, 0xc842, 0x7336, 0xc83c, - 0x7333, 0xc836, 0x7330, 0xc831, 0x732e, 0xc82b, 0x732b, 0xc825, - 0x7328, 0xc820, 0x7326, 0xc81a, 0x7323, 0xc814, 0x7320, 0xc80f, - 0x731d, 0xc809, 0x731b, 0xc803, 0x7318, 0xc7fe, 0x7315, 0xc7f8, - 0x7312, 0xc7f3, 0x7310, 0xc7ed, 0x730d, 0xc7e7, 0x730a, 0xc7e2, - 0x7307, 0xc7dc, 0x7305, 0xc7d6, 0x7302, 0xc7d1, 0x72ff, 0xc7cb, - 0x72fc, 0xc7c5, 0x72f9, 0xc7c0, 0x72f7, 0xc7ba, 0x72f4, 0xc7b4, - 0x72f1, 0xc7af, 0x72ee, 0xc7a9, 0x72ec, 0xc7a3, 0x72e9, 0xc79e, - 0x72e6, 0xc798, 0x72e3, 0xc793, 0x72e1, 0xc78d, 0x72de, 0xc787, - 0x72db, 0xc782, 0x72d8, 0xc77c, 0x72d5, 0xc776, 0x72d3, 0xc771, - 0x72d0, 0xc76b, 0x72cd, 0xc765, 0x72ca, 0xc760, 0x72c8, 0xc75a, - 0x72c5, 0xc755, 0x72c2, 0xc74f, 0x72bf, 0xc749, 0x72bc, 0xc744, - 0x72ba, 0xc73e, 0x72b7, 0xc738, 0x72b4, 0xc733, 0x72b1, 0xc72d, - 0x72af, 0xc728, 0x72ac, 0xc722, 0x72a9, 0xc71c, 0x72a6, 0xc717, - 0x72a3, 0xc711, 0x72a1, 0xc70b, 0x729e, 0xc706, 0x729b, 0xc700, - 0x7298, 0xc6fa, 0x7295, 0xc6f5, 0x7293, 0xc6ef, 0x7290, 0xc6ea, - 0x728d, 0xc6e4, 0x728a, 0xc6de, 0x7287, 0xc6d9, 0x7285, 0xc6d3, - 0x7282, 0xc6ce, 0x727f, 0xc6c8, 0x727c, 0xc6c2, 0x7279, 0xc6bd, - 0x7276, 0xc6b7, 0x7274, 0xc6b1, 0x7271, 0xc6ac, 0x726e, 0xc6a6, - 0x726b, 0xc6a1, 0x7268, 0xc69b, 0x7266, 0xc695, 0x7263, 0xc690, - 0x7260, 0xc68a, 0x725d, 0xc684, 0x725a, 0xc67f, 0x7257, 0xc679, - 0x7255, 0xc674, 0x7252, 0xc66e, 0x724f, 0xc668, 0x724c, 0xc663, - 0x7249, 0xc65d, 0x7247, 0xc658, 0x7244, 0xc652, 0x7241, 0xc64c, - 0x723e, 0xc647, 0x723b, 0xc641, 0x7238, 0xc63c, 0x7236, 0xc636, - 0x7233, 0xc630, 0x7230, 0xc62b, 0x722d, 0xc625, 0x722a, 0xc620, - 0x7227, 0xc61a, 0x7224, 0xc614, 0x7222, 0xc60f, 0x721f, 0xc609, - 0x721c, 0xc603, 0x7219, 0xc5fe, 0x7216, 0xc5f8, 0x7213, 0xc5f3, - 0x7211, 0xc5ed, 0x720e, 0xc5e7, 0x720b, 0xc5e2, 0x7208, 0xc5dc, - 0x7205, 0xc5d7, 0x7202, 0xc5d1, 0x71ff, 0xc5cc, 0x71fd, 0xc5c6, - 0x71fa, 0xc5c0, 0x71f7, 0xc5bb, 0x71f4, 0xc5b5, 0x71f1, 0xc5b0, - 0x71ee, 0xc5aa, 0x71eb, 0xc5a4, 0x71e9, 0xc59f, 0x71e6, 0xc599, - 0x71e3, 0xc594, 0x71e0, 0xc58e, 0x71dd, 0xc588, 0x71da, 0xc583, - 0x71d7, 0xc57d, 0x71d4, 0xc578, 0x71d2, 0xc572, 0x71cf, 0xc56c, - 0x71cc, 0xc567, 0x71c9, 0xc561, 0x71c6, 0xc55c, 0x71c3, 0xc556, - 0x71c0, 0xc551, 0x71bd, 0xc54b, 0x71bb, 0xc545, 0x71b8, 0xc540, - 0x71b5, 0xc53a, 0x71b2, 0xc535, 0x71af, 0xc52f, 0x71ac, 0xc529, - 0x71a9, 0xc524, 0x71a6, 0xc51e, 0x71a3, 0xc519, 0x71a1, 0xc513, - 0x719e, 0xc50e, 0x719b, 0xc508, 0x7198, 0xc502, 0x7195, 0xc4fd, - 0x7192, 0xc4f7, 0x718f, 0xc4f2, 0x718c, 0xc4ec, 0x7189, 0xc4e7, - 0x7186, 0xc4e1, 0x7184, 0xc4db, 0x7181, 0xc4d6, 0x717e, 0xc4d0, - 0x717b, 0xc4cb, 0x7178, 0xc4c5, 0x7175, 0xc4c0, 0x7172, 0xc4ba, - 0x716f, 0xc4b4, 0x716c, 0xc4af, 0x7169, 0xc4a9, 0x7167, 0xc4a4, - 0x7164, 0xc49e, 0x7161, 0xc499, 0x715e, 0xc493, 0x715b, 0xc48d, - 0x7158, 0xc488, 0x7155, 0xc482, 0x7152, 0xc47d, 0x714f, 0xc477, - 0x714c, 0xc472, 0x7149, 0xc46c, 0x7146, 0xc467, 0x7143, 0xc461, - 0x7141, 0xc45b, 0x713e, 0xc456, 0x713b, 0xc450, 0x7138, 0xc44b, - 0x7135, 0xc445, 0x7132, 0xc440, 0x712f, 0xc43a, 0x712c, 0xc434, - 0x7129, 0xc42f, 0x7126, 0xc429, 0x7123, 0xc424, 0x7120, 0xc41e, - 0x711d, 0xc419, 0x711a, 0xc413, 0x7117, 0xc40e, 0x7114, 0xc408, - 0x7112, 0xc403, 0x710f, 0xc3fd, 0x710c, 0xc3f7, 0x7109, 0xc3f2, - 0x7106, 0xc3ec, 0x7103, 0xc3e7, 0x7100, 0xc3e1, 0x70fd, 0xc3dc, - 0x70fa, 0xc3d6, 0x70f7, 0xc3d1, 0x70f4, 0xc3cb, 0x70f1, 0xc3c5, - 0x70ee, 0xc3c0, 0x70eb, 0xc3ba, 0x70e8, 0xc3b5, 0x70e5, 0xc3af, - 0x70e2, 0xc3aa, 0x70df, 0xc3a4, 0x70dc, 0xc39f, 0x70d9, 0xc399, - 0x70d6, 0xc394, 0x70d3, 0xc38e, 0x70d1, 0xc389, 0x70ce, 0xc383, - 0x70cb, 0xc37d, 0x70c8, 0xc378, 0x70c5, 0xc372, 0x70c2, 0xc36d, - 0x70bf, 0xc367, 0x70bc, 0xc362, 0x70b9, 0xc35c, 0x70b6, 0xc357, - 0x70b3, 0xc351, 0x70b0, 0xc34c, 0x70ad, 0xc346, 0x70aa, 0xc341, - 0x70a7, 0xc33b, 0x70a4, 0xc336, 0x70a1, 0xc330, 0x709e, 0xc32a, - 0x709b, 0xc325, 0x7098, 0xc31f, 0x7095, 0xc31a, 0x7092, 0xc314, - 0x708f, 0xc30f, 0x708c, 0xc309, 0x7089, 0xc304, 0x7086, 0xc2fe, - 0x7083, 0xc2f9, 0x7080, 0xc2f3, 0x707d, 0xc2ee, 0x707a, 0xc2e8, - 0x7077, 0xc2e3, 0x7074, 0xc2dd, 0x7071, 0xc2d8, 0x706e, 0xc2d2, - 0x706b, 0xc2cd, 0x7068, 0xc2c7, 0x7065, 0xc2c2, 0x7062, 0xc2bc, - 0x705f, 0xc2b7, 0x705c, 0xc2b1, 0x7059, 0xc2ab, 0x7056, 0xc2a6, - 0x7053, 0xc2a0, 0x7050, 0xc29b, 0x704d, 0xc295, 0x704a, 0xc290, - 0x7047, 0xc28a, 0x7044, 0xc285, 0x7041, 0xc27f, 0x703e, 0xc27a, - 0x703b, 0xc274, 0x7038, 0xc26f, 0x7035, 0xc269, 0x7032, 0xc264, - 0x702f, 0xc25e, 0x702c, 0xc259, 0x7029, 0xc253, 0x7026, 0xc24e, - 0x7023, 0xc248, 0x7020, 0xc243, 0x701d, 0xc23d, 0x7019, 0xc238, - 0x7016, 0xc232, 0x7013, 0xc22d, 0x7010, 0xc227, 0x700d, 0xc222, - 0x700a, 0xc21c, 0x7007, 0xc217, 0x7004, 0xc211, 0x7001, 0xc20c, - 0x6ffe, 0xc206, 0x6ffb, 0xc201, 0x6ff8, 0xc1fb, 0x6ff5, 0xc1f6, - 0x6ff2, 0xc1f0, 0x6fef, 0xc1eb, 0x6fec, 0xc1e5, 0x6fe9, 0xc1e0, - 0x6fe6, 0xc1da, 0x6fe3, 0xc1d5, 0x6fe0, 0xc1cf, 0x6fdd, 0xc1ca, - 0x6fda, 0xc1c4, 0x6fd6, 0xc1bf, 0x6fd3, 0xc1b9, 0x6fd0, 0xc1b4, - 0x6fcd, 0xc1ae, 0x6fca, 0xc1a9, 0x6fc7, 0xc1a3, 0x6fc4, 0xc19e, - 0x6fc1, 0xc198, 0x6fbe, 0xc193, 0x6fbb, 0xc18d, 0x6fb8, 0xc188, - 0x6fb5, 0xc183, 0x6fb2, 0xc17d, 0x6faf, 0xc178, 0x6fac, 0xc172, - 0x6fa9, 0xc16d, 0x6fa5, 0xc167, 0x6fa2, 0xc162, 0x6f9f, 0xc15c, - 0x6f9c, 0xc157, 0x6f99, 0xc151, 0x6f96, 0xc14c, 0x6f93, 0xc146, - 0x6f90, 0xc141, 0x6f8d, 0xc13b, 0x6f8a, 0xc136, 0x6f87, 0xc130, - 0x6f84, 0xc12b, 0x6f81, 0xc125, 0x6f7d, 0xc120, 0x6f7a, 0xc11a, - 0x6f77, 0xc115, 0x6f74, 0xc10f, 0x6f71, 0xc10a, 0x6f6e, 0xc105, - 0x6f6b, 0xc0ff, 0x6f68, 0xc0fa, 0x6f65, 0xc0f4, 0x6f62, 0xc0ef, - 0x6f5f, 0xc0e9, 0x6f5b, 0xc0e4, 0x6f58, 0xc0de, 0x6f55, 0xc0d9, - 0x6f52, 0xc0d3, 0x6f4f, 0xc0ce, 0x6f4c, 0xc0c8, 0x6f49, 0xc0c3, - 0x6f46, 0xc0bd, 0x6f43, 0xc0b8, 0x6f3f, 0xc0b3, 0x6f3c, 0xc0ad, - 0x6f39, 0xc0a8, 0x6f36, 0xc0a2, 0x6f33, 0xc09d, 0x6f30, 0xc097, - 0x6f2d, 0xc092, 0x6f2a, 0xc08c, 0x6f27, 0xc087, 0x6f23, 0xc081, - 0x6f20, 0xc07c, 0x6f1d, 0xc077, 0x6f1a, 0xc071, 0x6f17, 0xc06c, - 0x6f14, 0xc066, 0x6f11, 0xc061, 0x6f0e, 0xc05b, 0x6f0b, 0xc056, - 0x6f07, 0xc050, 0x6f04, 0xc04b, 0x6f01, 0xc045, 0x6efe, 0xc040, - 0x6efb, 0xc03b, 0x6ef8, 0xc035, 0x6ef5, 0xc030, 0x6ef1, 0xc02a, - 0x6eee, 0xc025, 0x6eeb, 0xc01f, 0x6ee8, 0xc01a, 0x6ee5, 0xc014, - 0x6ee2, 0xc00f, 0x6edf, 0xc00a, 0x6edc, 0xc004, 0x6ed8, 0xbfff, - 0x6ed5, 0xbff9, 0x6ed2, 0xbff4, 0x6ecf, 0xbfee, 0x6ecc, 0xbfe9, - 0x6ec9, 0xbfe3, 0x6ec6, 0xbfde, 0x6ec2, 0xbfd9, 0x6ebf, 0xbfd3, - 0x6ebc, 0xbfce, 0x6eb9, 0xbfc8, 0x6eb6, 0xbfc3, 0x6eb3, 0xbfbd, - 0x6eaf, 0xbfb8, 0x6eac, 0xbfb3, 0x6ea9, 0xbfad, 0x6ea6, 0xbfa8, - 0x6ea3, 0xbfa2, 0x6ea0, 0xbf9d, 0x6e9c, 0xbf97, 0x6e99, 0xbf92, - 0x6e96, 0xbf8d, 0x6e93, 0xbf87, 0x6e90, 0xbf82, 0x6e8d, 0xbf7c, - 0x6e89, 0xbf77, 0x6e86, 0xbf71, 0x6e83, 0xbf6c, 0x6e80, 0xbf67, - 0x6e7d, 0xbf61, 0x6e7a, 0xbf5c, 0x6e76, 0xbf56, 0x6e73, 0xbf51, - 0x6e70, 0xbf4b, 0x6e6d, 0xbf46, 0x6e6a, 0xbf41, 0x6e67, 0xbf3b, - 0x6e63, 0xbf36, 0x6e60, 0xbf30, 0x6e5d, 0xbf2b, 0x6e5a, 0xbf26, - 0x6e57, 0xbf20, 0x6e53, 0xbf1b, 0x6e50, 0xbf15, 0x6e4d, 0xbf10, - 0x6e4a, 0xbf0a, 0x6e47, 0xbf05, 0x6e44, 0xbf00, 0x6e40, 0xbefa, - 0x6e3d, 0xbef5, 0x6e3a, 0xbeef, 0x6e37, 0xbeea, 0x6e34, 0xbee5, - 0x6e30, 0xbedf, 0x6e2d, 0xbeda, 0x6e2a, 0xbed4, 0x6e27, 0xbecf, - 0x6e24, 0xbeca, 0x6e20, 0xbec4, 0x6e1d, 0xbebf, 0x6e1a, 0xbeb9, - 0x6e17, 0xbeb4, 0x6e14, 0xbeae, 0x6e10, 0xbea9, 0x6e0d, 0xbea4, - 0x6e0a, 0xbe9e, 0x6e07, 0xbe99, 0x6e04, 0xbe93, 0x6e00, 0xbe8e, - 0x6dfd, 0xbe89, 0x6dfa, 0xbe83, 0x6df7, 0xbe7e, 0x6df3, 0xbe78, - 0x6df0, 0xbe73, 0x6ded, 0xbe6e, 0x6dea, 0xbe68, 0x6de7, 0xbe63, - 0x6de3, 0xbe5e, 0x6de0, 0xbe58, 0x6ddd, 0xbe53, 0x6dda, 0xbe4d, - 0x6dd6, 0xbe48, 0x6dd3, 0xbe43, 0x6dd0, 0xbe3d, 0x6dcd, 0xbe38, - 0x6dca, 0xbe32, 0x6dc6, 0xbe2d, 0x6dc3, 0xbe28, 0x6dc0, 0xbe22, - 0x6dbd, 0xbe1d, 0x6db9, 0xbe17, 0x6db6, 0xbe12, 0x6db3, 0xbe0d, - 0x6db0, 0xbe07, 0x6dac, 0xbe02, 0x6da9, 0xbdfd, 0x6da6, 0xbdf7, - 0x6da3, 0xbdf2, 0x6d9f, 0xbdec, 0x6d9c, 0xbde7, 0x6d99, 0xbde2, - 0x6d96, 0xbddc, 0x6d92, 0xbdd7, 0x6d8f, 0xbdd1, 0x6d8c, 0xbdcc, - 0x6d89, 0xbdc7, 0x6d85, 0xbdc1, 0x6d82, 0xbdbc, 0x6d7f, 0xbdb7, - 0x6d7c, 0xbdb1, 0x6d78, 0xbdac, 0x6d75, 0xbda6, 0x6d72, 0xbda1, - 0x6d6f, 0xbd9c, 0x6d6b, 0xbd96, 0x6d68, 0xbd91, 0x6d65, 0xbd8c, - 0x6d62, 0xbd86, 0x6d5e, 0xbd81, 0x6d5b, 0xbd7c, 0x6d58, 0xbd76, - 0x6d55, 0xbd71, 0x6d51, 0xbd6b, 0x6d4e, 0xbd66, 0x6d4b, 0xbd61, - 0x6d48, 0xbd5b, 0x6d44, 0xbd56, 0x6d41, 0xbd51, 0x6d3e, 0xbd4b, - 0x6d3a, 0xbd46, 0x6d37, 0xbd40, 0x6d34, 0xbd3b, 0x6d31, 0xbd36, - 0x6d2d, 0xbd30, 0x6d2a, 0xbd2b, 0x6d27, 0xbd26, 0x6d23, 0xbd20, - 0x6d20, 0xbd1b, 0x6d1d, 0xbd16, 0x6d1a, 0xbd10, 0x6d16, 0xbd0b, - 0x6d13, 0xbd06, 0x6d10, 0xbd00, 0x6d0c, 0xbcfb, 0x6d09, 0xbcf5, - 0x6d06, 0xbcf0, 0x6d03, 0xbceb, 0x6cff, 0xbce5, 0x6cfc, 0xbce0, - 0x6cf9, 0xbcdb, 0x6cf5, 0xbcd5, 0x6cf2, 0xbcd0, 0x6cef, 0xbccb, - 0x6cec, 0xbcc5, 0x6ce8, 0xbcc0, 0x6ce5, 0xbcbb, 0x6ce2, 0xbcb5, - 0x6cde, 0xbcb0, 0x6cdb, 0xbcab, 0x6cd8, 0xbca5, 0x6cd4, 0xbca0, - 0x6cd1, 0xbc9b, 0x6cce, 0xbc95, 0x6cca, 0xbc90, 0x6cc7, 0xbc8b, - 0x6cc4, 0xbc85, 0x6cc1, 0xbc80, 0x6cbd, 0xbc7b, 0x6cba, 0xbc75, - 0x6cb7, 0xbc70, 0x6cb3, 0xbc6b, 0x6cb0, 0xbc65, 0x6cad, 0xbc60, - 0x6ca9, 0xbc5b, 0x6ca6, 0xbc55, 0x6ca3, 0xbc50, 0x6c9f, 0xbc4b, - 0x6c9c, 0xbc45, 0x6c99, 0xbc40, 0x6c95, 0xbc3b, 0x6c92, 0xbc35, - 0x6c8f, 0xbc30, 0x6c8b, 0xbc2b, 0x6c88, 0xbc25, 0x6c85, 0xbc20, - 0x6c81, 0xbc1b, 0x6c7e, 0xbc15, 0x6c7b, 0xbc10, 0x6c77, 0xbc0b, - 0x6c74, 0xbc05, 0x6c71, 0xbc00, 0x6c6d, 0xbbfb, 0x6c6a, 0xbbf5, - 0x6c67, 0xbbf0, 0x6c63, 0xbbeb, 0x6c60, 0xbbe5, 0x6c5d, 0xbbe0, - 0x6c59, 0xbbdb, 0x6c56, 0xbbd5, 0x6c53, 0xbbd0, 0x6c4f, 0xbbcb, - 0x6c4c, 0xbbc5, 0x6c49, 0xbbc0, 0x6c45, 0xbbbb, 0x6c42, 0xbbb5, - 0x6c3f, 0xbbb0, 0x6c3b, 0xbbab, 0x6c38, 0xbba6, 0x6c34, 0xbba0, - 0x6c31, 0xbb9b, 0x6c2e, 0xbb96, 0x6c2a, 0xbb90, 0x6c27, 0xbb8b, - 0x6c24, 0xbb86, 0x6c20, 0xbb80, 0x6c1d, 0xbb7b, 0x6c1a, 0xbb76, - 0x6c16, 0xbb70, 0x6c13, 0xbb6b, 0x6c0f, 0xbb66, 0x6c0c, 0xbb61, - 0x6c09, 0xbb5b, 0x6c05, 0xbb56, 0x6c02, 0xbb51, 0x6bff, 0xbb4b, - 0x6bfb, 0xbb46, 0x6bf8, 0xbb41, 0x6bf5, 0xbb3b, 0x6bf1, 0xbb36, - 0x6bee, 0xbb31, 0x6bea, 0xbb2c, 0x6be7, 0xbb26, 0x6be4, 0xbb21, - 0x6be0, 0xbb1c, 0x6bdd, 0xbb16, 0x6bd9, 0xbb11, 0x6bd6, 0xbb0c, - 0x6bd3, 0xbb06, 0x6bcf, 0xbb01, 0x6bcc, 0xbafc, 0x6bc9, 0xbaf7, - 0x6bc5, 0xbaf1, 0x6bc2, 0xbaec, 0x6bbe, 0xbae7, 0x6bbb, 0xbae1, - 0x6bb8, 0xbadc, 0x6bb4, 0xbad7, 0x6bb1, 0xbad2, 0x6bad, 0xbacc, - 0x6baa, 0xbac7, 0x6ba7, 0xbac2, 0x6ba3, 0xbabc, 0x6ba0, 0xbab7, - 0x6b9c, 0xbab2, 0x6b99, 0xbaad, 0x6b96, 0xbaa7, 0x6b92, 0xbaa2, - 0x6b8f, 0xba9d, 0x6b8b, 0xba97, 0x6b88, 0xba92, 0x6b85, 0xba8d, - 0x6b81, 0xba88, 0x6b7e, 0xba82, 0x6b7a, 0xba7d, 0x6b77, 0xba78, - 0x6b73, 0xba73, 0x6b70, 0xba6d, 0x6b6d, 0xba68, 0x6b69, 0xba63, - 0x6b66, 0xba5d, 0x6b62, 0xba58, 0x6b5f, 0xba53, 0x6b5c, 0xba4e, - 0x6b58, 0xba48, 0x6b55, 0xba43, 0x6b51, 0xba3e, 0x6b4e, 0xba39, - 0x6b4a, 0xba33, 0x6b47, 0xba2e, 0x6b44, 0xba29, 0x6b40, 0xba23, - 0x6b3d, 0xba1e, 0x6b39, 0xba19, 0x6b36, 0xba14, 0x6b32, 0xba0e, - 0x6b2f, 0xba09, 0x6b2c, 0xba04, 0x6b28, 0xb9ff, 0x6b25, 0xb9f9, - 0x6b21, 0xb9f4, 0x6b1e, 0xb9ef, 0x6b1a, 0xb9ea, 0x6b17, 0xb9e4, - 0x6b13, 0xb9df, 0x6b10, 0xb9da, 0x6b0d, 0xb9d5, 0x6b09, 0xb9cf, - 0x6b06, 0xb9ca, 0x6b02, 0xb9c5, 0x6aff, 0xb9c0, 0x6afb, 0xb9ba, - 0x6af8, 0xb9b5, 0x6af4, 0xb9b0, 0x6af1, 0xb9ab, 0x6aee, 0xb9a5, - 0x6aea, 0xb9a0, 0x6ae7, 0xb99b, 0x6ae3, 0xb996, 0x6ae0, 0xb990, - 0x6adc, 0xb98b, 0x6ad9, 0xb986, 0x6ad5, 0xb981, 0x6ad2, 0xb97b, - 0x6ace, 0xb976, 0x6acb, 0xb971, 0x6ac8, 0xb96c, 0x6ac4, 0xb966, - 0x6ac1, 0xb961, 0x6abd, 0xb95c, 0x6aba, 0xb957, 0x6ab6, 0xb951, - 0x6ab3, 0xb94c, 0x6aaf, 0xb947, 0x6aac, 0xb942, 0x6aa8, 0xb93c, - 0x6aa5, 0xb937, 0x6aa1, 0xb932, 0x6a9e, 0xb92d, 0x6a9a, 0xb928, - 0x6a97, 0xb922, 0x6a93, 0xb91d, 0x6a90, 0xb918, 0x6a8c, 0xb913, - 0x6a89, 0xb90d, 0x6a86, 0xb908, 0x6a82, 0xb903, 0x6a7f, 0xb8fe, - 0x6a7b, 0xb8f8, 0x6a78, 0xb8f3, 0x6a74, 0xb8ee, 0x6a71, 0xb8e9, - 0x6a6d, 0xb8e4, 0x6a6a, 0xb8de, 0x6a66, 0xb8d9, 0x6a63, 0xb8d4, - 0x6a5f, 0xb8cf, 0x6a5c, 0xb8c9, 0x6a58, 0xb8c4, 0x6a55, 0xb8bf, - 0x6a51, 0xb8ba, 0x6a4e, 0xb8b5, 0x6a4a, 0xb8af, 0x6a47, 0xb8aa, - 0x6a43, 0xb8a5, 0x6a40, 0xb8a0, 0x6a3c, 0xb89b, 0x6a39, 0xb895, - 0x6a35, 0xb890, 0x6a32, 0xb88b, 0x6a2e, 0xb886, 0x6a2b, 0xb880, - 0x6a27, 0xb87b, 0x6a24, 0xb876, 0x6a20, 0xb871, 0x6a1d, 0xb86c, - 0x6a19, 0xb866, 0x6a16, 0xb861, 0x6a12, 0xb85c, 0x6a0e, 0xb857, - 0x6a0b, 0xb852, 0x6a07, 0xb84c, 0x6a04, 0xb847, 0x6a00, 0xb842, - 0x69fd, 0xb83d, 0x69f9, 0xb838, 0x69f6, 0xb832, 0x69f2, 0xb82d, - 0x69ef, 0xb828, 0x69eb, 0xb823, 0x69e8, 0xb81e, 0x69e4, 0xb818, - 0x69e1, 0xb813, 0x69dd, 0xb80e, 0x69da, 0xb809, 0x69d6, 0xb804, - 0x69d3, 0xb7fe, 0x69cf, 0xb7f9, 0x69cb, 0xb7f4, 0x69c8, 0xb7ef, - 0x69c4, 0xb7ea, 0x69c1, 0xb7e4, 0x69bd, 0xb7df, 0x69ba, 0xb7da, - 0x69b6, 0xb7d5, 0x69b3, 0xb7d0, 0x69af, 0xb7ca, 0x69ac, 0xb7c5, - 0x69a8, 0xb7c0, 0x69a5, 0xb7bb, 0x69a1, 0xb7b6, 0x699d, 0xb7b1, - 0x699a, 0xb7ab, 0x6996, 0xb7a6, 0x6993, 0xb7a1, 0x698f, 0xb79c, - 0x698c, 0xb797, 0x6988, 0xb791, 0x6985, 0xb78c, 0x6981, 0xb787, - 0x697d, 0xb782, 0x697a, 0xb77d, 0x6976, 0xb778, 0x6973, 0xb772, - 0x696f, 0xb76d, 0x696c, 0xb768, 0x6968, 0xb763, 0x6964, 0xb75e, - 0x6961, 0xb758, 0x695d, 0xb753, 0x695a, 0xb74e, 0x6956, 0xb749, - 0x6953, 0xb744, 0x694f, 0xb73f, 0x694b, 0xb739, 0x6948, 0xb734, - 0x6944, 0xb72f, 0x6941, 0xb72a, 0x693d, 0xb725, 0x693a, 0xb720, - 0x6936, 0xb71a, 0x6932, 0xb715, 0x692f, 0xb710, 0x692b, 0xb70b, - 0x6928, 0xb706, 0x6924, 0xb701, 0x6921, 0xb6fb, 0x691d, 0xb6f6, - 0x6919, 0xb6f1, 0x6916, 0xb6ec, 0x6912, 0xb6e7, 0x690f, 0xb6e2, - 0x690b, 0xb6dd, 0x6907, 0xb6d7, 0x6904, 0xb6d2, 0x6900, 0xb6cd, - 0x68fd, 0xb6c8, 0x68f9, 0xb6c3, 0x68f5, 0xb6be, 0x68f2, 0xb6b8, - 0x68ee, 0xb6b3, 0x68eb, 0xb6ae, 0x68e7, 0xb6a9, 0x68e3, 0xb6a4, - 0x68e0, 0xb69f, 0x68dc, 0xb69a, 0x68d9, 0xb694, 0x68d5, 0xb68f, - 0x68d1, 0xb68a, 0x68ce, 0xb685, 0x68ca, 0xb680, 0x68c7, 0xb67b, - 0x68c3, 0xb676, 0x68bf, 0xb670, 0x68bc, 0xb66b, 0x68b8, 0xb666, - 0x68b5, 0xb661, 0x68b1, 0xb65c, 0x68ad, 0xb657, 0x68aa, 0xb652, - 0x68a6, 0xb64c, 0x68a3, 0xb647, 0x689f, 0xb642, 0x689b, 0xb63d, - 0x6898, 0xb638, 0x6894, 0xb633, 0x6890, 0xb62e, 0x688d, 0xb628, - 0x6889, 0xb623, 0x6886, 0xb61e, 0x6882, 0xb619, 0x687e, 0xb614, - 0x687b, 0xb60f, 0x6877, 0xb60a, 0x6873, 0xb605, 0x6870, 0xb5ff, - 0x686c, 0xb5fa, 0x6868, 0xb5f5, 0x6865, 0xb5f0, 0x6861, 0xb5eb, - 0x685e, 0xb5e6, 0x685a, 0xb5e1, 0x6856, 0xb5dc, 0x6853, 0xb5d6, - 0x684f, 0xb5d1, 0x684b, 0xb5cc, 0x6848, 0xb5c7, 0x6844, 0xb5c2, - 0x6840, 0xb5bd, 0x683d, 0xb5b8, 0x6839, 0xb5b3, 0x6835, 0xb5ae, - 0x6832, 0xb5a8, 0x682e, 0xb5a3, 0x682b, 0xb59e, 0x6827, 0xb599, - 0x6823, 0xb594, 0x6820, 0xb58f, 0x681c, 0xb58a, 0x6818, 0xb585, - 0x6815, 0xb57f, 0x6811, 0xb57a, 0x680d, 0xb575, 0x680a, 0xb570, - 0x6806, 0xb56b, 0x6802, 0xb566, 0x67ff, 0xb561, 0x67fb, 0xb55c, - 0x67f7, 0xb557, 0x67f4, 0xb552, 0x67f0, 0xb54c, 0x67ec, 0xb547, - 0x67e9, 0xb542, 0x67e5, 0xb53d, 0x67e1, 0xb538, 0x67de, 0xb533, - 0x67da, 0xb52e, 0x67d6, 0xb529, 0x67d3, 0xb524, 0x67cf, 0xb51f, - 0x67cb, 0xb519, 0x67c8, 0xb514, 0x67c4, 0xb50f, 0x67c0, 0xb50a, - 0x67bd, 0xb505, 0x67b9, 0xb500, 0x67b5, 0xb4fb, 0x67b2, 0xb4f6, - 0x67ae, 0xb4f1, 0x67aa, 0xb4ec, 0x67a6, 0xb4e7, 0x67a3, 0xb4e1, - 0x679f, 0xb4dc, 0x679b, 0xb4d7, 0x6798, 0xb4d2, 0x6794, 0xb4cd, - 0x6790, 0xb4c8, 0x678d, 0xb4c3, 0x6789, 0xb4be, 0x6785, 0xb4b9, - 0x6782, 0xb4b4, 0x677e, 0xb4af, 0x677a, 0xb4aa, 0x6776, 0xb4a4, - 0x6773, 0xb49f, 0x676f, 0xb49a, 0x676b, 0xb495, 0x6768, 0xb490, - 0x6764, 0xb48b, 0x6760, 0xb486, 0x675d, 0xb481, 0x6759, 0xb47c, - 0x6755, 0xb477, 0x6751, 0xb472, 0x674e, 0xb46d, 0x674a, 0xb468, - 0x6746, 0xb462, 0x6743, 0xb45d, 0x673f, 0xb458, 0x673b, 0xb453, - 0x6737, 0xb44e, 0x6734, 0xb449, 0x6730, 0xb444, 0x672c, 0xb43f, - 0x6729, 0xb43a, 0x6725, 0xb435, 0x6721, 0xb430, 0x671d, 0xb42b, - 0x671a, 0xb426, 0x6716, 0xb421, 0x6712, 0xb41c, 0x670e, 0xb417, - 0x670b, 0xb411, 0x6707, 0xb40c, 0x6703, 0xb407, 0x6700, 0xb402, - 0x66fc, 0xb3fd, 0x66f8, 0xb3f8, 0x66f4, 0xb3f3, 0x66f1, 0xb3ee, - 0x66ed, 0xb3e9, 0x66e9, 0xb3e4, 0x66e5, 0xb3df, 0x66e2, 0xb3da, - 0x66de, 0xb3d5, 0x66da, 0xb3d0, 0x66d6, 0xb3cb, 0x66d3, 0xb3c6, - 0x66cf, 0xb3c1, 0x66cb, 0xb3bc, 0x66c8, 0xb3b7, 0x66c4, 0xb3b1, - 0x66c0, 0xb3ac, 0x66bc, 0xb3a7, 0x66b9, 0xb3a2, 0x66b5, 0xb39d, - 0x66b1, 0xb398, 0x66ad, 0xb393, 0x66aa, 0xb38e, 0x66a6, 0xb389, - 0x66a2, 0xb384, 0x669e, 0xb37f, 0x669b, 0xb37a, 0x6697, 0xb375, - 0x6693, 0xb370, 0x668f, 0xb36b, 0x668b, 0xb366, 0x6688, 0xb361, - 0x6684, 0xb35c, 0x6680, 0xb357, 0x667c, 0xb352, 0x6679, 0xb34d, - 0x6675, 0xb348, 0x6671, 0xb343, 0x666d, 0xb33e, 0x666a, 0xb339, - 0x6666, 0xb334, 0x6662, 0xb32f, 0x665e, 0xb32a, 0x665b, 0xb325, - 0x6657, 0xb31f, 0x6653, 0xb31a, 0x664f, 0xb315, 0x664b, 0xb310, - 0x6648, 0xb30b, 0x6644, 0xb306, 0x6640, 0xb301, 0x663c, 0xb2fc, - 0x6639, 0xb2f7, 0x6635, 0xb2f2, 0x6631, 0xb2ed, 0x662d, 0xb2e8, - 0x6629, 0xb2e3, 0x6626, 0xb2de, 0x6622, 0xb2d9, 0x661e, 0xb2d4, - 0x661a, 0xb2cf, 0x6616, 0xb2ca, 0x6613, 0xb2c5, 0x660f, 0xb2c0, - 0x660b, 0xb2bb, 0x6607, 0xb2b6, 0x6603, 0xb2b1, 0x6600, 0xb2ac, - 0x65fc, 0xb2a7, 0x65f8, 0xb2a2, 0x65f4, 0xb29d, 0x65f0, 0xb298, - 0x65ed, 0xb293, 0x65e9, 0xb28e, 0x65e5, 0xb289, 0x65e1, 0xb284, - 0x65dd, 0xb27f, 0x65da, 0xb27a, 0x65d6, 0xb275, 0x65d2, 0xb270, - 0x65ce, 0xb26b, 0x65ca, 0xb266, 0x65c7, 0xb261, 0x65c3, 0xb25c, - 0x65bf, 0xb257, 0x65bb, 0xb252, 0x65b7, 0xb24d, 0x65b4, 0xb248, - 0x65b0, 0xb243, 0x65ac, 0xb23e, 0x65a8, 0xb239, 0x65a4, 0xb234, - 0x65a0, 0xb22f, 0x659d, 0xb22a, 0x6599, 0xb225, 0x6595, 0xb220, - 0x6591, 0xb21b, 0x658d, 0xb216, 0x658a, 0xb211, 0x6586, 0xb20c, - 0x6582, 0xb207, 0x657e, 0xb202, 0x657a, 0xb1fd, 0x6576, 0xb1f8, - 0x6573, 0xb1f3, 0x656f, 0xb1ee, 0x656b, 0xb1e9, 0x6567, 0xb1e4, - 0x6563, 0xb1df, 0x655f, 0xb1da, 0x655c, 0xb1d6, 0x6558, 0xb1d1, - 0x6554, 0xb1cc, 0x6550, 0xb1c7, 0x654c, 0xb1c2, 0x6548, 0xb1bd, - 0x6545, 0xb1b8, 0x6541, 0xb1b3, 0x653d, 0xb1ae, 0x6539, 0xb1a9, - 0x6535, 0xb1a4, 0x6531, 0xb19f, 0x652d, 0xb19a, 0x652a, 0xb195, - 0x6526, 0xb190, 0x6522, 0xb18b, 0x651e, 0xb186, 0x651a, 0xb181, - 0x6516, 0xb17c, 0x6513, 0xb177, 0x650f, 0xb172, 0x650b, 0xb16d, - 0x6507, 0xb168, 0x6503, 0xb163, 0x64ff, 0xb15e, 0x64fb, 0xb159, - 0x64f7, 0xb154, 0x64f4, 0xb14f, 0x64f0, 0xb14a, 0x64ec, 0xb146, - 0x64e8, 0xb141, 0x64e4, 0xb13c, 0x64e0, 0xb137, 0x64dc, 0xb132, - 0x64d9, 0xb12d, 0x64d5, 0xb128, 0x64d1, 0xb123, 0x64cd, 0xb11e, - 0x64c9, 0xb119, 0x64c5, 0xb114, 0x64c1, 0xb10f, 0x64bd, 0xb10a, - 0x64ba, 0xb105, 0x64b6, 0xb100, 0x64b2, 0xb0fb, 0x64ae, 0xb0f6, - 0x64aa, 0xb0f1, 0x64a6, 0xb0ec, 0x64a2, 0xb0e8, 0x649e, 0xb0e3, - 0x649b, 0xb0de, 0x6497, 0xb0d9, 0x6493, 0xb0d4, 0x648f, 0xb0cf, - 0x648b, 0xb0ca, 0x6487, 0xb0c5, 0x6483, 0xb0c0, 0x647f, 0xb0bb, - 0x647b, 0xb0b6, 0x6478, 0xb0b1, 0x6474, 0xb0ac, 0x6470, 0xb0a7, - 0x646c, 0xb0a2, 0x6468, 0xb09e, 0x6464, 0xb099, 0x6460, 0xb094, - 0x645c, 0xb08f, 0x6458, 0xb08a, 0x6454, 0xb085, 0x6451, 0xb080, - 0x644d, 0xb07b, 0x6449, 0xb076, 0x6445, 0xb071, 0x6441, 0xb06c, - 0x643d, 0xb067, 0x6439, 0xb062, 0x6435, 0xb05e, 0x6431, 0xb059, - 0x642d, 0xb054, 0x6429, 0xb04f, 0x6426, 0xb04a, 0x6422, 0xb045, - 0x641e, 0xb040, 0x641a, 0xb03b, 0x6416, 0xb036, 0x6412, 0xb031, - 0x640e, 0xb02c, 0x640a, 0xb027, 0x6406, 0xb023, 0x6402, 0xb01e, - 0x63fe, 0xb019, 0x63fa, 0xb014, 0x63f7, 0xb00f, 0x63f3, 0xb00a, - 0x63ef, 0xb005, 0x63eb, 0xb000, 0x63e7, 0xaffb, 0x63e3, 0xaff6, - 0x63df, 0xaff1, 0x63db, 0xafed, 0x63d7, 0xafe8, 0x63d3, 0xafe3, - 0x63cf, 0xafde, 0x63cb, 0xafd9, 0x63c7, 0xafd4, 0x63c3, 0xafcf, - 0x63c0, 0xafca, 0x63bc, 0xafc5, 0x63b8, 0xafc1, 0x63b4, 0xafbc, - 0x63b0, 0xafb7, 0x63ac, 0xafb2, 0x63a8, 0xafad, 0x63a4, 0xafa8, - 0x63a0, 0xafa3, 0x639c, 0xaf9e, 0x6398, 0xaf99, 0x6394, 0xaf94, - 0x6390, 0xaf90, 0x638c, 0xaf8b, 0x6388, 0xaf86, 0x6384, 0xaf81, - 0x6380, 0xaf7c, 0x637c, 0xaf77, 0x6378, 0xaf72, 0x6375, 0xaf6d, - 0x6371, 0xaf69, 0x636d, 0xaf64, 0x6369, 0xaf5f, 0x6365, 0xaf5a, - 0x6361, 0xaf55, 0x635d, 0xaf50, 0x6359, 0xaf4b, 0x6355, 0xaf46, - 0x6351, 0xaf41, 0x634d, 0xaf3d, 0x6349, 0xaf38, 0x6345, 0xaf33, - 0x6341, 0xaf2e, 0x633d, 0xaf29, 0x6339, 0xaf24, 0x6335, 0xaf1f, - 0x6331, 0xaf1b, 0x632d, 0xaf16, 0x6329, 0xaf11, 0x6325, 0xaf0c, - 0x6321, 0xaf07, 0x631d, 0xaf02, 0x6319, 0xaefd, 0x6315, 0xaef8, - 0x6311, 0xaef4, 0x630d, 0xaeef, 0x6309, 0xaeea, 0x6305, 0xaee5, - 0x6301, 0xaee0, 0x62fd, 0xaedb, 0x62f9, 0xaed6, 0x62f5, 0xaed2, - 0x62f2, 0xaecd, 0x62ee, 0xaec8, 0x62ea, 0xaec3, 0x62e6, 0xaebe, - 0x62e2, 0xaeb9, 0x62de, 0xaeb4, 0x62da, 0xaeb0, 0x62d6, 0xaeab, - 0x62d2, 0xaea6, 0x62ce, 0xaea1, 0x62ca, 0xae9c, 0x62c6, 0xae97, - 0x62c2, 0xae92, 0x62be, 0xae8e, 0x62ba, 0xae89, 0x62b6, 0xae84, - 0x62b2, 0xae7f, 0x62ae, 0xae7a, 0x62aa, 0xae75, 0x62a6, 0xae71, - 0x62a2, 0xae6c, 0x629e, 0xae67, 0x629a, 0xae62, 0x6296, 0xae5d, - 0x6292, 0xae58, 0x628e, 0xae54, 0x628a, 0xae4f, 0x6286, 0xae4a, - 0x6282, 0xae45, 0x627e, 0xae40, 0x627a, 0xae3b, 0x6275, 0xae37, - 0x6271, 0xae32, 0x626d, 0xae2d, 0x6269, 0xae28, 0x6265, 0xae23, - 0x6261, 0xae1e, 0x625d, 0xae1a, 0x6259, 0xae15, 0x6255, 0xae10, - 0x6251, 0xae0b, 0x624d, 0xae06, 0x6249, 0xae01, 0x6245, 0xadfd, - 0x6241, 0xadf8, 0x623d, 0xadf3, 0x6239, 0xadee, 0x6235, 0xade9, - 0x6231, 0xade4, 0x622d, 0xade0, 0x6229, 0xaddb, 0x6225, 0xadd6, - 0x6221, 0xadd1, 0x621d, 0xadcc, 0x6219, 0xadc8, 0x6215, 0xadc3, - 0x6211, 0xadbe, 0x620d, 0xadb9, 0x6209, 0xadb4, 0x6205, 0xadaf, - 0x6201, 0xadab, 0x61fd, 0xada6, 0x61f9, 0xada1, 0x61f5, 0xad9c, - 0x61f1, 0xad97, 0x61ec, 0xad93, 0x61e8, 0xad8e, 0x61e4, 0xad89, - 0x61e0, 0xad84, 0x61dc, 0xad7f, 0x61d8, 0xad7b, 0x61d4, 0xad76, - 0x61d0, 0xad71, 0x61cc, 0xad6c, 0x61c8, 0xad67, 0x61c4, 0xad63, - 0x61c0, 0xad5e, 0x61bc, 0xad59, 0x61b8, 0xad54, 0x61b4, 0xad4f, - 0x61b0, 0xad4b, 0x61ac, 0xad46, 0x61a8, 0xad41, 0x61a3, 0xad3c, - 0x619f, 0xad37, 0x619b, 0xad33, 0x6197, 0xad2e, 0x6193, 0xad29, - 0x618f, 0xad24, 0x618b, 0xad1f, 0x6187, 0xad1b, 0x6183, 0xad16, - 0x617f, 0xad11, 0x617b, 0xad0c, 0x6177, 0xad08, 0x6173, 0xad03, - 0x616f, 0xacfe, 0x616b, 0xacf9, 0x6166, 0xacf4, 0x6162, 0xacf0, - 0x615e, 0xaceb, 0x615a, 0xace6, 0x6156, 0xace1, 0x6152, 0xacdd, - 0x614e, 0xacd8, 0x614a, 0xacd3, 0x6146, 0xacce, 0x6142, 0xacc9, - 0x613e, 0xacc5, 0x613a, 0xacc0, 0x6135, 0xacbb, 0x6131, 0xacb6, - 0x612d, 0xacb2, 0x6129, 0xacad, 0x6125, 0xaca8, 0x6121, 0xaca3, - 0x611d, 0xac9e, 0x6119, 0xac9a, 0x6115, 0xac95, 0x6111, 0xac90, - 0x610d, 0xac8b, 0x6108, 0xac87, 0x6104, 0xac82, 0x6100, 0xac7d, - 0x60fc, 0xac78, 0x60f8, 0xac74, 0x60f4, 0xac6f, 0x60f0, 0xac6a, - 0x60ec, 0xac65, 0x60e8, 0xac61, 0x60e4, 0xac5c, 0x60df, 0xac57, - 0x60db, 0xac52, 0x60d7, 0xac4e, 0x60d3, 0xac49, 0x60cf, 0xac44, - 0x60cb, 0xac3f, 0x60c7, 0xac3b, 0x60c3, 0xac36, 0x60bf, 0xac31, - 0x60ba, 0xac2c, 0x60b6, 0xac28, 0x60b2, 0xac23, 0x60ae, 0xac1e, - 0x60aa, 0xac19, 0x60a6, 0xac15, 0x60a2, 0xac10, 0x609e, 0xac0b, - 0x6099, 0xac06, 0x6095, 0xac02, 0x6091, 0xabfd, 0x608d, 0xabf8, - 0x6089, 0xabf3, 0x6085, 0xabef, 0x6081, 0xabea, 0x607d, 0xabe5, - 0x6078, 0xabe0, 0x6074, 0xabdc, 0x6070, 0xabd7, 0x606c, 0xabd2, - 0x6068, 0xabcd, 0x6064, 0xabc9, 0x6060, 0xabc4, 0x605c, 0xabbf, - 0x6057, 0xabbb, 0x6053, 0xabb6, 0x604f, 0xabb1, 0x604b, 0xabac, - 0x6047, 0xaba8, 0x6043, 0xaba3, 0x603f, 0xab9e, 0x603a, 0xab99, - 0x6036, 0xab95, 0x6032, 0xab90, 0x602e, 0xab8b, 0x602a, 0xab87, - 0x6026, 0xab82, 0x6022, 0xab7d, 0x601d, 0xab78, 0x6019, 0xab74, - 0x6015, 0xab6f, 0x6011, 0xab6a, 0x600d, 0xab66, 0x6009, 0xab61, - 0x6004, 0xab5c, 0x6000, 0xab57, 0x5ffc, 0xab53, 0x5ff8, 0xab4e, - 0x5ff4, 0xab49, 0x5ff0, 0xab45, 0x5fec, 0xab40, 0x5fe7, 0xab3b, - 0x5fe3, 0xab36, 0x5fdf, 0xab32, 0x5fdb, 0xab2d, 0x5fd7, 0xab28, - 0x5fd3, 0xab24, 0x5fce, 0xab1f, 0x5fca, 0xab1a, 0x5fc6, 0xab16, - 0x5fc2, 0xab11, 0x5fbe, 0xab0c, 0x5fba, 0xab07, 0x5fb5, 0xab03, - 0x5fb1, 0xaafe, 0x5fad, 0xaaf9, 0x5fa9, 0xaaf5, 0x5fa5, 0xaaf0, - 0x5fa0, 0xaaeb, 0x5f9c, 0xaae7, 0x5f98, 0xaae2, 0x5f94, 0xaadd, - 0x5f90, 0xaad8, 0x5f8c, 0xaad4, 0x5f87, 0xaacf, 0x5f83, 0xaaca, - 0x5f7f, 0xaac6, 0x5f7b, 0xaac1, 0x5f77, 0xaabc, 0x5f72, 0xaab8, - 0x5f6e, 0xaab3, 0x5f6a, 0xaaae, 0x5f66, 0xaaaa, 0x5f62, 0xaaa5, - 0x5f5e, 0xaaa0, 0x5f59, 0xaa9c, 0x5f55, 0xaa97, 0x5f51, 0xaa92, - 0x5f4d, 0xaa8e, 0x5f49, 0xaa89, 0x5f44, 0xaa84, 0x5f40, 0xaa7f, - 0x5f3c, 0xaa7b, 0x5f38, 0xaa76, 0x5f34, 0xaa71, 0x5f2f, 0xaa6d, - 0x5f2b, 0xaa68, 0x5f27, 0xaa63, 0x5f23, 0xaa5f, 0x5f1f, 0xaa5a, - 0x5f1a, 0xaa55, 0x5f16, 0xaa51, 0x5f12, 0xaa4c, 0x5f0e, 0xaa47, - 0x5f0a, 0xaa43, 0x5f05, 0xaa3e, 0x5f01, 0xaa39, 0x5efd, 0xaa35, - 0x5ef9, 0xaa30, 0x5ef5, 0xaa2b, 0x5ef0, 0xaa27, 0x5eec, 0xaa22, - 0x5ee8, 0xaa1d, 0x5ee4, 0xaa19, 0x5edf, 0xaa14, 0x5edb, 0xaa10, - 0x5ed7, 0xaa0b, 0x5ed3, 0xaa06, 0x5ecf, 0xaa02, 0x5eca, 0xa9fd, - 0x5ec6, 0xa9f8, 0x5ec2, 0xa9f4, 0x5ebe, 0xa9ef, 0x5eb9, 0xa9ea, - 0x5eb5, 0xa9e6, 0x5eb1, 0xa9e1, 0x5ead, 0xa9dc, 0x5ea9, 0xa9d8, - 0x5ea4, 0xa9d3, 0x5ea0, 0xa9ce, 0x5e9c, 0xa9ca, 0x5e98, 0xa9c5, - 0x5e93, 0xa9c0, 0x5e8f, 0xa9bc, 0x5e8b, 0xa9b7, 0x5e87, 0xa9b3, - 0x5e82, 0xa9ae, 0x5e7e, 0xa9a9, 0x5e7a, 0xa9a5, 0x5e76, 0xa9a0, - 0x5e71, 0xa99b, 0x5e6d, 0xa997, 0x5e69, 0xa992, 0x5e65, 0xa98d, - 0x5e60, 0xa989, 0x5e5c, 0xa984, 0x5e58, 0xa980, 0x5e54, 0xa97b, - 0x5e50, 0xa976, 0x5e4b, 0xa972, 0x5e47, 0xa96d, 0x5e43, 0xa968, - 0x5e3f, 0xa964, 0x5e3a, 0xa95f, 0x5e36, 0xa95b, 0x5e32, 0xa956, - 0x5e2d, 0xa951, 0x5e29, 0xa94d, 0x5e25, 0xa948, 0x5e21, 0xa943, - 0x5e1c, 0xa93f, 0x5e18, 0xa93a, 0x5e14, 0xa936, 0x5e10, 0xa931, - 0x5e0b, 0xa92c, 0x5e07, 0xa928, 0x5e03, 0xa923, 0x5dff, 0xa91e, - 0x5dfa, 0xa91a, 0x5df6, 0xa915, 0x5df2, 0xa911, 0x5dee, 0xa90c, - 0x5de9, 0xa907, 0x5de5, 0xa903, 0x5de1, 0xa8fe, 0x5ddc, 0xa8fa, - 0x5dd8, 0xa8f5, 0x5dd4, 0xa8f0, 0x5dd0, 0xa8ec, 0x5dcb, 0xa8e7, - 0x5dc7, 0xa8e3, 0x5dc3, 0xa8de, 0x5dbf, 0xa8d9, 0x5dba, 0xa8d5, - 0x5db6, 0xa8d0, 0x5db2, 0xa8cc, 0x5dad, 0xa8c7, 0x5da9, 0xa8c2, - 0x5da5, 0xa8be, 0x5da1, 0xa8b9, 0x5d9c, 0xa8b5, 0x5d98, 0xa8b0, - 0x5d94, 0xa8ab, 0x5d8f, 0xa8a7, 0x5d8b, 0xa8a2, 0x5d87, 0xa89e, - 0x5d83, 0xa899, 0x5d7e, 0xa894, 0x5d7a, 0xa890, 0x5d76, 0xa88b, - 0x5d71, 0xa887, 0x5d6d, 0xa882, 0x5d69, 0xa87d, 0x5d65, 0xa879, - 0x5d60, 0xa874, 0x5d5c, 0xa870, 0x5d58, 0xa86b, 0x5d53, 0xa867, - 0x5d4f, 0xa862, 0x5d4b, 0xa85d, 0x5d46, 0xa859, 0x5d42, 0xa854, - 0x5d3e, 0xa850, 0x5d3a, 0xa84b, 0x5d35, 0xa847, 0x5d31, 0xa842, - 0x5d2d, 0xa83d, 0x5d28, 0xa839, 0x5d24, 0xa834, 0x5d20, 0xa830, - 0x5d1b, 0xa82b, 0x5d17, 0xa827, 0x5d13, 0xa822, 0x5d0e, 0xa81d, - 0x5d0a, 0xa819, 0x5d06, 0xa814, 0x5d01, 0xa810, 0x5cfd, 0xa80b, - 0x5cf9, 0xa807, 0x5cf5, 0xa802, 0x5cf0, 0xa7fd, 0x5cec, 0xa7f9, - 0x5ce8, 0xa7f4, 0x5ce3, 0xa7f0, 0x5cdf, 0xa7eb, 0x5cdb, 0xa7e7, - 0x5cd6, 0xa7e2, 0x5cd2, 0xa7de, 0x5cce, 0xa7d9, 0x5cc9, 0xa7d4, - 0x5cc5, 0xa7d0, 0x5cc1, 0xa7cb, 0x5cbc, 0xa7c7, 0x5cb8, 0xa7c2, - 0x5cb4, 0xa7be, 0x5caf, 0xa7b9, 0x5cab, 0xa7b5, 0x5ca7, 0xa7b0, - 0x5ca2, 0xa7ab, 0x5c9e, 0xa7a7, 0x5c9a, 0xa7a2, 0x5c95, 0xa79e, - 0x5c91, 0xa799, 0x5c8d, 0xa795, 0x5c88, 0xa790, 0x5c84, 0xa78c, - 0x5c80, 0xa787, 0x5c7b, 0xa783, 0x5c77, 0xa77e, 0x5c73, 0xa779, - 0x5c6e, 0xa775, 0x5c6a, 0xa770, 0x5c66, 0xa76c, 0x5c61, 0xa767, - 0x5c5d, 0xa763, 0x5c58, 0xa75e, 0x5c54, 0xa75a, 0x5c50, 0xa755, - 0x5c4b, 0xa751, 0x5c47, 0xa74c, 0x5c43, 0xa748, 0x5c3e, 0xa743, - 0x5c3a, 0xa73f, 0x5c36, 0xa73a, 0x5c31, 0xa735, 0x5c2d, 0xa731, - 0x5c29, 0xa72c, 0x5c24, 0xa728, 0x5c20, 0xa723, 0x5c1b, 0xa71f, - 0x5c17, 0xa71a, 0x5c13, 0xa716, 0x5c0e, 0xa711, 0x5c0a, 0xa70d, - 0x5c06, 0xa708, 0x5c01, 0xa704, 0x5bfd, 0xa6ff, 0x5bf9, 0xa6fb, - 0x5bf4, 0xa6f6, 0x5bf0, 0xa6f2, 0x5beb, 0xa6ed, 0x5be7, 0xa6e9, - 0x5be3, 0xa6e4, 0x5bde, 0xa6e0, 0x5bda, 0xa6db, 0x5bd6, 0xa6d7, - 0x5bd1, 0xa6d2, 0x5bcd, 0xa6ce, 0x5bc8, 0xa6c9, 0x5bc4, 0xa6c5, - 0x5bc0, 0xa6c0, 0x5bbb, 0xa6bc, 0x5bb7, 0xa6b7, 0x5bb2, 0xa6b3, - 0x5bae, 0xa6ae, 0x5baa, 0xa6aa, 0x5ba5, 0xa6a5, 0x5ba1, 0xa6a1, - 0x5b9d, 0xa69c, 0x5b98, 0xa698, 0x5b94, 0xa693, 0x5b8f, 0xa68f, - 0x5b8b, 0xa68a, 0x5b87, 0xa686, 0x5b82, 0xa681, 0x5b7e, 0xa67d, - 0x5b79, 0xa678, 0x5b75, 0xa674, 0x5b71, 0xa66f, 0x5b6c, 0xa66b, - 0x5b68, 0xa666, 0x5b63, 0xa662, 0x5b5f, 0xa65d, 0x5b5b, 0xa659, - 0x5b56, 0xa654, 0x5b52, 0xa650, 0x5b4d, 0xa64b, 0x5b49, 0xa647, - 0x5b45, 0xa642, 0x5b40, 0xa63e, 0x5b3c, 0xa639, 0x5b37, 0xa635, - 0x5b33, 0xa630, 0x5b2f, 0xa62c, 0x5b2a, 0xa627, 0x5b26, 0xa623, - 0x5b21, 0xa61f, 0x5b1d, 0xa61a, 0x5b19, 0xa616, 0x5b14, 0xa611, - 0x5b10, 0xa60d, 0x5b0b, 0xa608, 0x5b07, 0xa604, 0x5b02, 0xa5ff, - 0x5afe, 0xa5fb, 0x5afa, 0xa5f6, 0x5af5, 0xa5f2, 0x5af1, 0xa5ed, - 0x5aec, 0xa5e9, 0x5ae8, 0xa5e4, 0x5ae4, 0xa5e0, 0x5adf, 0xa5dc, - 0x5adb, 0xa5d7, 0x5ad6, 0xa5d3, 0x5ad2, 0xa5ce, 0x5acd, 0xa5ca, - 0x5ac9, 0xa5c5, 0x5ac5, 0xa5c1, 0x5ac0, 0xa5bc, 0x5abc, 0xa5b8, - 0x5ab7, 0xa5b3, 0x5ab3, 0xa5af, 0x5aae, 0xa5aa, 0x5aaa, 0xa5a6, - 0x5aa5, 0xa5a2, 0x5aa1, 0xa59d, 0x5a9d, 0xa599, 0x5a98, 0xa594, - 0x5a94, 0xa590, 0x5a8f, 0xa58b, 0x5a8b, 0xa587, 0x5a86, 0xa582, - 0x5a82, 0xa57e, 0x5a7e, 0xa57a, 0x5a79, 0xa575, 0x5a75, 0xa571, - 0x5a70, 0xa56c, 0x5a6c, 0xa568, 0x5a67, 0xa563, 0x5a63, 0xa55f, - 0x5a5e, 0xa55b, 0x5a5a, 0xa556, 0x5a56, 0xa552, 0x5a51, 0xa54d, - 0x5a4d, 0xa549, 0x5a48, 0xa544, 0x5a44, 0xa540, 0x5a3f, 0xa53b, - 0x5a3b, 0xa537, 0x5a36, 0xa533, 0x5a32, 0xa52e, 0x5a2d, 0xa52a, - 0x5a29, 0xa525, 0x5a24, 0xa521, 0x5a20, 0xa51c, 0x5a1c, 0xa518, - 0x5a17, 0xa514, 0x5a13, 0xa50f, 0x5a0e, 0xa50b, 0x5a0a, 0xa506, - 0x5a05, 0xa502, 0x5a01, 0xa4fe, 0x59fc, 0xa4f9, 0x59f8, 0xa4f5, - 0x59f3, 0xa4f0, 0x59ef, 0xa4ec, 0x59ea, 0xa4e7, 0x59e6, 0xa4e3, - 0x59e1, 0xa4df, 0x59dd, 0xa4da, 0x59d9, 0xa4d6, 0x59d4, 0xa4d1, - 0x59d0, 0xa4cd, 0x59cb, 0xa4c9, 0x59c7, 0xa4c4, 0x59c2, 0xa4c0, - 0x59be, 0xa4bb, 0x59b9, 0xa4b7, 0x59b5, 0xa4b3, 0x59b0, 0xa4ae, - 0x59ac, 0xa4aa, 0x59a7, 0xa4a5, 0x59a3, 0xa4a1, 0x599e, 0xa49d, - 0x599a, 0xa498, 0x5995, 0xa494, 0x5991, 0xa48f, 0x598c, 0xa48b, - 0x5988, 0xa487, 0x5983, 0xa482, 0x597f, 0xa47e, 0x597a, 0xa479, - 0x5976, 0xa475, 0x5971, 0xa471, 0x596d, 0xa46c, 0x5968, 0xa468, - 0x5964, 0xa463, 0x595f, 0xa45f, 0x595b, 0xa45b, 0x5956, 0xa456, - 0x5952, 0xa452, 0x594d, 0xa44e, 0x5949, 0xa449, 0x5944, 0xa445, - 0x5940, 0xa440, 0x593b, 0xa43c, 0x5937, 0xa438, 0x5932, 0xa433, - 0x592e, 0xa42f, 0x5929, 0xa42a, 0x5925, 0xa426, 0x5920, 0xa422, - 0x591c, 0xa41d, 0x5917, 0xa419, 0x5913, 0xa415, 0x590e, 0xa410, - 0x590a, 0xa40c, 0x5905, 0xa407, 0x5901, 0xa403, 0x58fc, 0xa3ff, - 0x58f8, 0xa3fa, 0x58f3, 0xa3f6, 0x58ef, 0xa3f2, 0x58ea, 0xa3ed, - 0x58e6, 0xa3e9, 0x58e1, 0xa3e5, 0x58dd, 0xa3e0, 0x58d8, 0xa3dc, - 0x58d4, 0xa3d7, 0x58cf, 0xa3d3, 0x58cb, 0xa3cf, 0x58c6, 0xa3ca, - 0x58c1, 0xa3c6, 0x58bd, 0xa3c2, 0x58b8, 0xa3bd, 0x58b4, 0xa3b9, - 0x58af, 0xa3b5, 0x58ab, 0xa3b0, 0x58a6, 0xa3ac, 0x58a2, 0xa3a8, - 0x589d, 0xa3a3, 0x5899, 0xa39f, 0x5894, 0xa39a, 0x5890, 0xa396, - 0x588b, 0xa392, 0x5887, 0xa38d, 0x5882, 0xa389, 0x587d, 0xa385, - 0x5879, 0xa380, 0x5874, 0xa37c, 0x5870, 0xa378, 0x586b, 0xa373, - 0x5867, 0xa36f, 0x5862, 0xa36b, 0x585e, 0xa366, 0x5859, 0xa362, - 0x5855, 0xa35e, 0x5850, 0xa359, 0x584b, 0xa355, 0x5847, 0xa351, - 0x5842, 0xa34c, 0x583e, 0xa348, 0x5839, 0xa344, 0x5835, 0xa33f, - 0x5830, 0xa33b, 0x582c, 0xa337, 0x5827, 0xa332, 0x5822, 0xa32e, - 0x581e, 0xa32a, 0x5819, 0xa325, 0x5815, 0xa321, 0x5810, 0xa31d, - 0x580c, 0xa318, 0x5807, 0xa314, 0x5803, 0xa310, 0x57fe, 0xa30b, - 0x57f9, 0xa307, 0x57f5, 0xa303, 0x57f0, 0xa2ff, 0x57ec, 0xa2fa, - 0x57e7, 0xa2f6, 0x57e3, 0xa2f2, 0x57de, 0xa2ed, 0x57d9, 0xa2e9, - 0x57d5, 0xa2e5, 0x57d0, 0xa2e0, 0x57cc, 0xa2dc, 0x57c7, 0xa2d8, - 0x57c3, 0xa2d3, 0x57be, 0xa2cf, 0x57b9, 0xa2cb, 0x57b5, 0xa2c6, - 0x57b0, 0xa2c2, 0x57ac, 0xa2be, 0x57a7, 0xa2ba, 0x57a3, 0xa2b5, - 0x579e, 0xa2b1, 0x5799, 0xa2ad, 0x5795, 0xa2a8, 0x5790, 0xa2a4, - 0x578c, 0xa2a0, 0x5787, 0xa29b, 0x5783, 0xa297, 0x577e, 0xa293, - 0x5779, 0xa28f, 0x5775, 0xa28a, 0x5770, 0xa286, 0x576c, 0xa282, - 0x5767, 0xa27d, 0x5762, 0xa279, 0x575e, 0xa275, 0x5759, 0xa271, - 0x5755, 0xa26c, 0x5750, 0xa268, 0x574b, 0xa264, 0x5747, 0xa25f, - 0x5742, 0xa25b, 0x573e, 0xa257, 0x5739, 0xa253, 0x5734, 0xa24e, - 0x5730, 0xa24a, 0x572b, 0xa246, 0x5727, 0xa241, 0x5722, 0xa23d, - 0x571d, 0xa239, 0x5719, 0xa235, 0x5714, 0xa230, 0x5710, 0xa22c, - 0x570b, 0xa228, 0x5706, 0xa224, 0x5702, 0xa21f, 0x56fd, 0xa21b, - 0x56f9, 0xa217, 0x56f4, 0xa212, 0x56ef, 0xa20e, 0x56eb, 0xa20a, - 0x56e6, 0xa206, 0x56e2, 0xa201, 0x56dd, 0xa1fd, 0x56d8, 0xa1f9, - 0x56d4, 0xa1f5, 0x56cf, 0xa1f0, 0x56ca, 0xa1ec, 0x56c6, 0xa1e8, - 0x56c1, 0xa1e4, 0x56bd, 0xa1df, 0x56b8, 0xa1db, 0x56b3, 0xa1d7, - 0x56af, 0xa1d3, 0x56aa, 0xa1ce, 0x56a5, 0xa1ca, 0x56a1, 0xa1c6, - 0x569c, 0xa1c1, 0x5698, 0xa1bd, 0x5693, 0xa1b9, 0x568e, 0xa1b5, - 0x568a, 0xa1b0, 0x5685, 0xa1ac, 0x5680, 0xa1a8, 0x567c, 0xa1a4, - 0x5677, 0xa1a0, 0x5673, 0xa19b, 0x566e, 0xa197, 0x5669, 0xa193, - 0x5665, 0xa18f, 0x5660, 0xa18a, 0x565b, 0xa186, 0x5657, 0xa182, - 0x5652, 0xa17e, 0x564d, 0xa179, 0x5649, 0xa175, 0x5644, 0xa171, - 0x5640, 0xa16d, 0x563b, 0xa168, 0x5636, 0xa164, 0x5632, 0xa160, - 0x562d, 0xa15c, 0x5628, 0xa157, 0x5624, 0xa153, 0x561f, 0xa14f, - 0x561a, 0xa14b, 0x5616, 0xa147, 0x5611, 0xa142, 0x560c, 0xa13e, - 0x5608, 0xa13a, 0x5603, 0xa136, 0x55fe, 0xa131, 0x55fa, 0xa12d, - 0x55f5, 0xa129, 0x55f0, 0xa125, 0x55ec, 0xa121, 0x55e7, 0xa11c, - 0x55e3, 0xa118, 0x55de, 0xa114, 0x55d9, 0xa110, 0x55d5, 0xa10b, - 0x55d0, 0xa107, 0x55cb, 0xa103, 0x55c7, 0xa0ff, 0x55c2, 0xa0fb, - 0x55bd, 0xa0f6, 0x55b9, 0xa0f2, 0x55b4, 0xa0ee, 0x55af, 0xa0ea, - 0x55ab, 0xa0e6, 0x55a6, 0xa0e1, 0x55a1, 0xa0dd, 0x559d, 0xa0d9, - 0x5598, 0xa0d5, 0x5593, 0xa0d1, 0x558f, 0xa0cc, 0x558a, 0xa0c8, - 0x5585, 0xa0c4, 0x5581, 0xa0c0, 0x557c, 0xa0bc, 0x5577, 0xa0b7, - 0x5572, 0xa0b3, 0x556e, 0xa0af, 0x5569, 0xa0ab, 0x5564, 0xa0a7, - 0x5560, 0xa0a2, 0x555b, 0xa09e, 0x5556, 0xa09a, 0x5552, 0xa096, - 0x554d, 0xa092, 0x5548, 0xa08e, 0x5544, 0xa089, 0x553f, 0xa085, - 0x553a, 0xa081, 0x5536, 0xa07d, 0x5531, 0xa079, 0x552c, 0xa074, - 0x5528, 0xa070, 0x5523, 0xa06c, 0x551e, 0xa068, 0x5519, 0xa064, - 0x5515, 0xa060, 0x5510, 0xa05b, 0x550b, 0xa057, 0x5507, 0xa053, - 0x5502, 0xa04f, 0x54fd, 0xa04b, 0x54f9, 0xa046, 0x54f4, 0xa042, - 0x54ef, 0xa03e, 0x54ea, 0xa03a, 0x54e6, 0xa036, 0x54e1, 0xa032, - 0x54dc, 0xa02d, 0x54d8, 0xa029, 0x54d3, 0xa025, 0x54ce, 0xa021, - 0x54ca, 0xa01d, 0x54c5, 0xa019, 0x54c0, 0xa014, 0x54bb, 0xa010, - 0x54b7, 0xa00c, 0x54b2, 0xa008, 0x54ad, 0xa004, 0x54a9, 0xa000, - 0x54a4, 0x9ffc, 0x549f, 0x9ff7, 0x549a, 0x9ff3, 0x5496, 0x9fef, - 0x5491, 0x9feb, 0x548c, 0x9fe7, 0x5488, 0x9fe3, 0x5483, 0x9fde, - 0x547e, 0x9fda, 0x5479, 0x9fd6, 0x5475, 0x9fd2, 0x5470, 0x9fce, - 0x546b, 0x9fca, 0x5467, 0x9fc6, 0x5462, 0x9fc1, 0x545d, 0x9fbd, - 0x5458, 0x9fb9, 0x5454, 0x9fb5, 0x544f, 0x9fb1, 0x544a, 0x9fad, - 0x5445, 0x9fa9, 0x5441, 0x9fa4, 0x543c, 0x9fa0, 0x5437, 0x9f9c, - 0x5433, 0x9f98, 0x542e, 0x9f94, 0x5429, 0x9f90, 0x5424, 0x9f8c, - 0x5420, 0x9f88, 0x541b, 0x9f83, 0x5416, 0x9f7f, 0x5411, 0x9f7b, - 0x540d, 0x9f77, 0x5408, 0x9f73, 0x5403, 0x9f6f, 0x53fe, 0x9f6b, - 0x53fa, 0x9f67, 0x53f5, 0x9f62, 0x53f0, 0x9f5e, 0x53eb, 0x9f5a, - 0x53e7, 0x9f56, 0x53e2, 0x9f52, 0x53dd, 0x9f4e, 0x53d8, 0x9f4a, - 0x53d4, 0x9f46, 0x53cf, 0x9f41, 0x53ca, 0x9f3d, 0x53c5, 0x9f39, - 0x53c1, 0x9f35, 0x53bc, 0x9f31, 0x53b7, 0x9f2d, 0x53b2, 0x9f29, - 0x53ae, 0x9f25, 0x53a9, 0x9f21, 0x53a4, 0x9f1c, 0x539f, 0x9f18, - 0x539b, 0x9f14, 0x5396, 0x9f10, 0x5391, 0x9f0c, 0x538c, 0x9f08, - 0x5388, 0x9f04, 0x5383, 0x9f00, 0x537e, 0x9efc, 0x5379, 0x9ef8, - 0x5375, 0x9ef3, 0x5370, 0x9eef, 0x536b, 0x9eeb, 0x5366, 0x9ee7, - 0x5362, 0x9ee3, 0x535d, 0x9edf, 0x5358, 0x9edb, 0x5353, 0x9ed7, - 0x534e, 0x9ed3, 0x534a, 0x9ecf, 0x5345, 0x9ecb, 0x5340, 0x9ec6, - 0x533b, 0x9ec2, 0x5337, 0x9ebe, 0x5332, 0x9eba, 0x532d, 0x9eb6, - 0x5328, 0x9eb2, 0x5323, 0x9eae, 0x531f, 0x9eaa, 0x531a, 0x9ea6, - 0x5315, 0x9ea2, 0x5310, 0x9e9e, 0x530c, 0x9e9a, 0x5307, 0x9e95, - 0x5302, 0x9e91, 0x52fd, 0x9e8d, 0x52f8, 0x9e89, 0x52f4, 0x9e85, - 0x52ef, 0x9e81, 0x52ea, 0x9e7d, 0x52e5, 0x9e79, 0x52e1, 0x9e75, - 0x52dc, 0x9e71, 0x52d7, 0x9e6d, 0x52d2, 0x9e69, 0x52cd, 0x9e65, - 0x52c9, 0x9e61, 0x52c4, 0x9e5d, 0x52bf, 0x9e58, 0x52ba, 0x9e54, - 0x52b5, 0x9e50, 0x52b1, 0x9e4c, 0x52ac, 0x9e48, 0x52a7, 0x9e44, - 0x52a2, 0x9e40, 0x529d, 0x9e3c, 0x5299, 0x9e38, 0x5294, 0x9e34, - 0x528f, 0x9e30, 0x528a, 0x9e2c, 0x5285, 0x9e28, 0x5281, 0x9e24, - 0x527c, 0x9e20, 0x5277, 0x9e1c, 0x5272, 0x9e18, 0x526d, 0x9e14, - 0x5269, 0x9e0f, 0x5264, 0x9e0b, 0x525f, 0x9e07, 0x525a, 0x9e03, - 0x5255, 0x9dff, 0x5251, 0x9dfb, 0x524c, 0x9df7, 0x5247, 0x9df3, - 0x5242, 0x9def, 0x523d, 0x9deb, 0x5238, 0x9de7, 0x5234, 0x9de3, - 0x522f, 0x9ddf, 0x522a, 0x9ddb, 0x5225, 0x9dd7, 0x5220, 0x9dd3, - 0x521c, 0x9dcf, 0x5217, 0x9dcb, 0x5212, 0x9dc7, 0x520d, 0x9dc3, - 0x5208, 0x9dbf, 0x5203, 0x9dbb, 0x51ff, 0x9db7, 0x51fa, 0x9db3, - 0x51f5, 0x9daf, 0x51f0, 0x9dab, 0x51eb, 0x9da7, 0x51e6, 0x9da3, - 0x51e2, 0x9d9f, 0x51dd, 0x9d9b, 0x51d8, 0x9d97, 0x51d3, 0x9d93, - 0x51ce, 0x9d8f, 0x51c9, 0x9d8b, 0x51c5, 0x9d86, 0x51c0, 0x9d82, - 0x51bb, 0x9d7e, 0x51b6, 0x9d7a, 0x51b1, 0x9d76, 0x51ac, 0x9d72, - 0x51a8, 0x9d6e, 0x51a3, 0x9d6a, 0x519e, 0x9d66, 0x5199, 0x9d62, - 0x5194, 0x9d5e, 0x518f, 0x9d5a, 0x518b, 0x9d56, 0x5186, 0x9d52, - 0x5181, 0x9d4e, 0x517c, 0x9d4a, 0x5177, 0x9d46, 0x5172, 0x9d42, - 0x516e, 0x9d3e, 0x5169, 0x9d3a, 0x5164, 0x9d36, 0x515f, 0x9d32, - 0x515a, 0x9d2e, 0x5155, 0x9d2a, 0x5150, 0x9d26, 0x514c, 0x9d22, - 0x5147, 0x9d1e, 0x5142, 0x9d1a, 0x513d, 0x9d16, 0x5138, 0x9d12, - 0x5133, 0x9d0e, 0x512e, 0x9d0b, 0x512a, 0x9d07, 0x5125, 0x9d03, - 0x5120, 0x9cff, 0x511b, 0x9cfb, 0x5116, 0x9cf7, 0x5111, 0x9cf3, - 0x510c, 0x9cef, 0x5108, 0x9ceb, 0x5103, 0x9ce7, 0x50fe, 0x9ce3, - 0x50f9, 0x9cdf, 0x50f4, 0x9cdb, 0x50ef, 0x9cd7, 0x50ea, 0x9cd3, - 0x50e5, 0x9ccf, 0x50e1, 0x9ccb, 0x50dc, 0x9cc7, 0x50d7, 0x9cc3, - 0x50d2, 0x9cbf, 0x50cd, 0x9cbb, 0x50c8, 0x9cb7, 0x50c3, 0x9cb3, - 0x50bf, 0x9caf, 0x50ba, 0x9cab, 0x50b5, 0x9ca7, 0x50b0, 0x9ca3, - 0x50ab, 0x9c9f, 0x50a6, 0x9c9b, 0x50a1, 0x9c97, 0x509c, 0x9c93, - 0x5097, 0x9c8f, 0x5093, 0x9c8b, 0x508e, 0x9c88, 0x5089, 0x9c84, - 0x5084, 0x9c80, 0x507f, 0x9c7c, 0x507a, 0x9c78, 0x5075, 0x9c74, - 0x5070, 0x9c70, 0x506c, 0x9c6c, 0x5067, 0x9c68, 0x5062, 0x9c64, - 0x505d, 0x9c60, 0x5058, 0x9c5c, 0x5053, 0x9c58, 0x504e, 0x9c54, - 0x5049, 0x9c50, 0x5044, 0x9c4c, 0x503f, 0x9c48, 0x503b, 0x9c44, - 0x5036, 0x9c40, 0x5031, 0x9c3d, 0x502c, 0x9c39, 0x5027, 0x9c35, - 0x5022, 0x9c31, 0x501d, 0x9c2d, 0x5018, 0x9c29, 0x5013, 0x9c25, - 0x500f, 0x9c21, 0x500a, 0x9c1d, 0x5005, 0x9c19, 0x5000, 0x9c15, - 0x4ffb, 0x9c11, 0x4ff6, 0x9c0d, 0x4ff1, 0x9c09, 0x4fec, 0x9c06, - 0x4fe7, 0x9c02, 0x4fe2, 0x9bfe, 0x4fdd, 0x9bfa, 0x4fd9, 0x9bf6, - 0x4fd4, 0x9bf2, 0x4fcf, 0x9bee, 0x4fca, 0x9bea, 0x4fc5, 0x9be6, - 0x4fc0, 0x9be2, 0x4fbb, 0x9bde, 0x4fb6, 0x9bda, 0x4fb1, 0x9bd7, - 0x4fac, 0x9bd3, 0x4fa7, 0x9bcf, 0x4fa2, 0x9bcb, 0x4f9e, 0x9bc7, - 0x4f99, 0x9bc3, 0x4f94, 0x9bbf, 0x4f8f, 0x9bbb, 0x4f8a, 0x9bb7, - 0x4f85, 0x9bb3, 0x4f80, 0x9baf, 0x4f7b, 0x9bac, 0x4f76, 0x9ba8, - 0x4f71, 0x9ba4, 0x4f6c, 0x9ba0, 0x4f67, 0x9b9c, 0x4f62, 0x9b98, - 0x4f5e, 0x9b94, 0x4f59, 0x9b90, 0x4f54, 0x9b8c, 0x4f4f, 0x9b88, - 0x4f4a, 0x9b85, 0x4f45, 0x9b81, 0x4f40, 0x9b7d, 0x4f3b, 0x9b79, - 0x4f36, 0x9b75, 0x4f31, 0x9b71, 0x4f2c, 0x9b6d, 0x4f27, 0x9b69, - 0x4f22, 0x9b65, 0x4f1d, 0x9b62, 0x4f18, 0x9b5e, 0x4f14, 0x9b5a, - 0x4f0f, 0x9b56, 0x4f0a, 0x9b52, 0x4f05, 0x9b4e, 0x4f00, 0x9b4a, - 0x4efb, 0x9b46, 0x4ef6, 0x9b43, 0x4ef1, 0x9b3f, 0x4eec, 0x9b3b, - 0x4ee7, 0x9b37, 0x4ee2, 0x9b33, 0x4edd, 0x9b2f, 0x4ed8, 0x9b2b, - 0x4ed3, 0x9b27, 0x4ece, 0x9b24, 0x4ec9, 0x9b20, 0x4ec4, 0x9b1c, - 0x4ebf, 0x9b18, 0x4eba, 0x9b14, 0x4eb6, 0x9b10, 0x4eb1, 0x9b0c, - 0x4eac, 0x9b09, 0x4ea7, 0x9b05, 0x4ea2, 0x9b01, 0x4e9d, 0x9afd, - 0x4e98, 0x9af9, 0x4e93, 0x9af5, 0x4e8e, 0x9af1, 0x4e89, 0x9aed, - 0x4e84, 0x9aea, 0x4e7f, 0x9ae6, 0x4e7a, 0x9ae2, 0x4e75, 0x9ade, - 0x4e70, 0x9ada, 0x4e6b, 0x9ad6, 0x4e66, 0x9ad3, 0x4e61, 0x9acf, - 0x4e5c, 0x9acb, 0x4e57, 0x9ac7, 0x4e52, 0x9ac3, 0x4e4d, 0x9abf, - 0x4e48, 0x9abb, 0x4e43, 0x9ab8, 0x4e3e, 0x9ab4, 0x4e39, 0x9ab0, - 0x4e34, 0x9aac, 0x4e2f, 0x9aa8, 0x4e2a, 0x9aa4, 0x4e26, 0x9aa1, - 0x4e21, 0x9a9d, 0x4e1c, 0x9a99, 0x4e17, 0x9a95, 0x4e12, 0x9a91, - 0x4e0d, 0x9a8d, 0x4e08, 0x9a8a, 0x4e03, 0x9a86, 0x4dfe, 0x9a82, - 0x4df9, 0x9a7e, 0x4df4, 0x9a7a, 0x4def, 0x9a76, 0x4dea, 0x9a73, - 0x4de5, 0x9a6f, 0x4de0, 0x9a6b, 0x4ddb, 0x9a67, 0x4dd6, 0x9a63, - 0x4dd1, 0x9a60, 0x4dcc, 0x9a5c, 0x4dc7, 0x9a58, 0x4dc2, 0x9a54, - 0x4dbd, 0x9a50, 0x4db8, 0x9a4c, 0x4db3, 0x9a49, 0x4dae, 0x9a45, - 0x4da9, 0x9a41, 0x4da4, 0x9a3d, 0x4d9f, 0x9a39, 0x4d9a, 0x9a36, - 0x4d95, 0x9a32, 0x4d90, 0x9a2e, 0x4d8b, 0x9a2a, 0x4d86, 0x9a26, - 0x4d81, 0x9a23, 0x4d7c, 0x9a1f, 0x4d77, 0x9a1b, 0x4d72, 0x9a17, - 0x4d6d, 0x9a13, 0x4d68, 0x9a10, 0x4d63, 0x9a0c, 0x4d5e, 0x9a08, - 0x4d59, 0x9a04, 0x4d54, 0x9a00, 0x4d4f, 0x99fd, 0x4d4a, 0x99f9, - 0x4d45, 0x99f5, 0x4d40, 0x99f1, 0x4d3b, 0x99ed, 0x4d36, 0x99ea, - 0x4d31, 0x99e6, 0x4d2c, 0x99e2, 0x4d27, 0x99de, 0x4d22, 0x99da, - 0x4d1d, 0x99d7, 0x4d18, 0x99d3, 0x4d13, 0x99cf, 0x4d0e, 0x99cb, - 0x4d09, 0x99c7, 0x4d04, 0x99c4, 0x4cff, 0x99c0, 0x4cfa, 0x99bc, - 0x4cf5, 0x99b8, 0x4cf0, 0x99b5, 0x4ceb, 0x99b1, 0x4ce6, 0x99ad, - 0x4ce1, 0x99a9, 0x4cdb, 0x99a5, 0x4cd6, 0x99a2, 0x4cd1, 0x999e, - 0x4ccc, 0x999a, 0x4cc7, 0x9996, 0x4cc2, 0x9993, 0x4cbd, 0x998f, - 0x4cb8, 0x998b, 0x4cb3, 0x9987, 0x4cae, 0x9984, 0x4ca9, 0x9980, - 0x4ca4, 0x997c, 0x4c9f, 0x9978, 0x4c9a, 0x9975, 0x4c95, 0x9971, - 0x4c90, 0x996d, 0x4c8b, 0x9969, 0x4c86, 0x9965, 0x4c81, 0x9962, - 0x4c7c, 0x995e, 0x4c77, 0x995a, 0x4c72, 0x9956, 0x4c6d, 0x9953, - 0x4c68, 0x994f, 0x4c63, 0x994b, 0x4c5e, 0x9947, 0x4c59, 0x9944, - 0x4c54, 0x9940, 0x4c4f, 0x993c, 0x4c49, 0x9938, 0x4c44, 0x9935, - 0x4c3f, 0x9931, 0x4c3a, 0x992d, 0x4c35, 0x992a, 0x4c30, 0x9926, - 0x4c2b, 0x9922, 0x4c26, 0x991e, 0x4c21, 0x991b, 0x4c1c, 0x9917, - 0x4c17, 0x9913, 0x4c12, 0x990f, 0x4c0d, 0x990c, 0x4c08, 0x9908, - 0x4c03, 0x9904, 0x4bfe, 0x9900, 0x4bf9, 0x98fd, 0x4bf4, 0x98f9, - 0x4bef, 0x98f5, 0x4be9, 0x98f2, 0x4be4, 0x98ee, 0x4bdf, 0x98ea, - 0x4bda, 0x98e6, 0x4bd5, 0x98e3, 0x4bd0, 0x98df, 0x4bcb, 0x98db, - 0x4bc6, 0x98d7, 0x4bc1, 0x98d4, 0x4bbc, 0x98d0, 0x4bb7, 0x98cc, - 0x4bb2, 0x98c9, 0x4bad, 0x98c5, 0x4ba8, 0x98c1, 0x4ba3, 0x98bd, - 0x4b9e, 0x98ba, 0x4b98, 0x98b6, 0x4b93, 0x98b2, 0x4b8e, 0x98af, - 0x4b89, 0x98ab, 0x4b84, 0x98a7, 0x4b7f, 0x98a3, 0x4b7a, 0x98a0, - 0x4b75, 0x989c, 0x4b70, 0x9898, 0x4b6b, 0x9895, 0x4b66, 0x9891, - 0x4b61, 0x988d, 0x4b5c, 0x988a, 0x4b56, 0x9886, 0x4b51, 0x9882, - 0x4b4c, 0x987e, 0x4b47, 0x987b, 0x4b42, 0x9877, 0x4b3d, 0x9873, - 0x4b38, 0x9870, 0x4b33, 0x986c, 0x4b2e, 0x9868, 0x4b29, 0x9865, - 0x4b24, 0x9861, 0x4b1f, 0x985d, 0x4b19, 0x985a, 0x4b14, 0x9856, - 0x4b0f, 0x9852, 0x4b0a, 0x984e, 0x4b05, 0x984b, 0x4b00, 0x9847, - 0x4afb, 0x9843, 0x4af6, 0x9840, 0x4af1, 0x983c, 0x4aec, 0x9838, - 0x4ae7, 0x9835, 0x4ae1, 0x9831, 0x4adc, 0x982d, 0x4ad7, 0x982a, - 0x4ad2, 0x9826, 0x4acd, 0x9822, 0x4ac8, 0x981f, 0x4ac3, 0x981b, - 0x4abe, 0x9817, 0x4ab9, 0x9814, 0x4ab4, 0x9810, 0x4aae, 0x980c, - 0x4aa9, 0x9809, 0x4aa4, 0x9805, 0x4a9f, 0x9801, 0x4a9a, 0x97fe, - 0x4a95, 0x97fa, 0x4a90, 0x97f6, 0x4a8b, 0x97f3, 0x4a86, 0x97ef, - 0x4a81, 0x97eb, 0x4a7b, 0x97e8, 0x4a76, 0x97e4, 0x4a71, 0x97e0, - 0x4a6c, 0x97dd, 0x4a67, 0x97d9, 0x4a62, 0x97d5, 0x4a5d, 0x97d2, - 0x4a58, 0x97ce, 0x4a52, 0x97cb, 0x4a4d, 0x97c7, 0x4a48, 0x97c3, - 0x4a43, 0x97c0, 0x4a3e, 0x97bc, 0x4a39, 0x97b8, 0x4a34, 0x97b5, - 0x4a2f, 0x97b1, 0x4a2a, 0x97ad, 0x4a24, 0x97aa, 0x4a1f, 0x97a6, - 0x4a1a, 0x97a2, 0x4a15, 0x979f, 0x4a10, 0x979b, 0x4a0b, 0x9798, - 0x4a06, 0x9794, 0x4a01, 0x9790, 0x49fb, 0x978d, 0x49f6, 0x9789, - 0x49f1, 0x9785, 0x49ec, 0x9782, 0x49e7, 0x977e, 0x49e2, 0x977a, - 0x49dd, 0x9777, 0x49d8, 0x9773, 0x49d2, 0x9770, 0x49cd, 0x976c, - 0x49c8, 0x9768, 0x49c3, 0x9765, 0x49be, 0x9761, 0x49b9, 0x975d, - 0x49b4, 0x975a, 0x49ae, 0x9756, 0x49a9, 0x9753, 0x49a4, 0x974f, - 0x499f, 0x974b, 0x499a, 0x9748, 0x4995, 0x9744, 0x4990, 0x9741, - 0x498a, 0x973d, 0x4985, 0x9739, 0x4980, 0x9736, 0x497b, 0x9732, - 0x4976, 0x972f, 0x4971, 0x972b, 0x496c, 0x9727, 0x4966, 0x9724, - 0x4961, 0x9720, 0x495c, 0x971d, 0x4957, 0x9719, 0x4952, 0x9715, - 0x494d, 0x9712, 0x4948, 0x970e, 0x4942, 0x970b, 0x493d, 0x9707, - 0x4938, 0x9703, 0x4933, 0x9700, 0x492e, 0x96fc, 0x4929, 0x96f9, - 0x4923, 0x96f5, 0x491e, 0x96f1, 0x4919, 0x96ee, 0x4914, 0x96ea, - 0x490f, 0x96e7, 0x490a, 0x96e3, 0x4905, 0x96df, 0x48ff, 0x96dc, - 0x48fa, 0x96d8, 0x48f5, 0x96d5, 0x48f0, 0x96d1, 0x48eb, 0x96ce, - 0x48e6, 0x96ca, 0x48e0, 0x96c6, 0x48db, 0x96c3, 0x48d6, 0x96bf, - 0x48d1, 0x96bc, 0x48cc, 0x96b8, 0x48c7, 0x96b5, 0x48c1, 0x96b1, - 0x48bc, 0x96ad, 0x48b7, 0x96aa, 0x48b2, 0x96a6, 0x48ad, 0x96a3, - 0x48a8, 0x969f, 0x48a2, 0x969c, 0x489d, 0x9698, 0x4898, 0x9694, - 0x4893, 0x9691, 0x488e, 0x968d, 0x4888, 0x968a, 0x4883, 0x9686, - 0x487e, 0x9683, 0x4879, 0x967f, 0x4874, 0x967b, 0x486f, 0x9678, - 0x4869, 0x9674, 0x4864, 0x9671, 0x485f, 0x966d, 0x485a, 0x966a, - 0x4855, 0x9666, 0x484f, 0x9663, 0x484a, 0x965f, 0x4845, 0x965b, - 0x4840, 0x9658, 0x483b, 0x9654, 0x4836, 0x9651, 0x4830, 0x964d, - 0x482b, 0x964a, 0x4826, 0x9646, 0x4821, 0x9643, 0x481c, 0x963f, - 0x4816, 0x963c, 0x4811, 0x9638, 0x480c, 0x9635, 0x4807, 0x9631, - 0x4802, 0x962d, 0x47fc, 0x962a, 0x47f7, 0x9626, 0x47f2, 0x9623, - 0x47ed, 0x961f, 0x47e8, 0x961c, 0x47e2, 0x9618, 0x47dd, 0x9615, - 0x47d8, 0x9611, 0x47d3, 0x960e, 0x47ce, 0x960a, 0x47c8, 0x9607, - 0x47c3, 0x9603, 0x47be, 0x9600, 0x47b9, 0x95fc, 0x47b4, 0x95f9, - 0x47ae, 0x95f5, 0x47a9, 0x95f2, 0x47a4, 0x95ee, 0x479f, 0x95ea, - 0x479a, 0x95e7, 0x4794, 0x95e3, 0x478f, 0x95e0, 0x478a, 0x95dc, - 0x4785, 0x95d9, 0x4780, 0x95d5, 0x477a, 0x95d2, 0x4775, 0x95ce, - 0x4770, 0x95cb, 0x476b, 0x95c7, 0x4765, 0x95c4, 0x4760, 0x95c0, - 0x475b, 0x95bd, 0x4756, 0x95b9, 0x4751, 0x95b6, 0x474b, 0x95b2, - 0x4746, 0x95af, 0x4741, 0x95ab, 0x473c, 0x95a8, 0x4737, 0x95a4, - 0x4731, 0x95a1, 0x472c, 0x959d, 0x4727, 0x959a, 0x4722, 0x9596, - 0x471c, 0x9593, 0x4717, 0x958f, 0x4712, 0x958c, 0x470d, 0x9588, - 0x4708, 0x9585, 0x4702, 0x9581, 0x46fd, 0x957e, 0x46f8, 0x957a, - 0x46f3, 0x9577, 0x46ed, 0x9574, 0x46e8, 0x9570, 0x46e3, 0x956d, - 0x46de, 0x9569, 0x46d8, 0x9566, 0x46d3, 0x9562, 0x46ce, 0x955f, - 0x46c9, 0x955b, 0x46c4, 0x9558, 0x46be, 0x9554, 0x46b9, 0x9551, - 0x46b4, 0x954d, 0x46af, 0x954a, 0x46a9, 0x9546, 0x46a4, 0x9543, - 0x469f, 0x953f, 0x469a, 0x953c, 0x4694, 0x9538, 0x468f, 0x9535, - 0x468a, 0x9532, 0x4685, 0x952e, 0x467f, 0x952b, 0x467a, 0x9527, - 0x4675, 0x9524, 0x4670, 0x9520, 0x466a, 0x951d, 0x4665, 0x9519, - 0x4660, 0x9516, 0x465b, 0x9512, 0x4655, 0x950f, 0x4650, 0x950c, - 0x464b, 0x9508, 0x4646, 0x9505, 0x4640, 0x9501, 0x463b, 0x94fe, - 0x4636, 0x94fa, 0x4631, 0x94f7, 0x462b, 0x94f3, 0x4626, 0x94f0, - 0x4621, 0x94ed, 0x461c, 0x94e9, 0x4616, 0x94e6, 0x4611, 0x94e2, - 0x460c, 0x94df, 0x4607, 0x94db, 0x4601, 0x94d8, 0x45fc, 0x94d4, - 0x45f7, 0x94d1, 0x45f2, 0x94ce, 0x45ec, 0x94ca, 0x45e7, 0x94c7, - 0x45e2, 0x94c3, 0x45dd, 0x94c0, 0x45d7, 0x94bc, 0x45d2, 0x94b9, - 0x45cd, 0x94b6, 0x45c7, 0x94b2, 0x45c2, 0x94af, 0x45bd, 0x94ab, - 0x45b8, 0x94a8, 0x45b2, 0x94a4, 0x45ad, 0x94a1, 0x45a8, 0x949e, - 0x45a3, 0x949a, 0x459d, 0x9497, 0x4598, 0x9493, 0x4593, 0x9490, - 0x458d, 0x948d, 0x4588, 0x9489, 0x4583, 0x9486, 0x457e, 0x9482, - 0x4578, 0x947f, 0x4573, 0x947b, 0x456e, 0x9478, 0x4569, 0x9475, - 0x4563, 0x9471, 0x455e, 0x946e, 0x4559, 0x946a, 0x4553, 0x9467, - 0x454e, 0x9464, 0x4549, 0x9460, 0x4544, 0x945d, 0x453e, 0x9459, - 0x4539, 0x9456, 0x4534, 0x9453, 0x452e, 0x944f, 0x4529, 0x944c, - 0x4524, 0x9448, 0x451f, 0x9445, 0x4519, 0x9442, 0x4514, 0x943e, - 0x450f, 0x943b, 0x4509, 0x9437, 0x4504, 0x9434, 0x44ff, 0x9431, - 0x44fa, 0x942d, 0x44f4, 0x942a, 0x44ef, 0x9427, 0x44ea, 0x9423, - 0x44e4, 0x9420, 0x44df, 0x941c, 0x44da, 0x9419, 0x44d4, 0x9416, - 0x44cf, 0x9412, 0x44ca, 0x940f, 0x44c5, 0x940b, 0x44bf, 0x9408, - 0x44ba, 0x9405, 0x44b5, 0x9401, 0x44af, 0x93fe, 0x44aa, 0x93fb, - 0x44a5, 0x93f7, 0x449f, 0x93f4, 0x449a, 0x93f1, 0x4495, 0x93ed, - 0x4490, 0x93ea, 0x448a, 0x93e6, 0x4485, 0x93e3, 0x4480, 0x93e0, - 0x447a, 0x93dc, 0x4475, 0x93d9, 0x4470, 0x93d6, 0x446a, 0x93d2, - 0x4465, 0x93cf, 0x4460, 0x93cc, 0x445a, 0x93c8, 0x4455, 0x93c5, - 0x4450, 0x93c1, 0x444b, 0x93be, 0x4445, 0x93bb, 0x4440, 0x93b7, - 0x443b, 0x93b4, 0x4435, 0x93b1, 0x4430, 0x93ad, 0x442b, 0x93aa, - 0x4425, 0x93a7, 0x4420, 0x93a3, 0x441b, 0x93a0, 0x4415, 0x939d, - 0x4410, 0x9399, 0x440b, 0x9396, 0x4405, 0x9393, 0x4400, 0x938f, - 0x43fb, 0x938c, 0x43f5, 0x9389, 0x43f0, 0x9385, 0x43eb, 0x9382, - 0x43e5, 0x937f, 0x43e0, 0x937b, 0x43db, 0x9378, 0x43d5, 0x9375, - 0x43d0, 0x9371, 0x43cb, 0x936e, 0x43c5, 0x936b, 0x43c0, 0x9367, - 0x43bb, 0x9364, 0x43b5, 0x9361, 0x43b0, 0x935d, 0x43ab, 0x935a, - 0x43a5, 0x9357, 0x43a0, 0x9353, 0x439b, 0x9350, 0x4395, 0x934d, - 0x4390, 0x9349, 0x438b, 0x9346, 0x4385, 0x9343, 0x4380, 0x933f, - 0x437b, 0x933c, 0x4375, 0x9339, 0x4370, 0x9336, 0x436b, 0x9332, - 0x4365, 0x932f, 0x4360, 0x932c, 0x435b, 0x9328, 0x4355, 0x9325, - 0x4350, 0x9322, 0x434b, 0x931e, 0x4345, 0x931b, 0x4340, 0x9318, - 0x433b, 0x9314, 0x4335, 0x9311, 0x4330, 0x930e, 0x432b, 0x930b, - 0x4325, 0x9307, 0x4320, 0x9304, 0x431b, 0x9301, 0x4315, 0x92fd, - 0x4310, 0x92fa, 0x430b, 0x92f7, 0x4305, 0x92f4, 0x4300, 0x92f0, - 0x42fa, 0x92ed, 0x42f5, 0x92ea, 0x42f0, 0x92e6, 0x42ea, 0x92e3, - 0x42e5, 0x92e0, 0x42e0, 0x92dd, 0x42da, 0x92d9, 0x42d5, 0x92d6, - 0x42d0, 0x92d3, 0x42ca, 0x92cf, 0x42c5, 0x92cc, 0x42c0, 0x92c9, - 0x42ba, 0x92c6, 0x42b5, 0x92c2, 0x42af, 0x92bf, 0x42aa, 0x92bc, - 0x42a5, 0x92b8, 0x429f, 0x92b5, 0x429a, 0x92b2, 0x4295, 0x92af, - 0x428f, 0x92ab, 0x428a, 0x92a8, 0x4284, 0x92a5, 0x427f, 0x92a2, - 0x427a, 0x929e, 0x4274, 0x929b, 0x426f, 0x9298, 0x426a, 0x9295, - 0x4264, 0x9291, 0x425f, 0x928e, 0x425a, 0x928b, 0x4254, 0x9288, - 0x424f, 0x9284, 0x4249, 0x9281, 0x4244, 0x927e, 0x423f, 0x927b, - 0x4239, 0x9277, 0x4234, 0x9274, 0x422f, 0x9271, 0x4229, 0x926e, - 0x4224, 0x926a, 0x421e, 0x9267, 0x4219, 0x9264, 0x4214, 0x9261, - 0x420e, 0x925d, 0x4209, 0x925a, 0x4203, 0x9257, 0x41fe, 0x9254, - 0x41f9, 0x9250, 0x41f3, 0x924d, 0x41ee, 0x924a, 0x41e9, 0x9247, - 0x41e3, 0x9243, 0x41de, 0x9240, 0x41d8, 0x923d, 0x41d3, 0x923a, - 0x41ce, 0x9236, 0x41c8, 0x9233, 0x41c3, 0x9230, 0x41bd, 0x922d, - 0x41b8, 0x922a, 0x41b3, 0x9226, 0x41ad, 0x9223, 0x41a8, 0x9220, - 0x41a2, 0x921d, 0x419d, 0x9219, 0x4198, 0x9216, 0x4192, 0x9213, - 0x418d, 0x9210, 0x4188, 0x920d, 0x4182, 0x9209, 0x417d, 0x9206, - 0x4177, 0x9203, 0x4172, 0x9200, 0x416d, 0x91fc, 0x4167, 0x91f9, - 0x4162, 0x91f6, 0x415c, 0x91f3, 0x4157, 0x91f0, 0x4152, 0x91ec, - 0x414c, 0x91e9, 0x4147, 0x91e6, 0x4141, 0x91e3, 0x413c, 0x91e0, - 0x4136, 0x91dc, 0x4131, 0x91d9, 0x412c, 0x91d6, 0x4126, 0x91d3, - 0x4121, 0x91d0, 0x411b, 0x91cc, 0x4116, 0x91c9, 0x4111, 0x91c6, - 0x410b, 0x91c3, 0x4106, 0x91c0, 0x4100, 0x91bc, 0x40fb, 0x91b9, - 0x40f6, 0x91b6, 0x40f0, 0x91b3, 0x40eb, 0x91b0, 0x40e5, 0x91ad, - 0x40e0, 0x91a9, 0x40da, 0x91a6, 0x40d5, 0x91a3, 0x40d0, 0x91a0, - 0x40ca, 0x919d, 0x40c5, 0x9199, 0x40bf, 0x9196, 0x40ba, 0x9193, - 0x40b5, 0x9190, 0x40af, 0x918d, 0x40aa, 0x918a, 0x40a4, 0x9186, - 0x409f, 0x9183, 0x4099, 0x9180, 0x4094, 0x917d, 0x408f, 0x917a, - 0x4089, 0x9177, 0x4084, 0x9173, 0x407e, 0x9170, 0x4079, 0x916d, - 0x4073, 0x916a, 0x406e, 0x9167, 0x4069, 0x9164, 0x4063, 0x9160, - 0x405e, 0x915d, 0x4058, 0x915a, 0x4053, 0x9157, 0x404d, 0x9154, - 0x4048, 0x9151, 0x4043, 0x914d, 0x403d, 0x914a, 0x4038, 0x9147, - 0x4032, 0x9144, 0x402d, 0x9141, 0x4027, 0x913e, 0x4022, 0x913a, - 0x401d, 0x9137, 0x4017, 0x9134, 0x4012, 0x9131, 0x400c, 0x912e, - 0x4007, 0x912b, 0x4001, 0x9128, 0x3ffc, 0x9124, 0x3ff6, 0x9121, - 0x3ff1, 0x911e, 0x3fec, 0x911b, 0x3fe6, 0x9118, 0x3fe1, 0x9115, - 0x3fdb, 0x9112, 0x3fd6, 0x910f, 0x3fd0, 0x910b, 0x3fcb, 0x9108, - 0x3fc5, 0x9105, 0x3fc0, 0x9102, 0x3fbb, 0x90ff, 0x3fb5, 0x90fc, - 0x3fb0, 0x90f9, 0x3faa, 0x90f5, 0x3fa5, 0x90f2, 0x3f9f, 0x90ef, - 0x3f9a, 0x90ec, 0x3f94, 0x90e9, 0x3f8f, 0x90e6, 0x3f89, 0x90e3, - 0x3f84, 0x90e0, 0x3f7f, 0x90dd, 0x3f79, 0x90d9, 0x3f74, 0x90d6, - 0x3f6e, 0x90d3, 0x3f69, 0x90d0, 0x3f63, 0x90cd, 0x3f5e, 0x90ca, - 0x3f58, 0x90c7, 0x3f53, 0x90c4, 0x3f4d, 0x90c1, 0x3f48, 0x90bd, - 0x3f43, 0x90ba, 0x3f3d, 0x90b7, 0x3f38, 0x90b4, 0x3f32, 0x90b1, - 0x3f2d, 0x90ae, 0x3f27, 0x90ab, 0x3f22, 0x90a8, 0x3f1c, 0x90a5, - 0x3f17, 0x90a1, 0x3f11, 0x909e, 0x3f0c, 0x909b, 0x3f06, 0x9098, - 0x3f01, 0x9095, 0x3efb, 0x9092, 0x3ef6, 0x908f, 0x3ef1, 0x908c, - 0x3eeb, 0x9089, 0x3ee6, 0x9086, 0x3ee0, 0x9083, 0x3edb, 0x907f, - 0x3ed5, 0x907c, 0x3ed0, 0x9079, 0x3eca, 0x9076, 0x3ec5, 0x9073, - 0x3ebf, 0x9070, 0x3eba, 0x906d, 0x3eb4, 0x906a, 0x3eaf, 0x9067, - 0x3ea9, 0x9064, 0x3ea4, 0x9061, 0x3e9e, 0x905e, 0x3e99, 0x905b, - 0x3e93, 0x9057, 0x3e8e, 0x9054, 0x3e88, 0x9051, 0x3e83, 0x904e, - 0x3e7d, 0x904b, 0x3e78, 0x9048, 0x3e73, 0x9045, 0x3e6d, 0x9042, - 0x3e68, 0x903f, 0x3e62, 0x903c, 0x3e5d, 0x9039, 0x3e57, 0x9036, - 0x3e52, 0x9033, 0x3e4c, 0x9030, 0x3e47, 0x902d, 0x3e41, 0x902a, - 0x3e3c, 0x9026, 0x3e36, 0x9023, 0x3e31, 0x9020, 0x3e2b, 0x901d, - 0x3e26, 0x901a, 0x3e20, 0x9017, 0x3e1b, 0x9014, 0x3e15, 0x9011, - 0x3e10, 0x900e, 0x3e0a, 0x900b, 0x3e05, 0x9008, 0x3dff, 0x9005, - 0x3dfa, 0x9002, 0x3df4, 0x8fff, 0x3def, 0x8ffc, 0x3de9, 0x8ff9, - 0x3de4, 0x8ff6, 0x3dde, 0x8ff3, 0x3dd9, 0x8ff0, 0x3dd3, 0x8fed, - 0x3dce, 0x8fea, 0x3dc8, 0x8fe7, 0x3dc3, 0x8fe3, 0x3dbd, 0x8fe0, - 0x3db8, 0x8fdd, 0x3db2, 0x8fda, 0x3dad, 0x8fd7, 0x3da7, 0x8fd4, - 0x3da2, 0x8fd1, 0x3d9c, 0x8fce, 0x3d97, 0x8fcb, 0x3d91, 0x8fc8, - 0x3d8c, 0x8fc5, 0x3d86, 0x8fc2, 0x3d81, 0x8fbf, 0x3d7b, 0x8fbc, - 0x3d76, 0x8fb9, 0x3d70, 0x8fb6, 0x3d6b, 0x8fb3, 0x3d65, 0x8fb0, - 0x3d60, 0x8fad, 0x3d5a, 0x8faa, 0x3d55, 0x8fa7, 0x3d4f, 0x8fa4, - 0x3d49, 0x8fa1, 0x3d44, 0x8f9e, 0x3d3e, 0x8f9b, 0x3d39, 0x8f98, - 0x3d33, 0x8f95, 0x3d2e, 0x8f92, 0x3d28, 0x8f8f, 0x3d23, 0x8f8c, - 0x3d1d, 0x8f89, 0x3d18, 0x8f86, 0x3d12, 0x8f83, 0x3d0d, 0x8f80, - 0x3d07, 0x8f7d, 0x3d02, 0x8f7a, 0x3cfc, 0x8f77, 0x3cf7, 0x8f74, - 0x3cf1, 0x8f71, 0x3cec, 0x8f6e, 0x3ce6, 0x8f6b, 0x3ce1, 0x8f68, - 0x3cdb, 0x8f65, 0x3cd6, 0x8f62, 0x3cd0, 0x8f5f, 0x3cca, 0x8f5c, - 0x3cc5, 0x8f59, 0x3cbf, 0x8f56, 0x3cba, 0x8f53, 0x3cb4, 0x8f50, - 0x3caf, 0x8f4d, 0x3ca9, 0x8f4a, 0x3ca4, 0x8f47, 0x3c9e, 0x8f44, - 0x3c99, 0x8f41, 0x3c93, 0x8f3e, 0x3c8e, 0x8f3b, 0x3c88, 0x8f38, - 0x3c83, 0x8f35, 0x3c7d, 0x8f32, 0x3c77, 0x8f2f, 0x3c72, 0x8f2d, - 0x3c6c, 0x8f2a, 0x3c67, 0x8f27, 0x3c61, 0x8f24, 0x3c5c, 0x8f21, - 0x3c56, 0x8f1e, 0x3c51, 0x8f1b, 0x3c4b, 0x8f18, 0x3c46, 0x8f15, - 0x3c40, 0x8f12, 0x3c3b, 0x8f0f, 0x3c35, 0x8f0c, 0x3c2f, 0x8f09, - 0x3c2a, 0x8f06, 0x3c24, 0x8f03, 0x3c1f, 0x8f00, 0x3c19, 0x8efd, - 0x3c14, 0x8efa, 0x3c0e, 0x8ef7, 0x3c09, 0x8ef4, 0x3c03, 0x8ef1, - 0x3bfd, 0x8eee, 0x3bf8, 0x8eec, 0x3bf2, 0x8ee9, 0x3bed, 0x8ee6, - 0x3be7, 0x8ee3, 0x3be2, 0x8ee0, 0x3bdc, 0x8edd, 0x3bd7, 0x8eda, - 0x3bd1, 0x8ed7, 0x3bcc, 0x8ed4, 0x3bc6, 0x8ed1, 0x3bc0, 0x8ece, - 0x3bbb, 0x8ecb, 0x3bb5, 0x8ec8, 0x3bb0, 0x8ec5, 0x3baa, 0x8ec2, - 0x3ba5, 0x8ebf, 0x3b9f, 0x8ebd, 0x3b99, 0x8eba, 0x3b94, 0x8eb7, - 0x3b8e, 0x8eb4, 0x3b89, 0x8eb1, 0x3b83, 0x8eae, 0x3b7e, 0x8eab, - 0x3b78, 0x8ea8, 0x3b73, 0x8ea5, 0x3b6d, 0x8ea2, 0x3b67, 0x8e9f, - 0x3b62, 0x8e9c, 0x3b5c, 0x8e99, 0x3b57, 0x8e97, 0x3b51, 0x8e94, - 0x3b4c, 0x8e91, 0x3b46, 0x8e8e, 0x3b40, 0x8e8b, 0x3b3b, 0x8e88, - 0x3b35, 0x8e85, 0x3b30, 0x8e82, 0x3b2a, 0x8e7f, 0x3b25, 0x8e7c, - 0x3b1f, 0x8e7a, 0x3b19, 0x8e77, 0x3b14, 0x8e74, 0x3b0e, 0x8e71, - 0x3b09, 0x8e6e, 0x3b03, 0x8e6b, 0x3afe, 0x8e68, 0x3af8, 0x8e65, - 0x3af2, 0x8e62, 0x3aed, 0x8e5f, 0x3ae7, 0x8e5d, 0x3ae2, 0x8e5a, - 0x3adc, 0x8e57, 0x3ad7, 0x8e54, 0x3ad1, 0x8e51, 0x3acb, 0x8e4e, - 0x3ac6, 0x8e4b, 0x3ac0, 0x8e48, 0x3abb, 0x8e45, 0x3ab5, 0x8e43, - 0x3aaf, 0x8e40, 0x3aaa, 0x8e3d, 0x3aa4, 0x8e3a, 0x3a9f, 0x8e37, - 0x3a99, 0x8e34, 0x3a94, 0x8e31, 0x3a8e, 0x8e2e, 0x3a88, 0x8e2c, - 0x3a83, 0x8e29, 0x3a7d, 0x8e26, 0x3a78, 0x8e23, 0x3a72, 0x8e20, - 0x3a6c, 0x8e1d, 0x3a67, 0x8e1a, 0x3a61, 0x8e17, 0x3a5c, 0x8e15, - 0x3a56, 0x8e12, 0x3a50, 0x8e0f, 0x3a4b, 0x8e0c, 0x3a45, 0x8e09, - 0x3a40, 0x8e06, 0x3a3a, 0x8e03, 0x3a34, 0x8e01, 0x3a2f, 0x8dfe, - 0x3a29, 0x8dfb, 0x3a24, 0x8df8, 0x3a1e, 0x8df5, 0x3a19, 0x8df2, - 0x3a13, 0x8def, 0x3a0d, 0x8ded, 0x3a08, 0x8dea, 0x3a02, 0x8de7, - 0x39fd, 0x8de4, 0x39f7, 0x8de1, 0x39f1, 0x8dde, 0x39ec, 0x8ddc, - 0x39e6, 0x8dd9, 0x39e0, 0x8dd6, 0x39db, 0x8dd3, 0x39d5, 0x8dd0, - 0x39d0, 0x8dcd, 0x39ca, 0x8dca, 0x39c4, 0x8dc8, 0x39bf, 0x8dc5, - 0x39b9, 0x8dc2, 0x39b4, 0x8dbf, 0x39ae, 0x8dbc, 0x39a8, 0x8db9, - 0x39a3, 0x8db7, 0x399d, 0x8db4, 0x3998, 0x8db1, 0x3992, 0x8dae, - 0x398c, 0x8dab, 0x3987, 0x8da9, 0x3981, 0x8da6, 0x397c, 0x8da3, - 0x3976, 0x8da0, 0x3970, 0x8d9d, 0x396b, 0x8d9a, 0x3965, 0x8d98, - 0x395f, 0x8d95, 0x395a, 0x8d92, 0x3954, 0x8d8f, 0x394f, 0x8d8c, - 0x3949, 0x8d8a, 0x3943, 0x8d87, 0x393e, 0x8d84, 0x3938, 0x8d81, - 0x3932, 0x8d7e, 0x392d, 0x8d7b, 0x3927, 0x8d79, 0x3922, 0x8d76, - 0x391c, 0x8d73, 0x3916, 0x8d70, 0x3911, 0x8d6d, 0x390b, 0x8d6b, - 0x3906, 0x8d68, 0x3900, 0x8d65, 0x38fa, 0x8d62, 0x38f5, 0x8d5f, - 0x38ef, 0x8d5d, 0x38e9, 0x8d5a, 0x38e4, 0x8d57, 0x38de, 0x8d54, - 0x38d8, 0x8d51, 0x38d3, 0x8d4f, 0x38cd, 0x8d4c, 0x38c8, 0x8d49, - 0x38c2, 0x8d46, 0x38bc, 0x8d44, 0x38b7, 0x8d41, 0x38b1, 0x8d3e, - 0x38ab, 0x8d3b, 0x38a6, 0x8d38, 0x38a0, 0x8d36, 0x389b, 0x8d33, - 0x3895, 0x8d30, 0x388f, 0x8d2d, 0x388a, 0x8d2b, 0x3884, 0x8d28, - 0x387e, 0x8d25, 0x3879, 0x8d22, 0x3873, 0x8d1f, 0x386d, 0x8d1d, - 0x3868, 0x8d1a, 0x3862, 0x8d17, 0x385d, 0x8d14, 0x3857, 0x8d12, - 0x3851, 0x8d0f, 0x384c, 0x8d0c, 0x3846, 0x8d09, 0x3840, 0x8d07, - 0x383b, 0x8d04, 0x3835, 0x8d01, 0x382f, 0x8cfe, 0x382a, 0x8cfb, - 0x3824, 0x8cf9, 0x381e, 0x8cf6, 0x3819, 0x8cf3, 0x3813, 0x8cf0, - 0x380d, 0x8cee, 0x3808, 0x8ceb, 0x3802, 0x8ce8, 0x37fd, 0x8ce5, - 0x37f7, 0x8ce3, 0x37f1, 0x8ce0, 0x37ec, 0x8cdd, 0x37e6, 0x8cda, - 0x37e0, 0x8cd8, 0x37db, 0x8cd5, 0x37d5, 0x8cd2, 0x37cf, 0x8cd0, - 0x37ca, 0x8ccd, 0x37c4, 0x8cca, 0x37be, 0x8cc7, 0x37b9, 0x8cc5, - 0x37b3, 0x8cc2, 0x37ad, 0x8cbf, 0x37a8, 0x8cbc, 0x37a2, 0x8cba, - 0x379c, 0x8cb7, 0x3797, 0x8cb4, 0x3791, 0x8cb1, 0x378b, 0x8caf, - 0x3786, 0x8cac, 0x3780, 0x8ca9, 0x377a, 0x8ca7, 0x3775, 0x8ca4, - 0x376f, 0x8ca1, 0x3769, 0x8c9e, 0x3764, 0x8c9c, 0x375e, 0x8c99, - 0x3758, 0x8c96, 0x3753, 0x8c94, 0x374d, 0x8c91, 0x3747, 0x8c8e, - 0x3742, 0x8c8b, 0x373c, 0x8c89, 0x3736, 0x8c86, 0x3731, 0x8c83, - 0x372b, 0x8c81, 0x3725, 0x8c7e, 0x3720, 0x8c7b, 0x371a, 0x8c78, - 0x3714, 0x8c76, 0x370f, 0x8c73, 0x3709, 0x8c70, 0x3703, 0x8c6e, - 0x36fe, 0x8c6b, 0x36f8, 0x8c68, 0x36f2, 0x8c65, 0x36ed, 0x8c63, - 0x36e7, 0x8c60, 0x36e1, 0x8c5d, 0x36dc, 0x8c5b, 0x36d6, 0x8c58, - 0x36d0, 0x8c55, 0x36cb, 0x8c53, 0x36c5, 0x8c50, 0x36bf, 0x8c4d, - 0x36ba, 0x8c4b, 0x36b4, 0x8c48, 0x36ae, 0x8c45, 0x36a9, 0x8c43, - 0x36a3, 0x8c40, 0x369d, 0x8c3d, 0x3698, 0x8c3a, 0x3692, 0x8c38, - 0x368c, 0x8c35, 0x3686, 0x8c32, 0x3681, 0x8c30, 0x367b, 0x8c2d, - 0x3675, 0x8c2a, 0x3670, 0x8c28, 0x366a, 0x8c25, 0x3664, 0x8c22, - 0x365f, 0x8c20, 0x3659, 0x8c1d, 0x3653, 0x8c1a, 0x364e, 0x8c18, - 0x3648, 0x8c15, 0x3642, 0x8c12, 0x363d, 0x8c10, 0x3637, 0x8c0d, - 0x3631, 0x8c0a, 0x362b, 0x8c08, 0x3626, 0x8c05, 0x3620, 0x8c02, - 0x361a, 0x8c00, 0x3615, 0x8bfd, 0x360f, 0x8bfa, 0x3609, 0x8bf8, - 0x3604, 0x8bf5, 0x35fe, 0x8bf3, 0x35f8, 0x8bf0, 0x35f3, 0x8bed, - 0x35ed, 0x8beb, 0x35e7, 0x8be8, 0x35e1, 0x8be5, 0x35dc, 0x8be3, - 0x35d6, 0x8be0, 0x35d0, 0x8bdd, 0x35cb, 0x8bdb, 0x35c5, 0x8bd8, - 0x35bf, 0x8bd5, 0x35ba, 0x8bd3, 0x35b4, 0x8bd0, 0x35ae, 0x8bce, - 0x35a8, 0x8bcb, 0x35a3, 0x8bc8, 0x359d, 0x8bc6, 0x3597, 0x8bc3, - 0x3592, 0x8bc0, 0x358c, 0x8bbe, 0x3586, 0x8bbb, 0x3580, 0x8bb8, - 0x357b, 0x8bb6, 0x3575, 0x8bb3, 0x356f, 0x8bb1, 0x356a, 0x8bae, - 0x3564, 0x8bab, 0x355e, 0x8ba9, 0x3558, 0x8ba6, 0x3553, 0x8ba4, - 0x354d, 0x8ba1, 0x3547, 0x8b9e, 0x3542, 0x8b9c, 0x353c, 0x8b99, - 0x3536, 0x8b96, 0x3530, 0x8b94, 0x352b, 0x8b91, 0x3525, 0x8b8f, - 0x351f, 0x8b8c, 0x351a, 0x8b89, 0x3514, 0x8b87, 0x350e, 0x8b84, - 0x3508, 0x8b82, 0x3503, 0x8b7f, 0x34fd, 0x8b7c, 0x34f7, 0x8b7a, - 0x34f2, 0x8b77, 0x34ec, 0x8b75, 0x34e6, 0x8b72, 0x34e0, 0x8b6f, - 0x34db, 0x8b6d, 0x34d5, 0x8b6a, 0x34cf, 0x8b68, 0x34ca, 0x8b65, - 0x34c4, 0x8b62, 0x34be, 0x8b60, 0x34b8, 0x8b5d, 0x34b3, 0x8b5b, - 0x34ad, 0x8b58, 0x34a7, 0x8b55, 0x34a1, 0x8b53, 0x349c, 0x8b50, - 0x3496, 0x8b4e, 0x3490, 0x8b4b, 0x348b, 0x8b49, 0x3485, 0x8b46, - 0x347f, 0x8b43, 0x3479, 0x8b41, 0x3474, 0x8b3e, 0x346e, 0x8b3c, - 0x3468, 0x8b39, 0x3462, 0x8b37, 0x345d, 0x8b34, 0x3457, 0x8b31, - 0x3451, 0x8b2f, 0x344b, 0x8b2c, 0x3446, 0x8b2a, 0x3440, 0x8b27, - 0x343a, 0x8b25, 0x3435, 0x8b22, 0x342f, 0x8b1f, 0x3429, 0x8b1d, - 0x3423, 0x8b1a, 0x341e, 0x8b18, 0x3418, 0x8b15, 0x3412, 0x8b13, - 0x340c, 0x8b10, 0x3407, 0x8b0e, 0x3401, 0x8b0b, 0x33fb, 0x8b08, - 0x33f5, 0x8b06, 0x33f0, 0x8b03, 0x33ea, 0x8b01, 0x33e4, 0x8afe, - 0x33de, 0x8afc, 0x33d9, 0x8af9, 0x33d3, 0x8af7, 0x33cd, 0x8af4, - 0x33c7, 0x8af1, 0x33c2, 0x8aef, 0x33bc, 0x8aec, 0x33b6, 0x8aea, - 0x33b0, 0x8ae7, 0x33ab, 0x8ae5, 0x33a5, 0x8ae2, 0x339f, 0x8ae0, - 0x3399, 0x8add, 0x3394, 0x8adb, 0x338e, 0x8ad8, 0x3388, 0x8ad6, - 0x3382, 0x8ad3, 0x337d, 0x8ad1, 0x3377, 0x8ace, 0x3371, 0x8acb, - 0x336b, 0x8ac9, 0x3366, 0x8ac6, 0x3360, 0x8ac4, 0x335a, 0x8ac1, - 0x3354, 0x8abf, 0x334f, 0x8abc, 0x3349, 0x8aba, 0x3343, 0x8ab7, - 0x333d, 0x8ab5, 0x3338, 0x8ab2, 0x3332, 0x8ab0, 0x332c, 0x8aad, - 0x3326, 0x8aab, 0x3321, 0x8aa8, 0x331b, 0x8aa6, 0x3315, 0x8aa3, - 0x330f, 0x8aa1, 0x330a, 0x8a9e, 0x3304, 0x8a9c, 0x32fe, 0x8a99, - 0x32f8, 0x8a97, 0x32f3, 0x8a94, 0x32ed, 0x8a92, 0x32e7, 0x8a8f, - 0x32e1, 0x8a8d, 0x32db, 0x8a8a, 0x32d6, 0x8a88, 0x32d0, 0x8a85, - 0x32ca, 0x8a83, 0x32c4, 0x8a80, 0x32bf, 0x8a7e, 0x32b9, 0x8a7b, - 0x32b3, 0x8a79, 0x32ad, 0x8a76, 0x32a8, 0x8a74, 0x32a2, 0x8a71, - 0x329c, 0x8a6f, 0x3296, 0x8a6c, 0x3290, 0x8a6a, 0x328b, 0x8a67, - 0x3285, 0x8a65, 0x327f, 0x8a62, 0x3279, 0x8a60, 0x3274, 0x8a5d, - 0x326e, 0x8a5b, 0x3268, 0x8a59, 0x3262, 0x8a56, 0x325d, 0x8a54, - 0x3257, 0x8a51, 0x3251, 0x8a4f, 0x324b, 0x8a4c, 0x3245, 0x8a4a, - 0x3240, 0x8a47, 0x323a, 0x8a45, 0x3234, 0x8a42, 0x322e, 0x8a40, - 0x3228, 0x8a3d, 0x3223, 0x8a3b, 0x321d, 0x8a38, 0x3217, 0x8a36, - 0x3211, 0x8a34, 0x320c, 0x8a31, 0x3206, 0x8a2f, 0x3200, 0x8a2c, - 0x31fa, 0x8a2a, 0x31f4, 0x8a27, 0x31ef, 0x8a25, 0x31e9, 0x8a22, - 0x31e3, 0x8a20, 0x31dd, 0x8a1d, 0x31d8, 0x8a1b, 0x31d2, 0x8a19, - 0x31cc, 0x8a16, 0x31c6, 0x8a14, 0x31c0, 0x8a11, 0x31bb, 0x8a0f, - 0x31b5, 0x8a0c, 0x31af, 0x8a0a, 0x31a9, 0x8a07, 0x31a3, 0x8a05, - 0x319e, 0x8a03, 0x3198, 0x8a00, 0x3192, 0x89fe, 0x318c, 0x89fb, - 0x3186, 0x89f9, 0x3181, 0x89f6, 0x317b, 0x89f4, 0x3175, 0x89f2, - 0x316f, 0x89ef, 0x3169, 0x89ed, 0x3164, 0x89ea, 0x315e, 0x89e8, - 0x3158, 0x89e5, 0x3152, 0x89e3, 0x314c, 0x89e1, 0x3147, 0x89de, - 0x3141, 0x89dc, 0x313b, 0x89d9, 0x3135, 0x89d7, 0x312f, 0x89d5, - 0x312a, 0x89d2, 0x3124, 0x89d0, 0x311e, 0x89cd, 0x3118, 0x89cb, - 0x3112, 0x89c8, 0x310d, 0x89c6, 0x3107, 0x89c4, 0x3101, 0x89c1, - 0x30fb, 0x89bf, 0x30f5, 0x89bc, 0x30f0, 0x89ba, 0x30ea, 0x89b8, - 0x30e4, 0x89b5, 0x30de, 0x89b3, 0x30d8, 0x89b0, 0x30d3, 0x89ae, - 0x30cd, 0x89ac, 0x30c7, 0x89a9, 0x30c1, 0x89a7, 0x30bb, 0x89a4, - 0x30b6, 0x89a2, 0x30b0, 0x89a0, 0x30aa, 0x899d, 0x30a4, 0x899b, - 0x309e, 0x8998, 0x3099, 0x8996, 0x3093, 0x8994, 0x308d, 0x8991, - 0x3087, 0x898f, 0x3081, 0x898d, 0x307b, 0x898a, 0x3076, 0x8988, - 0x3070, 0x8985, 0x306a, 0x8983, 0x3064, 0x8981, 0x305e, 0x897e, - 0x3059, 0x897c, 0x3053, 0x897a, 0x304d, 0x8977, 0x3047, 0x8975, - 0x3041, 0x8972, 0x303b, 0x8970, 0x3036, 0x896e, 0x3030, 0x896b, - 0x302a, 0x8969, 0x3024, 0x8967, 0x301e, 0x8964, 0x3019, 0x8962, - 0x3013, 0x8960, 0x300d, 0x895d, 0x3007, 0x895b, 0x3001, 0x8958, - 0x2ffb, 0x8956, 0x2ff6, 0x8954, 0x2ff0, 0x8951, 0x2fea, 0x894f, - 0x2fe4, 0x894d, 0x2fde, 0x894a, 0x2fd8, 0x8948, 0x2fd3, 0x8946, - 0x2fcd, 0x8943, 0x2fc7, 0x8941, 0x2fc1, 0x893f, 0x2fbb, 0x893c, - 0x2fb5, 0x893a, 0x2fb0, 0x8938, 0x2faa, 0x8935, 0x2fa4, 0x8933, - 0x2f9e, 0x8931, 0x2f98, 0x892e, 0x2f92, 0x892c, 0x2f8d, 0x892a, - 0x2f87, 0x8927, 0x2f81, 0x8925, 0x2f7b, 0x8923, 0x2f75, 0x8920, - 0x2f6f, 0x891e, 0x2f6a, 0x891c, 0x2f64, 0x8919, 0x2f5e, 0x8917, - 0x2f58, 0x8915, 0x2f52, 0x8912, 0x2f4c, 0x8910, 0x2f47, 0x890e, - 0x2f41, 0x890b, 0x2f3b, 0x8909, 0x2f35, 0x8907, 0x2f2f, 0x8904, - 0x2f29, 0x8902, 0x2f24, 0x8900, 0x2f1e, 0x88fd, 0x2f18, 0x88fb, - 0x2f12, 0x88f9, 0x2f0c, 0x88f6, 0x2f06, 0x88f4, 0x2f01, 0x88f2, - 0x2efb, 0x88f0, 0x2ef5, 0x88ed, 0x2eef, 0x88eb, 0x2ee9, 0x88e9, - 0x2ee3, 0x88e6, 0x2edd, 0x88e4, 0x2ed8, 0x88e2, 0x2ed2, 0x88df, - 0x2ecc, 0x88dd, 0x2ec6, 0x88db, 0x2ec0, 0x88d9, 0x2eba, 0x88d6, - 0x2eb5, 0x88d4, 0x2eaf, 0x88d2, 0x2ea9, 0x88cf, 0x2ea3, 0x88cd, - 0x2e9d, 0x88cb, 0x2e97, 0x88c8, 0x2e91, 0x88c6, 0x2e8c, 0x88c4, - 0x2e86, 0x88c2, 0x2e80, 0x88bf, 0x2e7a, 0x88bd, 0x2e74, 0x88bb, - 0x2e6e, 0x88b9, 0x2e68, 0x88b6, 0x2e63, 0x88b4, 0x2e5d, 0x88b2, - 0x2e57, 0x88af, 0x2e51, 0x88ad, 0x2e4b, 0x88ab, 0x2e45, 0x88a9, - 0x2e3f, 0x88a6, 0x2e3a, 0x88a4, 0x2e34, 0x88a2, 0x2e2e, 0x88a0, - 0x2e28, 0x889d, 0x2e22, 0x889b, 0x2e1c, 0x8899, 0x2e16, 0x8896, - 0x2e11, 0x8894, 0x2e0b, 0x8892, 0x2e05, 0x8890, 0x2dff, 0x888d, - 0x2df9, 0x888b, 0x2df3, 0x8889, 0x2ded, 0x8887, 0x2de7, 0x8884, - 0x2de2, 0x8882, 0x2ddc, 0x8880, 0x2dd6, 0x887e, 0x2dd0, 0x887b, - 0x2dca, 0x8879, 0x2dc4, 0x8877, 0x2dbe, 0x8875, 0x2db9, 0x8872, - 0x2db3, 0x8870, 0x2dad, 0x886e, 0x2da7, 0x886c, 0x2da1, 0x8869, - 0x2d9b, 0x8867, 0x2d95, 0x8865, 0x2d8f, 0x8863, 0x2d8a, 0x8860, - 0x2d84, 0x885e, 0x2d7e, 0x885c, 0x2d78, 0x885a, 0x2d72, 0x8858, - 0x2d6c, 0x8855, 0x2d66, 0x8853, 0x2d60, 0x8851, 0x2d5b, 0x884f, - 0x2d55, 0x884c, 0x2d4f, 0x884a, 0x2d49, 0x8848, 0x2d43, 0x8846, - 0x2d3d, 0x8844, 0x2d37, 0x8841, 0x2d31, 0x883f, 0x2d2c, 0x883d, - 0x2d26, 0x883b, 0x2d20, 0x8838, 0x2d1a, 0x8836, 0x2d14, 0x8834, - 0x2d0e, 0x8832, 0x2d08, 0x8830, 0x2d02, 0x882d, 0x2cfd, 0x882b, - 0x2cf7, 0x8829, 0x2cf1, 0x8827, 0x2ceb, 0x8825, 0x2ce5, 0x8822, - 0x2cdf, 0x8820, 0x2cd9, 0x881e, 0x2cd3, 0x881c, 0x2ccd, 0x881a, - 0x2cc8, 0x8817, 0x2cc2, 0x8815, 0x2cbc, 0x8813, 0x2cb6, 0x8811, - 0x2cb0, 0x880f, 0x2caa, 0x880c, 0x2ca4, 0x880a, 0x2c9e, 0x8808, - 0x2c98, 0x8806, 0x2c93, 0x8804, 0x2c8d, 0x8801, 0x2c87, 0x87ff, - 0x2c81, 0x87fd, 0x2c7b, 0x87fb, 0x2c75, 0x87f9, 0x2c6f, 0x87f6, - 0x2c69, 0x87f4, 0x2c63, 0x87f2, 0x2c5e, 0x87f0, 0x2c58, 0x87ee, - 0x2c52, 0x87ec, 0x2c4c, 0x87e9, 0x2c46, 0x87e7, 0x2c40, 0x87e5, - 0x2c3a, 0x87e3, 0x2c34, 0x87e1, 0x2c2e, 0x87df, 0x2c29, 0x87dc, - 0x2c23, 0x87da, 0x2c1d, 0x87d8, 0x2c17, 0x87d6, 0x2c11, 0x87d4, - 0x2c0b, 0x87d2, 0x2c05, 0x87cf, 0x2bff, 0x87cd, 0x2bf9, 0x87cb, - 0x2bf3, 0x87c9, 0x2bee, 0x87c7, 0x2be8, 0x87c5, 0x2be2, 0x87c2, - 0x2bdc, 0x87c0, 0x2bd6, 0x87be, 0x2bd0, 0x87bc, 0x2bca, 0x87ba, - 0x2bc4, 0x87b8, 0x2bbe, 0x87b6, 0x2bb8, 0x87b3, 0x2bb2, 0x87b1, - 0x2bad, 0x87af, 0x2ba7, 0x87ad, 0x2ba1, 0x87ab, 0x2b9b, 0x87a9, - 0x2b95, 0x87a7, 0x2b8f, 0x87a4, 0x2b89, 0x87a2, 0x2b83, 0x87a0, - 0x2b7d, 0x879e, 0x2b77, 0x879c, 0x2b71, 0x879a, 0x2b6c, 0x8798, - 0x2b66, 0x8795, 0x2b60, 0x8793, 0x2b5a, 0x8791, 0x2b54, 0x878f, - 0x2b4e, 0x878d, 0x2b48, 0x878b, 0x2b42, 0x8789, 0x2b3c, 0x8787, - 0x2b36, 0x8784, 0x2b30, 0x8782, 0x2b2b, 0x8780, 0x2b25, 0x877e, - 0x2b1f, 0x877c, 0x2b19, 0x877a, 0x2b13, 0x8778, 0x2b0d, 0x8776, - 0x2b07, 0x8774, 0x2b01, 0x8771, 0x2afb, 0x876f, 0x2af5, 0x876d, - 0x2aef, 0x876b, 0x2ae9, 0x8769, 0x2ae4, 0x8767, 0x2ade, 0x8765, - 0x2ad8, 0x8763, 0x2ad2, 0x8761, 0x2acc, 0x875e, 0x2ac6, 0x875c, - 0x2ac0, 0x875a, 0x2aba, 0x8758, 0x2ab4, 0x8756, 0x2aae, 0x8754, - 0x2aa8, 0x8752, 0x2aa2, 0x8750, 0x2a9c, 0x874e, 0x2a97, 0x874c, - 0x2a91, 0x874a, 0x2a8b, 0x8747, 0x2a85, 0x8745, 0x2a7f, 0x8743, - 0x2a79, 0x8741, 0x2a73, 0x873f, 0x2a6d, 0x873d, 0x2a67, 0x873b, - 0x2a61, 0x8739, 0x2a5b, 0x8737, 0x2a55, 0x8735, 0x2a4f, 0x8733, - 0x2a49, 0x8731, 0x2a44, 0x872e, 0x2a3e, 0x872c, 0x2a38, 0x872a, - 0x2a32, 0x8728, 0x2a2c, 0x8726, 0x2a26, 0x8724, 0x2a20, 0x8722, - 0x2a1a, 0x8720, 0x2a14, 0x871e, 0x2a0e, 0x871c, 0x2a08, 0x871a, - 0x2a02, 0x8718, 0x29fc, 0x8716, 0x29f6, 0x8714, 0x29f0, 0x8712, - 0x29eb, 0x870f, 0x29e5, 0x870d, 0x29df, 0x870b, 0x29d9, 0x8709, - 0x29d3, 0x8707, 0x29cd, 0x8705, 0x29c7, 0x8703, 0x29c1, 0x8701, - 0x29bb, 0x86ff, 0x29b5, 0x86fd, 0x29af, 0x86fb, 0x29a9, 0x86f9, - 0x29a3, 0x86f7, 0x299d, 0x86f5, 0x2997, 0x86f3, 0x2991, 0x86f1, - 0x298b, 0x86ef, 0x2986, 0x86ed, 0x2980, 0x86eb, 0x297a, 0x86e9, - 0x2974, 0x86e7, 0x296e, 0x86e4, 0x2968, 0x86e2, 0x2962, 0x86e0, - 0x295c, 0x86de, 0x2956, 0x86dc, 0x2950, 0x86da, 0x294a, 0x86d8, - 0x2944, 0x86d6, 0x293e, 0x86d4, 0x2938, 0x86d2, 0x2932, 0x86d0, - 0x292c, 0x86ce, 0x2926, 0x86cc, 0x2920, 0x86ca, 0x291b, 0x86c8, - 0x2915, 0x86c6, 0x290f, 0x86c4, 0x2909, 0x86c2, 0x2903, 0x86c0, - 0x28fd, 0x86be, 0x28f7, 0x86bc, 0x28f1, 0x86ba, 0x28eb, 0x86b8, - 0x28e5, 0x86b6, 0x28df, 0x86b4, 0x28d9, 0x86b2, 0x28d3, 0x86b0, - 0x28cd, 0x86ae, 0x28c7, 0x86ac, 0x28c1, 0x86aa, 0x28bb, 0x86a8, - 0x28b5, 0x86a6, 0x28af, 0x86a4, 0x28a9, 0x86a2, 0x28a3, 0x86a0, - 0x289d, 0x869e, 0x2898, 0x869c, 0x2892, 0x869a, 0x288c, 0x8698, - 0x2886, 0x8696, 0x2880, 0x8694, 0x287a, 0x8692, 0x2874, 0x8690, - 0x286e, 0x868e, 0x2868, 0x868c, 0x2862, 0x868a, 0x285c, 0x8688, - 0x2856, 0x8686, 0x2850, 0x8684, 0x284a, 0x8682, 0x2844, 0x8680, - 0x283e, 0x867e, 0x2838, 0x867c, 0x2832, 0x867a, 0x282c, 0x8678, - 0x2826, 0x8676, 0x2820, 0x8674, 0x281a, 0x8672, 0x2814, 0x8670, - 0x280e, 0x866e, 0x2808, 0x866d, 0x2802, 0x866b, 0x27fc, 0x8669, - 0x27f6, 0x8667, 0x27f1, 0x8665, 0x27eb, 0x8663, 0x27e5, 0x8661, - 0x27df, 0x865f, 0x27d9, 0x865d, 0x27d3, 0x865b, 0x27cd, 0x8659, - 0x27c7, 0x8657, 0x27c1, 0x8655, 0x27bb, 0x8653, 0x27b5, 0x8651, - 0x27af, 0x864f, 0x27a9, 0x864d, 0x27a3, 0x864b, 0x279d, 0x8649, - 0x2797, 0x8647, 0x2791, 0x8645, 0x278b, 0x8644, 0x2785, 0x8642, - 0x277f, 0x8640, 0x2779, 0x863e, 0x2773, 0x863c, 0x276d, 0x863a, - 0x2767, 0x8638, 0x2761, 0x8636, 0x275b, 0x8634, 0x2755, 0x8632, - 0x274f, 0x8630, 0x2749, 0x862e, 0x2743, 0x862c, 0x273d, 0x862a, - 0x2737, 0x8628, 0x2731, 0x8627, 0x272b, 0x8625, 0x2725, 0x8623, - 0x271f, 0x8621, 0x2719, 0x861f, 0x2713, 0x861d, 0x270d, 0x861b, - 0x2707, 0x8619, 0x2701, 0x8617, 0x26fb, 0x8615, 0x26f5, 0x8613, - 0x26ef, 0x8611, 0x26e9, 0x8610, 0x26e4, 0x860e, 0x26de, 0x860c, - 0x26d8, 0x860a, 0x26d2, 0x8608, 0x26cc, 0x8606, 0x26c6, 0x8604, - 0x26c0, 0x8602, 0x26ba, 0x8600, 0x26b4, 0x85fe, 0x26ae, 0x85fc, - 0x26a8, 0x85fb, 0x26a2, 0x85f9, 0x269c, 0x85f7, 0x2696, 0x85f5, - 0x2690, 0x85f3, 0x268a, 0x85f1, 0x2684, 0x85ef, 0x267e, 0x85ed, - 0x2678, 0x85eb, 0x2672, 0x85ea, 0x266c, 0x85e8, 0x2666, 0x85e6, - 0x2660, 0x85e4, 0x265a, 0x85e2, 0x2654, 0x85e0, 0x264e, 0x85de, - 0x2648, 0x85dc, 0x2642, 0x85da, 0x263c, 0x85d9, 0x2636, 0x85d7, - 0x2630, 0x85d5, 0x262a, 0x85d3, 0x2624, 0x85d1, 0x261e, 0x85cf, - 0x2618, 0x85cd, 0x2612, 0x85cb, 0x260c, 0x85ca, 0x2606, 0x85c8, - 0x2600, 0x85c6, 0x25fa, 0x85c4, 0x25f4, 0x85c2, 0x25ee, 0x85c0, - 0x25e8, 0x85be, 0x25e2, 0x85bd, 0x25dc, 0x85bb, 0x25d6, 0x85b9, - 0x25d0, 0x85b7, 0x25ca, 0x85b5, 0x25c4, 0x85b3, 0x25be, 0x85b1, - 0x25b8, 0x85b0, 0x25b2, 0x85ae, 0x25ac, 0x85ac, 0x25a6, 0x85aa, - 0x25a0, 0x85a8, 0x259a, 0x85a6, 0x2594, 0x85a4, 0x258e, 0x85a3, - 0x2588, 0x85a1, 0x2582, 0x859f, 0x257c, 0x859d, 0x2576, 0x859b, - 0x2570, 0x8599, 0x256a, 0x8598, 0x2564, 0x8596, 0x255e, 0x8594, - 0x2558, 0x8592, 0x2552, 0x8590, 0x254c, 0x858e, 0x2546, 0x858d, - 0x2540, 0x858b, 0x253a, 0x8589, 0x2534, 0x8587, 0x252e, 0x8585, - 0x2528, 0x8583, 0x2522, 0x8582, 0x251c, 0x8580, 0x2516, 0x857e, - 0x250f, 0x857c, 0x2509, 0x857a, 0x2503, 0x8579, 0x24fd, 0x8577, - 0x24f7, 0x8575, 0x24f1, 0x8573, 0x24eb, 0x8571, 0x24e5, 0x856f, - 0x24df, 0x856e, 0x24d9, 0x856c, 0x24d3, 0x856a, 0x24cd, 0x8568, - 0x24c7, 0x8566, 0x24c1, 0x8565, 0x24bb, 0x8563, 0x24b5, 0x8561, - 0x24af, 0x855f, 0x24a9, 0x855d, 0x24a3, 0x855c, 0x249d, 0x855a, - 0x2497, 0x8558, 0x2491, 0x8556, 0x248b, 0x8554, 0x2485, 0x8553, - 0x247f, 0x8551, 0x2479, 0x854f, 0x2473, 0x854d, 0x246d, 0x854b, - 0x2467, 0x854a, 0x2461, 0x8548, 0x245b, 0x8546, 0x2455, 0x8544, - 0x244f, 0x8543, 0x2449, 0x8541, 0x2443, 0x853f, 0x243d, 0x853d, - 0x2437, 0x853b, 0x2431, 0x853a, 0x242b, 0x8538, 0x2425, 0x8536, - 0x241f, 0x8534, 0x2419, 0x8533, 0x2413, 0x8531, 0x240d, 0x852f, - 0x2407, 0x852d, 0x2401, 0x852b, 0x23fa, 0x852a, 0x23f4, 0x8528, - 0x23ee, 0x8526, 0x23e8, 0x8524, 0x23e2, 0x8523, 0x23dc, 0x8521, - 0x23d6, 0x851f, 0x23d0, 0x851d, 0x23ca, 0x851c, 0x23c4, 0x851a, - 0x23be, 0x8518, 0x23b8, 0x8516, 0x23b2, 0x8515, 0x23ac, 0x8513, - 0x23a6, 0x8511, 0x23a0, 0x850f, 0x239a, 0x850e, 0x2394, 0x850c, - 0x238e, 0x850a, 0x2388, 0x8508, 0x2382, 0x8507, 0x237c, 0x8505, - 0x2376, 0x8503, 0x2370, 0x8501, 0x236a, 0x8500, 0x2364, 0x84fe, - 0x235e, 0x84fc, 0x2358, 0x84fa, 0x2352, 0x84f9, 0x234b, 0x84f7, - 0x2345, 0x84f5, 0x233f, 0x84f4, 0x2339, 0x84f2, 0x2333, 0x84f0, - 0x232d, 0x84ee, 0x2327, 0x84ed, 0x2321, 0x84eb, 0x231b, 0x84e9, - 0x2315, 0x84e7, 0x230f, 0x84e6, 0x2309, 0x84e4, 0x2303, 0x84e2, - 0x22fd, 0x84e1, 0x22f7, 0x84df, 0x22f1, 0x84dd, 0x22eb, 0x84db, - 0x22e5, 0x84da, 0x22df, 0x84d8, 0x22d9, 0x84d6, 0x22d3, 0x84d5, - 0x22cd, 0x84d3, 0x22c7, 0x84d1, 0x22c0, 0x84cf, 0x22ba, 0x84ce, - 0x22b4, 0x84cc, 0x22ae, 0x84ca, 0x22a8, 0x84c9, 0x22a2, 0x84c7, - 0x229c, 0x84c5, 0x2296, 0x84c4, 0x2290, 0x84c2, 0x228a, 0x84c0, - 0x2284, 0x84be, 0x227e, 0x84bd, 0x2278, 0x84bb, 0x2272, 0x84b9, - 0x226c, 0x84b8, 0x2266, 0x84b6, 0x2260, 0x84b4, 0x225a, 0x84b3, - 0x2254, 0x84b1, 0x224e, 0x84af, 0x2247, 0x84ae, 0x2241, 0x84ac, - 0x223b, 0x84aa, 0x2235, 0x84a9, 0x222f, 0x84a7, 0x2229, 0x84a5, - 0x2223, 0x84a3, 0x221d, 0x84a2, 0x2217, 0x84a0, 0x2211, 0x849e, - 0x220b, 0x849d, 0x2205, 0x849b, 0x21ff, 0x8499, 0x21f9, 0x8498, - 0x21f3, 0x8496, 0x21ed, 0x8494, 0x21e7, 0x8493, 0x21e1, 0x8491, - 0x21da, 0x848f, 0x21d4, 0x848e, 0x21ce, 0x848c, 0x21c8, 0x848a, - 0x21c2, 0x8489, 0x21bc, 0x8487, 0x21b6, 0x8486, 0x21b0, 0x8484, - 0x21aa, 0x8482, 0x21a4, 0x8481, 0x219e, 0x847f, 0x2198, 0x847d, - 0x2192, 0x847c, 0x218c, 0x847a, 0x2186, 0x8478, 0x2180, 0x8477, - 0x2179, 0x8475, 0x2173, 0x8473, 0x216d, 0x8472, 0x2167, 0x8470, - 0x2161, 0x846e, 0x215b, 0x846d, 0x2155, 0x846b, 0x214f, 0x846a, - 0x2149, 0x8468, 0x2143, 0x8466, 0x213d, 0x8465, 0x2137, 0x8463, - 0x2131, 0x8461, 0x212b, 0x8460, 0x2125, 0x845e, 0x211e, 0x845d, - 0x2118, 0x845b, 0x2112, 0x8459, 0x210c, 0x8458, 0x2106, 0x8456, - 0x2100, 0x8454, 0x20fa, 0x8453, 0x20f4, 0x8451, 0x20ee, 0x8450, - 0x20e8, 0x844e, 0x20e2, 0x844c, 0x20dc, 0x844b, 0x20d6, 0x8449, - 0x20d0, 0x8447, 0x20c9, 0x8446, 0x20c3, 0x8444, 0x20bd, 0x8443, - 0x20b7, 0x8441, 0x20b1, 0x843f, 0x20ab, 0x843e, 0x20a5, 0x843c, - 0x209f, 0x843b, 0x2099, 0x8439, 0x2093, 0x8437, 0x208d, 0x8436, - 0x2087, 0x8434, 0x2081, 0x8433, 0x207a, 0x8431, 0x2074, 0x842f, - 0x206e, 0x842e, 0x2068, 0x842c, 0x2062, 0x842b, 0x205c, 0x8429, - 0x2056, 0x8427, 0x2050, 0x8426, 0x204a, 0x8424, 0x2044, 0x8423, - 0x203e, 0x8421, 0x2038, 0x8420, 0x2032, 0x841e, 0x202b, 0x841c, - 0x2025, 0x841b, 0x201f, 0x8419, 0x2019, 0x8418, 0x2013, 0x8416, - 0x200d, 0x8415, 0x2007, 0x8413, 0x2001, 0x8411, 0x1ffb, 0x8410, - 0x1ff5, 0x840e, 0x1fef, 0x840d, 0x1fe9, 0x840b, 0x1fe2, 0x840a, - 0x1fdc, 0x8408, 0x1fd6, 0x8406, 0x1fd0, 0x8405, 0x1fca, 0x8403, - 0x1fc4, 0x8402, 0x1fbe, 0x8400, 0x1fb8, 0x83ff, 0x1fb2, 0x83fd, - 0x1fac, 0x83fb, 0x1fa6, 0x83fa, 0x1f9f, 0x83f8, 0x1f99, 0x83f7, - 0x1f93, 0x83f5, 0x1f8d, 0x83f4, 0x1f87, 0x83f2, 0x1f81, 0x83f1, - 0x1f7b, 0x83ef, 0x1f75, 0x83ee, 0x1f6f, 0x83ec, 0x1f69, 0x83ea, - 0x1f63, 0x83e9, 0x1f5d, 0x83e7, 0x1f56, 0x83e6, 0x1f50, 0x83e4, - 0x1f4a, 0x83e3, 0x1f44, 0x83e1, 0x1f3e, 0x83e0, 0x1f38, 0x83de, - 0x1f32, 0x83dd, 0x1f2c, 0x83db, 0x1f26, 0x83da, 0x1f20, 0x83d8, - 0x1f19, 0x83d7, 0x1f13, 0x83d5, 0x1f0d, 0x83d3, 0x1f07, 0x83d2, - 0x1f01, 0x83d0, 0x1efb, 0x83cf, 0x1ef5, 0x83cd, 0x1eef, 0x83cc, - 0x1ee9, 0x83ca, 0x1ee3, 0x83c9, 0x1edd, 0x83c7, 0x1ed6, 0x83c6, - 0x1ed0, 0x83c4, 0x1eca, 0x83c3, 0x1ec4, 0x83c1, 0x1ebe, 0x83c0, - 0x1eb8, 0x83be, 0x1eb2, 0x83bd, 0x1eac, 0x83bb, 0x1ea6, 0x83ba, - 0x1ea0, 0x83b8, 0x1e99, 0x83b7, 0x1e93, 0x83b5, 0x1e8d, 0x83b4, - 0x1e87, 0x83b2, 0x1e81, 0x83b1, 0x1e7b, 0x83af, 0x1e75, 0x83ae, - 0x1e6f, 0x83ac, 0x1e69, 0x83ab, 0x1e62, 0x83a9, 0x1e5c, 0x83a8, - 0x1e56, 0x83a6, 0x1e50, 0x83a5, 0x1e4a, 0x83a3, 0x1e44, 0x83a2, - 0x1e3e, 0x83a0, 0x1e38, 0x839f, 0x1e32, 0x839d, 0x1e2c, 0x839c, - 0x1e25, 0x839a, 0x1e1f, 0x8399, 0x1e19, 0x8397, 0x1e13, 0x8396, - 0x1e0d, 0x8394, 0x1e07, 0x8393, 0x1e01, 0x8392, 0x1dfb, 0x8390, - 0x1df5, 0x838f, 0x1dee, 0x838d, 0x1de8, 0x838c, 0x1de2, 0x838a, - 0x1ddc, 0x8389, 0x1dd6, 0x8387, 0x1dd0, 0x8386, 0x1dca, 0x8384, - 0x1dc4, 0x8383, 0x1dbe, 0x8381, 0x1db7, 0x8380, 0x1db1, 0x837e, - 0x1dab, 0x837d, 0x1da5, 0x837c, 0x1d9f, 0x837a, 0x1d99, 0x8379, - 0x1d93, 0x8377, 0x1d8d, 0x8376, 0x1d87, 0x8374, 0x1d80, 0x8373, - 0x1d7a, 0x8371, 0x1d74, 0x8370, 0x1d6e, 0x836f, 0x1d68, 0x836d, - 0x1d62, 0x836c, 0x1d5c, 0x836a, 0x1d56, 0x8369, 0x1d50, 0x8367, - 0x1d49, 0x8366, 0x1d43, 0x8364, 0x1d3d, 0x8363, 0x1d37, 0x8362, - 0x1d31, 0x8360, 0x1d2b, 0x835f, 0x1d25, 0x835d, 0x1d1f, 0x835c, - 0x1d18, 0x835a, 0x1d12, 0x8359, 0x1d0c, 0x8358, 0x1d06, 0x8356, - 0x1d00, 0x8355, 0x1cfa, 0x8353, 0x1cf4, 0x8352, 0x1cee, 0x8350, - 0x1ce8, 0x834f, 0x1ce1, 0x834e, 0x1cdb, 0x834c, 0x1cd5, 0x834b, - 0x1ccf, 0x8349, 0x1cc9, 0x8348, 0x1cc3, 0x8347, 0x1cbd, 0x8345, - 0x1cb7, 0x8344, 0x1cb0, 0x8342, 0x1caa, 0x8341, 0x1ca4, 0x833f, - 0x1c9e, 0x833e, 0x1c98, 0x833d, 0x1c92, 0x833b, 0x1c8c, 0x833a, - 0x1c86, 0x8338, 0x1c7f, 0x8337, 0x1c79, 0x8336, 0x1c73, 0x8334, - 0x1c6d, 0x8333, 0x1c67, 0x8331, 0x1c61, 0x8330, 0x1c5b, 0x832f, - 0x1c55, 0x832d, 0x1c4e, 0x832c, 0x1c48, 0x832b, 0x1c42, 0x8329, - 0x1c3c, 0x8328, 0x1c36, 0x8326, 0x1c30, 0x8325, 0x1c2a, 0x8324, - 0x1c24, 0x8322, 0x1c1d, 0x8321, 0x1c17, 0x831f, 0x1c11, 0x831e, - 0x1c0b, 0x831d, 0x1c05, 0x831b, 0x1bff, 0x831a, 0x1bf9, 0x8319, - 0x1bf2, 0x8317, 0x1bec, 0x8316, 0x1be6, 0x8314, 0x1be0, 0x8313, - 0x1bda, 0x8312, 0x1bd4, 0x8310, 0x1bce, 0x830f, 0x1bc8, 0x830e, - 0x1bc1, 0x830c, 0x1bbb, 0x830b, 0x1bb5, 0x830a, 0x1baf, 0x8308, - 0x1ba9, 0x8307, 0x1ba3, 0x8305, 0x1b9d, 0x8304, 0x1b96, 0x8303, - 0x1b90, 0x8301, 0x1b8a, 0x8300, 0x1b84, 0x82ff, 0x1b7e, 0x82fd, - 0x1b78, 0x82fc, 0x1b72, 0x82fb, 0x1b6c, 0x82f9, 0x1b65, 0x82f8, - 0x1b5f, 0x82f7, 0x1b59, 0x82f5, 0x1b53, 0x82f4, 0x1b4d, 0x82f3, - 0x1b47, 0x82f1, 0x1b41, 0x82f0, 0x1b3a, 0x82ef, 0x1b34, 0x82ed, - 0x1b2e, 0x82ec, 0x1b28, 0x82eb, 0x1b22, 0x82e9, 0x1b1c, 0x82e8, - 0x1b16, 0x82e7, 0x1b0f, 0x82e5, 0x1b09, 0x82e4, 0x1b03, 0x82e3, - 0x1afd, 0x82e1, 0x1af7, 0x82e0, 0x1af1, 0x82df, 0x1aeb, 0x82dd, - 0x1ae4, 0x82dc, 0x1ade, 0x82db, 0x1ad8, 0x82d9, 0x1ad2, 0x82d8, - 0x1acc, 0x82d7, 0x1ac6, 0x82d5, 0x1ac0, 0x82d4, 0x1ab9, 0x82d3, - 0x1ab3, 0x82d1, 0x1aad, 0x82d0, 0x1aa7, 0x82cf, 0x1aa1, 0x82ce, - 0x1a9b, 0x82cc, 0x1a95, 0x82cb, 0x1a8e, 0x82ca, 0x1a88, 0x82c8, - 0x1a82, 0x82c7, 0x1a7c, 0x82c6, 0x1a76, 0x82c4, 0x1a70, 0x82c3, - 0x1a6a, 0x82c2, 0x1a63, 0x82c1, 0x1a5d, 0x82bf, 0x1a57, 0x82be, - 0x1a51, 0x82bd, 0x1a4b, 0x82bb, 0x1a45, 0x82ba, 0x1a3e, 0x82b9, - 0x1a38, 0x82b7, 0x1a32, 0x82b6, 0x1a2c, 0x82b5, 0x1a26, 0x82b4, - 0x1a20, 0x82b2, 0x1a1a, 0x82b1, 0x1a13, 0x82b0, 0x1a0d, 0x82ae, - 0x1a07, 0x82ad, 0x1a01, 0x82ac, 0x19fb, 0x82ab, 0x19f5, 0x82a9, - 0x19ef, 0x82a8, 0x19e8, 0x82a7, 0x19e2, 0x82a6, 0x19dc, 0x82a4, - 0x19d6, 0x82a3, 0x19d0, 0x82a2, 0x19ca, 0x82a0, 0x19c3, 0x829f, - 0x19bd, 0x829e, 0x19b7, 0x829d, 0x19b1, 0x829b, 0x19ab, 0x829a, - 0x19a5, 0x8299, 0x199f, 0x8298, 0x1998, 0x8296, 0x1992, 0x8295, - 0x198c, 0x8294, 0x1986, 0x8293, 0x1980, 0x8291, 0x197a, 0x8290, - 0x1973, 0x828f, 0x196d, 0x828e, 0x1967, 0x828c, 0x1961, 0x828b, - 0x195b, 0x828a, 0x1955, 0x8289, 0x194e, 0x8287, 0x1948, 0x8286, - 0x1942, 0x8285, 0x193c, 0x8284, 0x1936, 0x8282, 0x1930, 0x8281, - 0x192a, 0x8280, 0x1923, 0x827f, 0x191d, 0x827e, 0x1917, 0x827c, - 0x1911, 0x827b, 0x190b, 0x827a, 0x1905, 0x8279, 0x18fe, 0x8277, - 0x18f8, 0x8276, 0x18f2, 0x8275, 0x18ec, 0x8274, 0x18e6, 0x8272, - 0x18e0, 0x8271, 0x18d9, 0x8270, 0x18d3, 0x826f, 0x18cd, 0x826e, - 0x18c7, 0x826c, 0x18c1, 0x826b, 0x18bb, 0x826a, 0x18b4, 0x8269, - 0x18ae, 0x8268, 0x18a8, 0x8266, 0x18a2, 0x8265, 0x189c, 0x8264, - 0x1896, 0x8263, 0x188f, 0x8261, 0x1889, 0x8260, 0x1883, 0x825f, - 0x187d, 0x825e, 0x1877, 0x825d, 0x1871, 0x825b, 0x186a, 0x825a, - 0x1864, 0x8259, 0x185e, 0x8258, 0x1858, 0x8257, 0x1852, 0x8255, - 0x184c, 0x8254, 0x1845, 0x8253, 0x183f, 0x8252, 0x1839, 0x8251, - 0x1833, 0x8250, 0x182d, 0x824e, 0x1827, 0x824d, 0x1820, 0x824c, - 0x181a, 0x824b, 0x1814, 0x824a, 0x180e, 0x8248, 0x1808, 0x8247, - 0x1802, 0x8246, 0x17fb, 0x8245, 0x17f5, 0x8244, 0x17ef, 0x8243, - 0x17e9, 0x8241, 0x17e3, 0x8240, 0x17dd, 0x823f, 0x17d6, 0x823e, - 0x17d0, 0x823d, 0x17ca, 0x823b, 0x17c4, 0x823a, 0x17be, 0x8239, - 0x17b7, 0x8238, 0x17b1, 0x8237, 0x17ab, 0x8236, 0x17a5, 0x8234, - 0x179f, 0x8233, 0x1799, 0x8232, 0x1792, 0x8231, 0x178c, 0x8230, - 0x1786, 0x822f, 0x1780, 0x822e, 0x177a, 0x822c, 0x1774, 0x822b, - 0x176d, 0x822a, 0x1767, 0x8229, 0x1761, 0x8228, 0x175b, 0x8227, - 0x1755, 0x8226, 0x174e, 0x8224, 0x1748, 0x8223, 0x1742, 0x8222, - 0x173c, 0x8221, 0x1736, 0x8220, 0x1730, 0x821f, 0x1729, 0x821e, - 0x1723, 0x821c, 0x171d, 0x821b, 0x1717, 0x821a, 0x1711, 0x8219, - 0x170a, 0x8218, 0x1704, 0x8217, 0x16fe, 0x8216, 0x16f8, 0x8214, - 0x16f2, 0x8213, 0x16ec, 0x8212, 0x16e5, 0x8211, 0x16df, 0x8210, - 0x16d9, 0x820f, 0x16d3, 0x820e, 0x16cd, 0x820d, 0x16c6, 0x820b, - 0x16c0, 0x820a, 0x16ba, 0x8209, 0x16b4, 0x8208, 0x16ae, 0x8207, - 0x16a8, 0x8206, 0x16a1, 0x8205, 0x169b, 0x8204, 0x1695, 0x8203, - 0x168f, 0x8201, 0x1689, 0x8200, 0x1682, 0x81ff, 0x167c, 0x81fe, - 0x1676, 0x81fd, 0x1670, 0x81fc, 0x166a, 0x81fb, 0x1664, 0x81fa, - 0x165d, 0x81f9, 0x1657, 0x81f8, 0x1651, 0x81f6, 0x164b, 0x81f5, - 0x1645, 0x81f4, 0x163e, 0x81f3, 0x1638, 0x81f2, 0x1632, 0x81f1, - 0x162c, 0x81f0, 0x1626, 0x81ef, 0x161f, 0x81ee, 0x1619, 0x81ed, - 0x1613, 0x81ec, 0x160d, 0x81ea, 0x1607, 0x81e9, 0x1601, 0x81e8, - 0x15fa, 0x81e7, 0x15f4, 0x81e6, 0x15ee, 0x81e5, 0x15e8, 0x81e4, - 0x15e2, 0x81e3, 0x15db, 0x81e2, 0x15d5, 0x81e1, 0x15cf, 0x81e0, - 0x15c9, 0x81df, 0x15c3, 0x81de, 0x15bc, 0x81dc, 0x15b6, 0x81db, - 0x15b0, 0x81da, 0x15aa, 0x81d9, 0x15a4, 0x81d8, 0x159d, 0x81d7, - 0x1597, 0x81d6, 0x1591, 0x81d5, 0x158b, 0x81d4, 0x1585, 0x81d3, - 0x157f, 0x81d2, 0x1578, 0x81d1, 0x1572, 0x81d0, 0x156c, 0x81cf, - 0x1566, 0x81ce, 0x1560, 0x81cd, 0x1559, 0x81cc, 0x1553, 0x81cb, - 0x154d, 0x81c9, 0x1547, 0x81c8, 0x1541, 0x81c7, 0x153a, 0x81c6, - 0x1534, 0x81c5, 0x152e, 0x81c4, 0x1528, 0x81c3, 0x1522, 0x81c2, - 0x151b, 0x81c1, 0x1515, 0x81c0, 0x150f, 0x81bf, 0x1509, 0x81be, - 0x1503, 0x81bd, 0x14fc, 0x81bc, 0x14f6, 0x81bb, 0x14f0, 0x81ba, - 0x14ea, 0x81b9, 0x14e4, 0x81b8, 0x14dd, 0x81b7, 0x14d7, 0x81b6, - 0x14d1, 0x81b5, 0x14cb, 0x81b4, 0x14c5, 0x81b3, 0x14be, 0x81b2, - 0x14b8, 0x81b1, 0x14b2, 0x81b0, 0x14ac, 0x81af, 0x14a6, 0x81ae, - 0x149f, 0x81ad, 0x1499, 0x81ac, 0x1493, 0x81ab, 0x148d, 0x81aa, - 0x1487, 0x81a9, 0x1480, 0x81a8, 0x147a, 0x81a7, 0x1474, 0x81a6, - 0x146e, 0x81a5, 0x1468, 0x81a4, 0x1461, 0x81a3, 0x145b, 0x81a2, - 0x1455, 0x81a1, 0x144f, 0x81a0, 0x1449, 0x819f, 0x1442, 0x819e, - 0x143c, 0x819d, 0x1436, 0x819c, 0x1430, 0x819b, 0x142a, 0x819a, - 0x1423, 0x8199, 0x141d, 0x8198, 0x1417, 0x8197, 0x1411, 0x8196, - 0x140b, 0x8195, 0x1404, 0x8194, 0x13fe, 0x8193, 0x13f8, 0x8192, - 0x13f2, 0x8191, 0x13eb, 0x8190, 0x13e5, 0x818f, 0x13df, 0x818e, - 0x13d9, 0x818d, 0x13d3, 0x818c, 0x13cc, 0x818b, 0x13c6, 0x818a, - 0x13c0, 0x8189, 0x13ba, 0x8188, 0x13b4, 0x8187, 0x13ad, 0x8186, - 0x13a7, 0x8185, 0x13a1, 0x8184, 0x139b, 0x8183, 0x1395, 0x8182, - 0x138e, 0x8181, 0x1388, 0x8180, 0x1382, 0x817f, 0x137c, 0x817e, - 0x1376, 0x817d, 0x136f, 0x817c, 0x1369, 0x817c, 0x1363, 0x817b, - 0x135d, 0x817a, 0x1356, 0x8179, 0x1350, 0x8178, 0x134a, 0x8177, - 0x1344, 0x8176, 0x133e, 0x8175, 0x1337, 0x8174, 0x1331, 0x8173, - 0x132b, 0x8172, 0x1325, 0x8171, 0x131f, 0x8170, 0x1318, 0x816f, - 0x1312, 0x816e, 0x130c, 0x816d, 0x1306, 0x816c, 0x12ff, 0x816c, - 0x12f9, 0x816b, 0x12f3, 0x816a, 0x12ed, 0x8169, 0x12e7, 0x8168, - 0x12e0, 0x8167, 0x12da, 0x8166, 0x12d4, 0x8165, 0x12ce, 0x8164, - 0x12c8, 0x8163, 0x12c1, 0x8162, 0x12bb, 0x8161, 0x12b5, 0x8160, - 0x12af, 0x815f, 0x12a8, 0x815f, 0x12a2, 0x815e, 0x129c, 0x815d, - 0x1296, 0x815c, 0x1290, 0x815b, 0x1289, 0x815a, 0x1283, 0x8159, - 0x127d, 0x8158, 0x1277, 0x8157, 0x1271, 0x8156, 0x126a, 0x8155, - 0x1264, 0x8155, 0x125e, 0x8154, 0x1258, 0x8153, 0x1251, 0x8152, - 0x124b, 0x8151, 0x1245, 0x8150, 0x123f, 0x814f, 0x1239, 0x814e, - 0x1232, 0x814d, 0x122c, 0x814c, 0x1226, 0x814c, 0x1220, 0x814b, - 0x1219, 0x814a, 0x1213, 0x8149, 0x120d, 0x8148, 0x1207, 0x8147, - 0x1201, 0x8146, 0x11fa, 0x8145, 0x11f4, 0x8145, 0x11ee, 0x8144, - 0x11e8, 0x8143, 0x11e1, 0x8142, 0x11db, 0x8141, 0x11d5, 0x8140, - 0x11cf, 0x813f, 0x11c9, 0x813e, 0x11c2, 0x813d, 0x11bc, 0x813d, - 0x11b6, 0x813c, 0x11b0, 0x813b, 0x11a9, 0x813a, 0x11a3, 0x8139, - 0x119d, 0x8138, 0x1197, 0x8137, 0x1191, 0x8137, 0x118a, 0x8136, - 0x1184, 0x8135, 0x117e, 0x8134, 0x1178, 0x8133, 0x1171, 0x8132, - 0x116b, 0x8131, 0x1165, 0x8131, 0x115f, 0x8130, 0x1159, 0x812f, - 0x1152, 0x812e, 0x114c, 0x812d, 0x1146, 0x812c, 0x1140, 0x812b, - 0x1139, 0x812b, 0x1133, 0x812a, 0x112d, 0x8129, 0x1127, 0x8128, - 0x1121, 0x8127, 0x111a, 0x8126, 0x1114, 0x8126, 0x110e, 0x8125, - 0x1108, 0x8124, 0x1101, 0x8123, 0x10fb, 0x8122, 0x10f5, 0x8121, - 0x10ef, 0x8121, 0x10e8, 0x8120, 0x10e2, 0x811f, 0x10dc, 0x811e, - 0x10d6, 0x811d, 0x10d0, 0x811c, 0x10c9, 0x811c, 0x10c3, 0x811b, - 0x10bd, 0x811a, 0x10b7, 0x8119, 0x10b0, 0x8118, 0x10aa, 0x8117, - 0x10a4, 0x8117, 0x109e, 0x8116, 0x1098, 0x8115, 0x1091, 0x8114, - 0x108b, 0x8113, 0x1085, 0x8113, 0x107f, 0x8112, 0x1078, 0x8111, - 0x1072, 0x8110, 0x106c, 0x810f, 0x1066, 0x810f, 0x105f, 0x810e, - 0x1059, 0x810d, 0x1053, 0x810c, 0x104d, 0x810b, 0x1047, 0x810b, - 0x1040, 0x810a, 0x103a, 0x8109, 0x1034, 0x8108, 0x102e, 0x8107, - 0x1027, 0x8107, 0x1021, 0x8106, 0x101b, 0x8105, 0x1015, 0x8104, - 0x100e, 0x8103, 0x1008, 0x8103, 0x1002, 0x8102, 0xffc, 0x8101, - 0xff5, 0x8100, 0xfef, 0x80ff, 0xfe9, 0x80ff, 0xfe3, 0x80fe, - 0xfdd, 0x80fd, 0xfd6, 0x80fc, 0xfd0, 0x80fc, 0xfca, 0x80fb, - 0xfc4, 0x80fa, 0xfbd, 0x80f9, 0xfb7, 0x80f8, 0xfb1, 0x80f8, - 0xfab, 0x80f7, 0xfa4, 0x80f6, 0xf9e, 0x80f5, 0xf98, 0x80f5, - 0xf92, 0x80f4, 0xf8b, 0x80f3, 0xf85, 0x80f2, 0xf7f, 0x80f2, - 0xf79, 0x80f1, 0xf73, 0x80f0, 0xf6c, 0x80ef, 0xf66, 0x80ef, - 0xf60, 0x80ee, 0xf5a, 0x80ed, 0xf53, 0x80ec, 0xf4d, 0x80ec, - 0xf47, 0x80eb, 0xf41, 0x80ea, 0xf3a, 0x80e9, 0xf34, 0x80e9, - 0xf2e, 0x80e8, 0xf28, 0x80e7, 0xf21, 0x80e6, 0xf1b, 0x80e6, - 0xf15, 0x80e5, 0xf0f, 0x80e4, 0xf08, 0x80e3, 0xf02, 0x80e3, - 0xefc, 0x80e2, 0xef6, 0x80e1, 0xef0, 0x80e0, 0xee9, 0x80e0, - 0xee3, 0x80df, 0xedd, 0x80de, 0xed7, 0x80dd, 0xed0, 0x80dd, - 0xeca, 0x80dc, 0xec4, 0x80db, 0xebe, 0x80db, 0xeb7, 0x80da, - 0xeb1, 0x80d9, 0xeab, 0x80d8, 0xea5, 0x80d8, 0xe9e, 0x80d7, - 0xe98, 0x80d6, 0xe92, 0x80d6, 0xe8c, 0x80d5, 0xe85, 0x80d4, - 0xe7f, 0x80d3, 0xe79, 0x80d3, 0xe73, 0x80d2, 0xe6c, 0x80d1, - 0xe66, 0x80d1, 0xe60, 0x80d0, 0xe5a, 0x80cf, 0xe53, 0x80ce, - 0xe4d, 0x80ce, 0xe47, 0x80cd, 0xe41, 0x80cc, 0xe3a, 0x80cc, - 0xe34, 0x80cb, 0xe2e, 0x80ca, 0xe28, 0x80ca, 0xe22, 0x80c9, - 0xe1b, 0x80c8, 0xe15, 0x80c7, 0xe0f, 0x80c7, 0xe09, 0x80c6, - 0xe02, 0x80c5, 0xdfc, 0x80c5, 0xdf6, 0x80c4, 0xdf0, 0x80c3, - 0xde9, 0x80c3, 0xde3, 0x80c2, 0xddd, 0x80c1, 0xdd7, 0x80c1, - 0xdd0, 0x80c0, 0xdca, 0x80bf, 0xdc4, 0x80bf, 0xdbe, 0x80be, - 0xdb7, 0x80bd, 0xdb1, 0x80bd, 0xdab, 0x80bc, 0xda5, 0x80bb, - 0xd9e, 0x80bb, 0xd98, 0x80ba, 0xd92, 0x80b9, 0xd8c, 0x80b9, - 0xd85, 0x80b8, 0xd7f, 0x80b7, 0xd79, 0x80b7, 0xd73, 0x80b6, - 0xd6c, 0x80b5, 0xd66, 0x80b5, 0xd60, 0x80b4, 0xd5a, 0x80b3, - 0xd53, 0x80b3, 0xd4d, 0x80b2, 0xd47, 0x80b1, 0xd41, 0x80b1, - 0xd3a, 0x80b0, 0xd34, 0x80af, 0xd2e, 0x80af, 0xd28, 0x80ae, - 0xd21, 0x80ad, 0xd1b, 0x80ad, 0xd15, 0x80ac, 0xd0f, 0x80ab, - 0xd08, 0x80ab, 0xd02, 0x80aa, 0xcfc, 0x80aa, 0xcf6, 0x80a9, - 0xcef, 0x80a8, 0xce9, 0x80a8, 0xce3, 0x80a7, 0xcdd, 0x80a6, - 0xcd6, 0x80a6, 0xcd0, 0x80a5, 0xcca, 0x80a5, 0xcc4, 0x80a4, - 0xcbd, 0x80a3, 0xcb7, 0x80a3, 0xcb1, 0x80a2, 0xcab, 0x80a1, - 0xca4, 0x80a1, 0xc9e, 0x80a0, 0xc98, 0x80a0, 0xc92, 0x809f, - 0xc8b, 0x809e, 0xc85, 0x809e, 0xc7f, 0x809d, 0xc79, 0x809c, - 0xc72, 0x809c, 0xc6c, 0x809b, 0xc66, 0x809b, 0xc60, 0x809a, - 0xc59, 0x8099, 0xc53, 0x8099, 0xc4d, 0x8098, 0xc47, 0x8098, - 0xc40, 0x8097, 0xc3a, 0x8096, 0xc34, 0x8096, 0xc2e, 0x8095, - 0xc27, 0x8095, 0xc21, 0x8094, 0xc1b, 0x8093, 0xc14, 0x8093, - 0xc0e, 0x8092, 0xc08, 0x8092, 0xc02, 0x8091, 0xbfb, 0x8090, - 0xbf5, 0x8090, 0xbef, 0x808f, 0xbe9, 0x808f, 0xbe2, 0x808e, - 0xbdc, 0x808e, 0xbd6, 0x808d, 0xbd0, 0x808c, 0xbc9, 0x808c, - 0xbc3, 0x808b, 0xbbd, 0x808b, 0xbb7, 0x808a, 0xbb0, 0x8089, - 0xbaa, 0x8089, 0xba4, 0x8088, 0xb9e, 0x8088, 0xb97, 0x8087, - 0xb91, 0x8087, 0xb8b, 0x8086, 0xb85, 0x8085, 0xb7e, 0x8085, - 0xb78, 0x8084, 0xb72, 0x8084, 0xb6c, 0x8083, 0xb65, 0x8083, - 0xb5f, 0x8082, 0xb59, 0x8082, 0xb53, 0x8081, 0xb4c, 0x8080, - 0xb46, 0x8080, 0xb40, 0x807f, 0xb3a, 0x807f, 0xb33, 0x807e, - 0xb2d, 0x807e, 0xb27, 0x807d, 0xb20, 0x807d, 0xb1a, 0x807c, - 0xb14, 0x807b, 0xb0e, 0x807b, 0xb07, 0x807a, 0xb01, 0x807a, - 0xafb, 0x8079, 0xaf5, 0x8079, 0xaee, 0x8078, 0xae8, 0x8078, - 0xae2, 0x8077, 0xadc, 0x8077, 0xad5, 0x8076, 0xacf, 0x8076, - 0xac9, 0x8075, 0xac3, 0x8075, 0xabc, 0x8074, 0xab6, 0x8073, - 0xab0, 0x8073, 0xaaa, 0x8072, 0xaa3, 0x8072, 0xa9d, 0x8071, - 0xa97, 0x8071, 0xa90, 0x8070, 0xa8a, 0x8070, 0xa84, 0x806f, - 0xa7e, 0x806f, 0xa77, 0x806e, 0xa71, 0x806e, 0xa6b, 0x806d, - 0xa65, 0x806d, 0xa5e, 0x806c, 0xa58, 0x806c, 0xa52, 0x806b, - 0xa4c, 0x806b, 0xa45, 0x806a, 0xa3f, 0x806a, 0xa39, 0x8069, - 0xa33, 0x8069, 0xa2c, 0x8068, 0xa26, 0x8068, 0xa20, 0x8067, - 0xa19, 0x8067, 0xa13, 0x8066, 0xa0d, 0x8066, 0xa07, 0x8065, - 0xa00, 0x8065, 0x9fa, 0x8064, 0x9f4, 0x8064, 0x9ee, 0x8063, - 0x9e7, 0x8063, 0x9e1, 0x8062, 0x9db, 0x8062, 0x9d5, 0x8061, - 0x9ce, 0x8061, 0x9c8, 0x8060, 0x9c2, 0x8060, 0x9bc, 0x805f, - 0x9b5, 0x805f, 0x9af, 0x805e, 0x9a9, 0x805e, 0x9a2, 0x805d, - 0x99c, 0x805d, 0x996, 0x805d, 0x990, 0x805c, 0x989, 0x805c, - 0x983, 0x805b, 0x97d, 0x805b, 0x977, 0x805a, 0x970, 0x805a, - 0x96a, 0x8059, 0x964, 0x8059, 0x95e, 0x8058, 0x957, 0x8058, - 0x951, 0x8057, 0x94b, 0x8057, 0x944, 0x8057, 0x93e, 0x8056, - 0x938, 0x8056, 0x932, 0x8055, 0x92b, 0x8055, 0x925, 0x8054, - 0x91f, 0x8054, 0x919, 0x8053, 0x912, 0x8053, 0x90c, 0x8052, - 0x906, 0x8052, 0x900, 0x8052, 0x8f9, 0x8051, 0x8f3, 0x8051, - 0x8ed, 0x8050, 0x8e6, 0x8050, 0x8e0, 0x804f, 0x8da, 0x804f, - 0x8d4, 0x804f, 0x8cd, 0x804e, 0x8c7, 0x804e, 0x8c1, 0x804d, - 0x8bb, 0x804d, 0x8b4, 0x804c, 0x8ae, 0x804c, 0x8a8, 0x804c, - 0x8a2, 0x804b, 0x89b, 0x804b, 0x895, 0x804a, 0x88f, 0x804a, - 0x888, 0x8049, 0x882, 0x8049, 0x87c, 0x8049, 0x876, 0x8048, - 0x86f, 0x8048, 0x869, 0x8047, 0x863, 0x8047, 0x85d, 0x8047, - 0x856, 0x8046, 0x850, 0x8046, 0x84a, 0x8045, 0x843, 0x8045, - 0x83d, 0x8044, 0x837, 0x8044, 0x831, 0x8044, 0x82a, 0x8043, - 0x824, 0x8043, 0x81e, 0x8042, 0x818, 0x8042, 0x811, 0x8042, - 0x80b, 0x8041, 0x805, 0x8041, 0x7fe, 0x8040, 0x7f8, 0x8040, - 0x7f2, 0x8040, 0x7ec, 0x803f, 0x7e5, 0x803f, 0x7df, 0x803f, - 0x7d9, 0x803e, 0x7d3, 0x803e, 0x7cc, 0x803d, 0x7c6, 0x803d, - 0x7c0, 0x803d, 0x7ba, 0x803c, 0x7b3, 0x803c, 0x7ad, 0x803b, - 0x7a7, 0x803b, 0x7a0, 0x803b, 0x79a, 0x803a, 0x794, 0x803a, - 0x78e, 0x803a, 0x787, 0x8039, 0x781, 0x8039, 0x77b, 0x8039, - 0x775, 0x8038, 0x76e, 0x8038, 0x768, 0x8037, 0x762, 0x8037, - 0x75b, 0x8037, 0x755, 0x8036, 0x74f, 0x8036, 0x749, 0x8036, - 0x742, 0x8035, 0x73c, 0x8035, 0x736, 0x8035, 0x730, 0x8034, - 0x729, 0x8034, 0x723, 0x8033, 0x71d, 0x8033, 0x716, 0x8033, - 0x710, 0x8032, 0x70a, 0x8032, 0x704, 0x8032, 0x6fd, 0x8031, - 0x6f7, 0x8031, 0x6f1, 0x8031, 0x6ea, 0x8030, 0x6e4, 0x8030, - 0x6de, 0x8030, 0x6d8, 0x802f, 0x6d1, 0x802f, 0x6cb, 0x802f, - 0x6c5, 0x802e, 0x6bf, 0x802e, 0x6b8, 0x802e, 0x6b2, 0x802d, - 0x6ac, 0x802d, 0x6a5, 0x802d, 0x69f, 0x802c, 0x699, 0x802c, - 0x693, 0x802c, 0x68c, 0x802b, 0x686, 0x802b, 0x680, 0x802b, - 0x67a, 0x802a, 0x673, 0x802a, 0x66d, 0x802a, 0x667, 0x802a, - 0x660, 0x8029, 0x65a, 0x8029, 0x654, 0x8029, 0x64e, 0x8028, - 0x647, 0x8028, 0x641, 0x8028, 0x63b, 0x8027, 0x635, 0x8027, - 0x62e, 0x8027, 0x628, 0x8026, 0x622, 0x8026, 0x61b, 0x8026, - 0x615, 0x8026, 0x60f, 0x8025, 0x609, 0x8025, 0x602, 0x8025, - 0x5fc, 0x8024, 0x5f6, 0x8024, 0x5ef, 0x8024, 0x5e9, 0x8023, - 0x5e3, 0x8023, 0x5dd, 0x8023, 0x5d6, 0x8023, 0x5d0, 0x8022, - 0x5ca, 0x8022, 0x5c4, 0x8022, 0x5bd, 0x8021, 0x5b7, 0x8021, - 0x5b1, 0x8021, 0x5aa, 0x8021, 0x5a4, 0x8020, 0x59e, 0x8020, - 0x598, 0x8020, 0x591, 0x8020, 0x58b, 0x801f, 0x585, 0x801f, - 0x57f, 0x801f, 0x578, 0x801e, 0x572, 0x801e, 0x56c, 0x801e, - 0x565, 0x801e, 0x55f, 0x801d, 0x559, 0x801d, 0x553, 0x801d, - 0x54c, 0x801d, 0x546, 0x801c, 0x540, 0x801c, 0x539, 0x801c, - 0x533, 0x801c, 0x52d, 0x801b, 0x527, 0x801b, 0x520, 0x801b, - 0x51a, 0x801b, 0x514, 0x801a, 0x50d, 0x801a, 0x507, 0x801a, - 0x501, 0x801a, 0x4fb, 0x8019, 0x4f4, 0x8019, 0x4ee, 0x8019, - 0x4e8, 0x8019, 0x4e2, 0x8018, 0x4db, 0x8018, 0x4d5, 0x8018, - 0x4cf, 0x8018, 0x4c8, 0x8017, 0x4c2, 0x8017, 0x4bc, 0x8017, - 0x4b6, 0x8017, 0x4af, 0x8016, 0x4a9, 0x8016, 0x4a3, 0x8016, - 0x49c, 0x8016, 0x496, 0x8016, 0x490, 0x8015, 0x48a, 0x8015, - 0x483, 0x8015, 0x47d, 0x8015, 0x477, 0x8014, 0x471, 0x8014, - 0x46a, 0x8014, 0x464, 0x8014, 0x45e, 0x8014, 0x457, 0x8013, - 0x451, 0x8013, 0x44b, 0x8013, 0x445, 0x8013, 0x43e, 0x8013, - 0x438, 0x8012, 0x432, 0x8012, 0x42b, 0x8012, 0x425, 0x8012, - 0x41f, 0x8012, 0x419, 0x8011, 0x412, 0x8011, 0x40c, 0x8011, - 0x406, 0x8011, 0x3ff, 0x8011, 0x3f9, 0x8010, 0x3f3, 0x8010, - 0x3ed, 0x8010, 0x3e6, 0x8010, 0x3e0, 0x8010, 0x3da, 0x800f, - 0x3d4, 0x800f, 0x3cd, 0x800f, 0x3c7, 0x800f, 0x3c1, 0x800f, - 0x3ba, 0x800e, 0x3b4, 0x800e, 0x3ae, 0x800e, 0x3a8, 0x800e, - 0x3a1, 0x800e, 0x39b, 0x800e, 0x395, 0x800d, 0x38e, 0x800d, - 0x388, 0x800d, 0x382, 0x800d, 0x37c, 0x800d, 0x375, 0x800c, - 0x36f, 0x800c, 0x369, 0x800c, 0x362, 0x800c, 0x35c, 0x800c, - 0x356, 0x800c, 0x350, 0x800b, 0x349, 0x800b, 0x343, 0x800b, - 0x33d, 0x800b, 0x337, 0x800b, 0x330, 0x800b, 0x32a, 0x800b, - 0x324, 0x800a, 0x31d, 0x800a, 0x317, 0x800a, 0x311, 0x800a, - 0x30b, 0x800a, 0x304, 0x800a, 0x2fe, 0x8009, 0x2f8, 0x8009, - 0x2f1, 0x8009, 0x2eb, 0x8009, 0x2e5, 0x8009, 0x2df, 0x8009, - 0x2d8, 0x8009, 0x2d2, 0x8008, 0x2cc, 0x8008, 0x2c5, 0x8008, - 0x2bf, 0x8008, 0x2b9, 0x8008, 0x2b3, 0x8008, 0x2ac, 0x8008, - 0x2a6, 0x8008, 0x2a0, 0x8007, 0x299, 0x8007, 0x293, 0x8007, - 0x28d, 0x8007, 0x287, 0x8007, 0x280, 0x8007, 0x27a, 0x8007, - 0x274, 0x8007, 0x26d, 0x8006, 0x267, 0x8006, 0x261, 0x8006, - 0x25b, 0x8006, 0x254, 0x8006, 0x24e, 0x8006, 0x248, 0x8006, - 0x242, 0x8006, 0x23b, 0x8005, 0x235, 0x8005, 0x22f, 0x8005, - 0x228, 0x8005, 0x222, 0x8005, 0x21c, 0x8005, 0x216, 0x8005, - 0x20f, 0x8005, 0x209, 0x8005, 0x203, 0x8005, 0x1fc, 0x8004, - 0x1f6, 0x8004, 0x1f0, 0x8004, 0x1ea, 0x8004, 0x1e3, 0x8004, - 0x1dd, 0x8004, 0x1d7, 0x8004, 0x1d0, 0x8004, 0x1ca, 0x8004, - 0x1c4, 0x8004, 0x1be, 0x8004, 0x1b7, 0x8003, 0x1b1, 0x8003, - 0x1ab, 0x8003, 0x1a4, 0x8003, 0x19e, 0x8003, 0x198, 0x8003, - 0x192, 0x8003, 0x18b, 0x8003, 0x185, 0x8003, 0x17f, 0x8003, - 0x178, 0x8003, 0x172, 0x8003, 0x16c, 0x8003, 0x166, 0x8002, - 0x15f, 0x8002, 0x159, 0x8002, 0x153, 0x8002, 0x14d, 0x8002, - 0x146, 0x8002, 0x140, 0x8002, 0x13a, 0x8002, 0x133, 0x8002, - 0x12d, 0x8002, 0x127, 0x8002, 0x121, 0x8002, 0x11a, 0x8002, - 0x114, 0x8002, 0x10e, 0x8002, 0x107, 0x8002, 0x101, 0x8002, - 0xfb, 0x8001, 0xf5, 0x8001, 0xee, 0x8001, 0xe8, 0x8001, - 0xe2, 0x8001, 0xdb, 0x8001, 0xd5, 0x8001, 0xcf, 0x8001, - 0xc9, 0x8001, 0xc2, 0x8001, 0xbc, 0x8001, 0xb6, 0x8001, - 0xaf, 0x8001, 0xa9, 0x8001, 0xa3, 0x8001, 0x9d, 0x8001, - 0x96, 0x8001, 0x90, 0x8001, 0x8a, 0x8001, 0x83, 0x8001, - 0x7d, 0x8001, 0x77, 0x8001, 0x71, 0x8001, 0x6a, 0x8001, - 0x64, 0x8001, 0x5e, 0x8001, 0x57, 0x8001, 0x51, 0x8001, - 0x4b, 0x8001, 0x45, 0x8001, 0x3e, 0x8001, 0x38, 0x8001, - 0x32, 0x8001, 0x2b, 0x8001, 0x25, 0x8001, 0x1f, 0x8001, - 0x19, 0x8001, 0x12, 0x8001, 0xc, 0x8001, 0x6, 0x8001, -}; - - -/** -* \par -* cosFactor tables are generated using the formula :
 cos_factors[n] = 2 * cos((2n+1)*pi/(4*N)) 
-* \par -* C command to generate the table -*
    
-* for(i = 0; i< N; i++)    
-* {    
-*   cos_factors[i]= 2 * cos((2*i+1)*c/2);    
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -* \par -* Then converted to q15 format by multiplying with 2^31 and saturated if required. - -*/ - -static const q15_t ALIGN4 cos_factorsQ15_128[128] = { - 0x7fff, 0x7ffa, 0x7ff0, 0x7fe1, 0x7fce, 0x7fb5, 0x7f97, 0x7f75, - 0x7f4d, 0x7f21, 0x7ef0, 0x7eba, 0x7e7f, 0x7e3f, 0x7dfa, 0x7db0, - 0x7d62, 0x7d0f, 0x7cb7, 0x7c5a, 0x7bf8, 0x7b92, 0x7b26, 0x7ab6, - 0x7a42, 0x79c8, 0x794a, 0x78c7, 0x7840, 0x77b4, 0x7723, 0x768e, - 0x75f4, 0x7555, 0x74b2, 0x740b, 0x735f, 0x72af, 0x71fa, 0x7141, - 0x7083, 0x6fc1, 0x6efb, 0x6e30, 0x6d62, 0x6c8f, 0x6bb8, 0x6adc, - 0x69fd, 0x6919, 0x6832, 0x6746, 0x6657, 0x6563, 0x646c, 0x6371, - 0x6271, 0x616f, 0x6068, 0x5f5e, 0x5e50, 0x5d3e, 0x5c29, 0x5b10, - 0x59f3, 0x58d4, 0x57b0, 0x568a, 0x5560, 0x5433, 0x5302, 0x51ce, - 0x5097, 0x4f5e, 0x4e21, 0x4ce1, 0x4b9e, 0x4a58, 0x490f, 0x47c3, - 0x4675, 0x4524, 0x43d0, 0x427a, 0x4121, 0x3fc5, 0x3e68, 0x3d07, - 0x3ba5, 0x3a40, 0x38d8, 0x376f, 0x3604, 0x3496, 0x3326, 0x31b5, - 0x3041, 0x2ecc, 0x2d55, 0x2bdc, 0x2a61, 0x28e5, 0x2767, 0x25e8, - 0x2467, 0x22e5, 0x2161, 0x1fdc, 0x1e56, 0x1ccf, 0x1b47, 0x19bd, - 0x1833, 0x16a8, 0x151b, 0x138e, 0x1201, 0x1072, 0xee3, 0xd53, - 0xbc3, 0xa33, 0x8a2, 0x710, 0x57f, 0x3ed, 0x25b, 0xc9 -}; - -static const q15_t ALIGN4 cos_factorsQ15_512[512] = { - 0x7fff, 0x7fff, 0x7fff, 0x7ffe, 0x7ffc, 0x7ffb, 0x7ff9, 0x7ff7, - 0x7ff4, 0x7ff2, 0x7fee, 0x7feb, 0x7fe7, 0x7fe3, 0x7fdf, 0x7fda, - 0x7fd6, 0x7fd0, 0x7fcb, 0x7fc5, 0x7fbf, 0x7fb8, 0x7fb1, 0x7faa, - 0x7fa3, 0x7f9b, 0x7f93, 0x7f8b, 0x7f82, 0x7f79, 0x7f70, 0x7f67, - 0x7f5d, 0x7f53, 0x7f48, 0x7f3d, 0x7f32, 0x7f27, 0x7f1b, 0x7f0f, - 0x7f03, 0x7ef6, 0x7ee9, 0x7edc, 0x7ecf, 0x7ec1, 0x7eb3, 0x7ea4, - 0x7e95, 0x7e86, 0x7e77, 0x7e67, 0x7e57, 0x7e47, 0x7e37, 0x7e26, - 0x7e14, 0x7e03, 0x7df1, 0x7ddf, 0x7dcd, 0x7dba, 0x7da7, 0x7d94, - 0x7d80, 0x7d6c, 0x7d58, 0x7d43, 0x7d2f, 0x7d19, 0x7d04, 0x7cee, - 0x7cd8, 0x7cc2, 0x7cab, 0x7c94, 0x7c7d, 0x7c66, 0x7c4e, 0x7c36, - 0x7c1d, 0x7c05, 0x7beb, 0x7bd2, 0x7bb9, 0x7b9f, 0x7b84, 0x7b6a, - 0x7b4f, 0x7b34, 0x7b19, 0x7afd, 0x7ae1, 0x7ac5, 0x7aa8, 0x7a8b, - 0x7a6e, 0x7a50, 0x7a33, 0x7a15, 0x79f6, 0x79d8, 0x79b9, 0x7999, - 0x797a, 0x795a, 0x793a, 0x7919, 0x78f9, 0x78d8, 0x78b6, 0x7895, - 0x7873, 0x7851, 0x782e, 0x780c, 0x77e9, 0x77c5, 0x77a2, 0x777e, - 0x775a, 0x7735, 0x7710, 0x76eb, 0x76c6, 0x76a0, 0x767b, 0x7654, - 0x762e, 0x7607, 0x75e0, 0x75b9, 0x7591, 0x7569, 0x7541, 0x7519, - 0x74f0, 0x74c7, 0x749e, 0x7474, 0x744a, 0x7420, 0x73f6, 0x73cb, - 0x73a0, 0x7375, 0x7349, 0x731d, 0x72f1, 0x72c5, 0x7298, 0x726b, - 0x723e, 0x7211, 0x71e3, 0x71b5, 0x7186, 0x7158, 0x7129, 0x70fa, - 0x70cb, 0x709b, 0x706b, 0x703b, 0x700a, 0x6fda, 0x6fa9, 0x6f77, - 0x6f46, 0x6f14, 0x6ee2, 0x6eaf, 0x6e7d, 0x6e4a, 0x6e17, 0x6de3, - 0x6db0, 0x6d7c, 0x6d48, 0x6d13, 0x6cde, 0x6ca9, 0x6c74, 0x6c3f, - 0x6c09, 0x6bd3, 0x6b9c, 0x6b66, 0x6b2f, 0x6af8, 0x6ac1, 0x6a89, - 0x6a51, 0x6a19, 0x69e1, 0x69a8, 0x696f, 0x6936, 0x68fd, 0x68c3, - 0x6889, 0x684f, 0x6815, 0x67da, 0x679f, 0x6764, 0x6729, 0x66ed, - 0x66b1, 0x6675, 0x6639, 0x65fc, 0x65bf, 0x6582, 0x6545, 0x6507, - 0x64c9, 0x648b, 0x644d, 0x640e, 0x63cf, 0x6390, 0x6351, 0x6311, - 0x62d2, 0x6292, 0x6251, 0x6211, 0x61d0, 0x618f, 0x614e, 0x610d, - 0x60cb, 0x6089, 0x6047, 0x6004, 0x5fc2, 0x5f7f, 0x5f3c, 0x5ef9, - 0x5eb5, 0x5e71, 0x5e2d, 0x5de9, 0x5da5, 0x5d60, 0x5d1b, 0x5cd6, - 0x5c91, 0x5c4b, 0x5c06, 0x5bc0, 0x5b79, 0x5b33, 0x5aec, 0x5aa5, - 0x5a5e, 0x5a17, 0x59d0, 0x5988, 0x5940, 0x58f8, 0x58af, 0x5867, - 0x581e, 0x57d5, 0x578c, 0x5742, 0x56f9, 0x56af, 0x5665, 0x561a, - 0x55d0, 0x5585, 0x553a, 0x54ef, 0x54a4, 0x5458, 0x540d, 0x53c1, - 0x5375, 0x5328, 0x52dc, 0x528f, 0x5242, 0x51f5, 0x51a8, 0x515a, - 0x510c, 0x50bf, 0x5070, 0x5022, 0x4fd4, 0x4f85, 0x4f36, 0x4ee7, - 0x4e98, 0x4e48, 0x4df9, 0x4da9, 0x4d59, 0x4d09, 0x4cb8, 0x4c68, - 0x4c17, 0x4bc6, 0x4b75, 0x4b24, 0x4ad2, 0x4a81, 0x4a2f, 0x49dd, - 0x498a, 0x4938, 0x48e6, 0x4893, 0x4840, 0x47ed, 0x479a, 0x4746, - 0x46f3, 0x469f, 0x464b, 0x45f7, 0x45a3, 0x454e, 0x44fa, 0x44a5, - 0x4450, 0x43fb, 0x43a5, 0x4350, 0x42fa, 0x42a5, 0x424f, 0x41f9, - 0x41a2, 0x414c, 0x40f6, 0x409f, 0x4048, 0x3ff1, 0x3f9a, 0x3f43, - 0x3eeb, 0x3e93, 0x3e3c, 0x3de4, 0x3d8c, 0x3d33, 0x3cdb, 0x3c83, - 0x3c2a, 0x3bd1, 0x3b78, 0x3b1f, 0x3ac6, 0x3a6c, 0x3a13, 0x39b9, - 0x395f, 0x3906, 0x38ab, 0x3851, 0x37f7, 0x379c, 0x3742, 0x36e7, - 0x368c, 0x3631, 0x35d6, 0x357b, 0x351f, 0x34c4, 0x3468, 0x340c, - 0x33b0, 0x3354, 0x32f8, 0x329c, 0x3240, 0x31e3, 0x3186, 0x312a, - 0x30cd, 0x3070, 0x3013, 0x2fb5, 0x2f58, 0x2efb, 0x2e9d, 0x2e3f, - 0x2de2, 0x2d84, 0x2d26, 0x2cc8, 0x2c69, 0x2c0b, 0x2bad, 0x2b4e, - 0x2aef, 0x2a91, 0x2a32, 0x29d3, 0x2974, 0x2915, 0x28b5, 0x2856, - 0x27f6, 0x2797, 0x2737, 0x26d8, 0x2678, 0x2618, 0x25b8, 0x2558, - 0x24f7, 0x2497, 0x2437, 0x23d6, 0x2376, 0x2315, 0x22b4, 0x2254, - 0x21f3, 0x2192, 0x2131, 0x20d0, 0x206e, 0x200d, 0x1fac, 0x1f4a, - 0x1ee9, 0x1e87, 0x1e25, 0x1dc4, 0x1d62, 0x1d00, 0x1c9e, 0x1c3c, - 0x1bda, 0x1b78, 0x1b16, 0x1ab3, 0x1a51, 0x19ef, 0x198c, 0x192a, - 0x18c7, 0x1864, 0x1802, 0x179f, 0x173c, 0x16d9, 0x1676, 0x1613, - 0x15b0, 0x154d, 0x14ea, 0x1487, 0x1423, 0x13c0, 0x135d, 0x12f9, - 0x1296, 0x1232, 0x11cf, 0x116b, 0x1108, 0x10a4, 0x1040, 0xfdd, - 0xf79, 0xf15, 0xeb1, 0xe4d, 0xde9, 0xd85, 0xd21, 0xcbd, - 0xc59, 0xbf5, 0xb91, 0xb2d, 0xac9, 0xa65, 0xa00, 0x99c, - 0x938, 0x8d4, 0x86f, 0x80b, 0x7a7, 0x742, 0x6de, 0x67a, - 0x615, 0x5b1, 0x54c, 0x4e8, 0x483, 0x41f, 0x3ba, 0x356, - 0x2f1, 0x28d, 0x228, 0x1c4, 0x15f, 0xfb, 0x96, 0x32, -}; - -static const q15_t ALIGN4 cos_factorsQ15_2048[2048] = { - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffd, 0x7ffd, - 0x7ffd, 0x7ffd, 0x7ffc, 0x7ffc, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffa, - 0x7ffa, 0x7ff9, 0x7ff9, 0x7ff8, 0x7ff8, 0x7ff7, 0x7ff7, 0x7ff6, - 0x7ff5, 0x7ff5, 0x7ff4, 0x7ff3, 0x7ff3, 0x7ff2, 0x7ff1, 0x7ff0, - 0x7ff0, 0x7fef, 0x7fee, 0x7fed, 0x7fec, 0x7fec, 0x7feb, 0x7fea, - 0x7fe9, 0x7fe8, 0x7fe7, 0x7fe6, 0x7fe5, 0x7fe4, 0x7fe3, 0x7fe2, - 0x7fe1, 0x7fe0, 0x7fdf, 0x7fdd, 0x7fdc, 0x7fdb, 0x7fda, 0x7fd9, - 0x7fd7, 0x7fd6, 0x7fd5, 0x7fd4, 0x7fd2, 0x7fd1, 0x7fd0, 0x7fce, - 0x7fcd, 0x7fcb, 0x7fca, 0x7fc9, 0x7fc7, 0x7fc6, 0x7fc4, 0x7fc3, - 0x7fc1, 0x7fc0, 0x7fbe, 0x7fbc, 0x7fbb, 0x7fb9, 0x7fb7, 0x7fb6, - 0x7fb4, 0x7fb2, 0x7fb1, 0x7faf, 0x7fad, 0x7fab, 0x7fa9, 0x7fa8, - 0x7fa6, 0x7fa4, 0x7fa2, 0x7fa0, 0x7f9e, 0x7f9c, 0x7f9a, 0x7f98, - 0x7f96, 0x7f94, 0x7f92, 0x7f90, 0x7f8e, 0x7f8c, 0x7f8a, 0x7f88, - 0x7f86, 0x7f83, 0x7f81, 0x7f7f, 0x7f7d, 0x7f7b, 0x7f78, 0x7f76, - 0x7f74, 0x7f71, 0x7f6f, 0x7f6d, 0x7f6a, 0x7f68, 0x7f65, 0x7f63, - 0x7f60, 0x7f5e, 0x7f5b, 0x7f59, 0x7f56, 0x7f54, 0x7f51, 0x7f4f, - 0x7f4c, 0x7f49, 0x7f47, 0x7f44, 0x7f41, 0x7f3f, 0x7f3c, 0x7f39, - 0x7f36, 0x7f34, 0x7f31, 0x7f2e, 0x7f2b, 0x7f28, 0x7f25, 0x7f23, - 0x7f20, 0x7f1d, 0x7f1a, 0x7f17, 0x7f14, 0x7f11, 0x7f0e, 0x7f0b, - 0x7f08, 0x7f04, 0x7f01, 0x7efe, 0x7efb, 0x7ef8, 0x7ef5, 0x7ef1, - 0x7eee, 0x7eeb, 0x7ee8, 0x7ee4, 0x7ee1, 0x7ede, 0x7eda, 0x7ed7, - 0x7ed4, 0x7ed0, 0x7ecd, 0x7ec9, 0x7ec6, 0x7ec3, 0x7ebf, 0x7ebb, - 0x7eb8, 0x7eb4, 0x7eb1, 0x7ead, 0x7eaa, 0x7ea6, 0x7ea2, 0x7e9f, - 0x7e9b, 0x7e97, 0x7e94, 0x7e90, 0x7e8c, 0x7e88, 0x7e84, 0x7e81, - 0x7e7d, 0x7e79, 0x7e75, 0x7e71, 0x7e6d, 0x7e69, 0x7e65, 0x7e61, - 0x7e5d, 0x7e59, 0x7e55, 0x7e51, 0x7e4d, 0x7e49, 0x7e45, 0x7e41, - 0x7e3d, 0x7e39, 0x7e34, 0x7e30, 0x7e2c, 0x7e28, 0x7e24, 0x7e1f, - 0x7e1b, 0x7e17, 0x7e12, 0x7e0e, 0x7e0a, 0x7e05, 0x7e01, 0x7dfc, - 0x7df8, 0x7df3, 0x7def, 0x7dea, 0x7de6, 0x7de1, 0x7ddd, 0x7dd8, - 0x7dd4, 0x7dcf, 0x7dca, 0x7dc6, 0x7dc1, 0x7dbc, 0x7db8, 0x7db3, - 0x7dae, 0x7da9, 0x7da5, 0x7da0, 0x7d9b, 0x7d96, 0x7d91, 0x7d8c, - 0x7d87, 0x7d82, 0x7d7e, 0x7d79, 0x7d74, 0x7d6f, 0x7d6a, 0x7d65, - 0x7d60, 0x7d5a, 0x7d55, 0x7d50, 0x7d4b, 0x7d46, 0x7d41, 0x7d3c, - 0x7d36, 0x7d31, 0x7d2c, 0x7d27, 0x7d21, 0x7d1c, 0x7d17, 0x7d11, - 0x7d0c, 0x7d07, 0x7d01, 0x7cfc, 0x7cf6, 0x7cf1, 0x7cec, 0x7ce6, - 0x7ce1, 0x7cdb, 0x7cd5, 0x7cd0, 0x7cca, 0x7cc5, 0x7cbf, 0x7cb9, - 0x7cb4, 0x7cae, 0x7ca8, 0x7ca3, 0x7c9d, 0x7c97, 0x7c91, 0x7c8c, - 0x7c86, 0x7c80, 0x7c7a, 0x7c74, 0x7c6e, 0x7c69, 0x7c63, 0x7c5d, - 0x7c57, 0x7c51, 0x7c4b, 0x7c45, 0x7c3f, 0x7c39, 0x7c33, 0x7c2d, - 0x7c26, 0x7c20, 0x7c1a, 0x7c14, 0x7c0e, 0x7c08, 0x7c01, 0x7bfb, - 0x7bf5, 0x7bef, 0x7be8, 0x7be2, 0x7bdc, 0x7bd5, 0x7bcf, 0x7bc9, - 0x7bc2, 0x7bbc, 0x7bb5, 0x7baf, 0x7ba8, 0x7ba2, 0x7b9b, 0x7b95, - 0x7b8e, 0x7b88, 0x7b81, 0x7b7a, 0x7b74, 0x7b6d, 0x7b67, 0x7b60, - 0x7b59, 0x7b52, 0x7b4c, 0x7b45, 0x7b3e, 0x7b37, 0x7b31, 0x7b2a, - 0x7b23, 0x7b1c, 0x7b15, 0x7b0e, 0x7b07, 0x7b00, 0x7af9, 0x7af2, - 0x7aeb, 0x7ae4, 0x7add, 0x7ad6, 0x7acf, 0x7ac8, 0x7ac1, 0x7aba, - 0x7ab3, 0x7aac, 0x7aa4, 0x7a9d, 0x7a96, 0x7a8f, 0x7a87, 0x7a80, - 0x7a79, 0x7a72, 0x7a6a, 0x7a63, 0x7a5c, 0x7a54, 0x7a4d, 0x7a45, - 0x7a3e, 0x7a36, 0x7a2f, 0x7a27, 0x7a20, 0x7a18, 0x7a11, 0x7a09, - 0x7a02, 0x79fa, 0x79f2, 0x79eb, 0x79e3, 0x79db, 0x79d4, 0x79cc, - 0x79c4, 0x79bc, 0x79b5, 0x79ad, 0x79a5, 0x799d, 0x7995, 0x798e, - 0x7986, 0x797e, 0x7976, 0x796e, 0x7966, 0x795e, 0x7956, 0x794e, - 0x7946, 0x793e, 0x7936, 0x792e, 0x7926, 0x791e, 0x7915, 0x790d, - 0x7905, 0x78fd, 0x78f5, 0x78ec, 0x78e4, 0x78dc, 0x78d4, 0x78cb, - 0x78c3, 0x78bb, 0x78b2, 0x78aa, 0x78a2, 0x7899, 0x7891, 0x7888, - 0x7880, 0x7877, 0x786f, 0x7866, 0x785e, 0x7855, 0x784d, 0x7844, - 0x783b, 0x7833, 0x782a, 0x7821, 0x7819, 0x7810, 0x7807, 0x77ff, - 0x77f6, 0x77ed, 0x77e4, 0x77db, 0x77d3, 0x77ca, 0x77c1, 0x77b8, - 0x77af, 0x77a6, 0x779d, 0x7794, 0x778b, 0x7782, 0x7779, 0x7770, - 0x7767, 0x775e, 0x7755, 0x774c, 0x7743, 0x773a, 0x7731, 0x7727, - 0x771e, 0x7715, 0x770c, 0x7703, 0x76f9, 0x76f0, 0x76e7, 0x76dd, - 0x76d4, 0x76cb, 0x76c1, 0x76b8, 0x76af, 0x76a5, 0x769c, 0x7692, - 0x7689, 0x767f, 0x7676, 0x766c, 0x7663, 0x7659, 0x7650, 0x7646, - 0x763c, 0x7633, 0x7629, 0x761f, 0x7616, 0x760c, 0x7602, 0x75f9, - 0x75ef, 0x75e5, 0x75db, 0x75d1, 0x75c8, 0x75be, 0x75b4, 0x75aa, - 0x75a0, 0x7596, 0x758c, 0x7582, 0x7578, 0x756e, 0x7564, 0x755a, - 0x7550, 0x7546, 0x753c, 0x7532, 0x7528, 0x751e, 0x7514, 0x7509, - 0x74ff, 0x74f5, 0x74eb, 0x74e1, 0x74d6, 0x74cc, 0x74c2, 0x74b7, - 0x74ad, 0x74a3, 0x7498, 0x748e, 0x7484, 0x7479, 0x746f, 0x7464, - 0x745a, 0x744f, 0x7445, 0x743a, 0x7430, 0x7425, 0x741b, 0x7410, - 0x7406, 0x73fb, 0x73f0, 0x73e6, 0x73db, 0x73d0, 0x73c6, 0x73bb, - 0x73b0, 0x73a5, 0x739b, 0x7390, 0x7385, 0x737a, 0x736f, 0x7364, - 0x7359, 0x734f, 0x7344, 0x7339, 0x732e, 0x7323, 0x7318, 0x730d, - 0x7302, 0x72f7, 0x72ec, 0x72e1, 0x72d5, 0x72ca, 0x72bf, 0x72b4, - 0x72a9, 0x729e, 0x7293, 0x7287, 0x727c, 0x7271, 0x7266, 0x725a, - 0x724f, 0x7244, 0x7238, 0x722d, 0x7222, 0x7216, 0x720b, 0x71ff, - 0x71f4, 0x71e9, 0x71dd, 0x71d2, 0x71c6, 0x71bb, 0x71af, 0x71a3, - 0x7198, 0x718c, 0x7181, 0x7175, 0x7169, 0x715e, 0x7152, 0x7146, - 0x713b, 0x712f, 0x7123, 0x7117, 0x710c, 0x7100, 0x70f4, 0x70e8, - 0x70dc, 0x70d1, 0x70c5, 0x70b9, 0x70ad, 0x70a1, 0x7095, 0x7089, - 0x707d, 0x7071, 0x7065, 0x7059, 0x704d, 0x7041, 0x7035, 0x7029, - 0x701d, 0x7010, 0x7004, 0x6ff8, 0x6fec, 0x6fe0, 0x6fd3, 0x6fc7, - 0x6fbb, 0x6faf, 0x6fa2, 0x6f96, 0x6f8a, 0x6f7d, 0x6f71, 0x6f65, - 0x6f58, 0x6f4c, 0x6f3f, 0x6f33, 0x6f27, 0x6f1a, 0x6f0e, 0x6f01, - 0x6ef5, 0x6ee8, 0x6edc, 0x6ecf, 0x6ec2, 0x6eb6, 0x6ea9, 0x6e9c, - 0x6e90, 0x6e83, 0x6e76, 0x6e6a, 0x6e5d, 0x6e50, 0x6e44, 0x6e37, - 0x6e2a, 0x6e1d, 0x6e10, 0x6e04, 0x6df7, 0x6dea, 0x6ddd, 0x6dd0, - 0x6dc3, 0x6db6, 0x6da9, 0x6d9c, 0x6d8f, 0x6d82, 0x6d75, 0x6d68, - 0x6d5b, 0x6d4e, 0x6d41, 0x6d34, 0x6d27, 0x6d1a, 0x6d0c, 0x6cff, - 0x6cf2, 0x6ce5, 0x6cd8, 0x6cca, 0x6cbd, 0x6cb0, 0x6ca3, 0x6c95, - 0x6c88, 0x6c7b, 0x6c6d, 0x6c60, 0x6c53, 0x6c45, 0x6c38, 0x6c2a, - 0x6c1d, 0x6c0f, 0x6c02, 0x6bf5, 0x6be7, 0x6bd9, 0x6bcc, 0x6bbe, - 0x6bb1, 0x6ba3, 0x6b96, 0x6b88, 0x6b7a, 0x6b6d, 0x6b5f, 0x6b51, - 0x6b44, 0x6b36, 0x6b28, 0x6b1a, 0x6b0d, 0x6aff, 0x6af1, 0x6ae3, - 0x6ad5, 0x6ac8, 0x6aba, 0x6aac, 0x6a9e, 0x6a90, 0x6a82, 0x6a74, - 0x6a66, 0x6a58, 0x6a4a, 0x6a3c, 0x6a2e, 0x6a20, 0x6a12, 0x6a04, - 0x69f6, 0x69e8, 0x69da, 0x69cb, 0x69bd, 0x69af, 0x69a1, 0x6993, - 0x6985, 0x6976, 0x6968, 0x695a, 0x694b, 0x693d, 0x692f, 0x6921, - 0x6912, 0x6904, 0x68f5, 0x68e7, 0x68d9, 0x68ca, 0x68bc, 0x68ad, - 0x689f, 0x6890, 0x6882, 0x6873, 0x6865, 0x6856, 0x6848, 0x6839, - 0x682b, 0x681c, 0x680d, 0x67ff, 0x67f0, 0x67e1, 0x67d3, 0x67c4, - 0x67b5, 0x67a6, 0x6798, 0x6789, 0x677a, 0x676b, 0x675d, 0x674e, - 0x673f, 0x6730, 0x6721, 0x6712, 0x6703, 0x66f4, 0x66e5, 0x66d6, - 0x66c8, 0x66b9, 0x66aa, 0x669b, 0x668b, 0x667c, 0x666d, 0x665e, - 0x664f, 0x6640, 0x6631, 0x6622, 0x6613, 0x6603, 0x65f4, 0x65e5, - 0x65d6, 0x65c7, 0x65b7, 0x65a8, 0x6599, 0x658a, 0x657a, 0x656b, - 0x655c, 0x654c, 0x653d, 0x652d, 0x651e, 0x650f, 0x64ff, 0x64f0, - 0x64e0, 0x64d1, 0x64c1, 0x64b2, 0x64a2, 0x6493, 0x6483, 0x6474, - 0x6464, 0x6454, 0x6445, 0x6435, 0x6426, 0x6416, 0x6406, 0x63f7, - 0x63e7, 0x63d7, 0x63c7, 0x63b8, 0x63a8, 0x6398, 0x6388, 0x6378, - 0x6369, 0x6359, 0x6349, 0x6339, 0x6329, 0x6319, 0x6309, 0x62f9, - 0x62ea, 0x62da, 0x62ca, 0x62ba, 0x62aa, 0x629a, 0x628a, 0x627a, - 0x6269, 0x6259, 0x6249, 0x6239, 0x6229, 0x6219, 0x6209, 0x61f9, - 0x61e8, 0x61d8, 0x61c8, 0x61b8, 0x61a8, 0x6197, 0x6187, 0x6177, - 0x6166, 0x6156, 0x6146, 0x6135, 0x6125, 0x6115, 0x6104, 0x60f4, - 0x60e4, 0x60d3, 0x60c3, 0x60b2, 0x60a2, 0x6091, 0x6081, 0x6070, - 0x6060, 0x604f, 0x603f, 0x602e, 0x601d, 0x600d, 0x5ffc, 0x5fec, - 0x5fdb, 0x5fca, 0x5fba, 0x5fa9, 0x5f98, 0x5f87, 0x5f77, 0x5f66, - 0x5f55, 0x5f44, 0x5f34, 0x5f23, 0x5f12, 0x5f01, 0x5ef0, 0x5edf, - 0x5ecf, 0x5ebe, 0x5ead, 0x5e9c, 0x5e8b, 0x5e7a, 0x5e69, 0x5e58, - 0x5e47, 0x5e36, 0x5e25, 0x5e14, 0x5e03, 0x5df2, 0x5de1, 0x5dd0, - 0x5dbf, 0x5dad, 0x5d9c, 0x5d8b, 0x5d7a, 0x5d69, 0x5d58, 0x5d46, - 0x5d35, 0x5d24, 0x5d13, 0x5d01, 0x5cf0, 0x5cdf, 0x5cce, 0x5cbc, - 0x5cab, 0x5c9a, 0x5c88, 0x5c77, 0x5c66, 0x5c54, 0x5c43, 0x5c31, - 0x5c20, 0x5c0e, 0x5bfd, 0x5beb, 0x5bda, 0x5bc8, 0x5bb7, 0x5ba5, - 0x5b94, 0x5b82, 0x5b71, 0x5b5f, 0x5b4d, 0x5b3c, 0x5b2a, 0x5b19, - 0x5b07, 0x5af5, 0x5ae4, 0x5ad2, 0x5ac0, 0x5aae, 0x5a9d, 0x5a8b, - 0x5a79, 0x5a67, 0x5a56, 0x5a44, 0x5a32, 0x5a20, 0x5a0e, 0x59fc, - 0x59ea, 0x59d9, 0x59c7, 0x59b5, 0x59a3, 0x5991, 0x597f, 0x596d, - 0x595b, 0x5949, 0x5937, 0x5925, 0x5913, 0x5901, 0x58ef, 0x58dd, - 0x58cb, 0x58b8, 0x58a6, 0x5894, 0x5882, 0x5870, 0x585e, 0x584b, - 0x5839, 0x5827, 0x5815, 0x5803, 0x57f0, 0x57de, 0x57cc, 0x57b9, - 0x57a7, 0x5795, 0x5783, 0x5770, 0x575e, 0x574b, 0x5739, 0x5727, - 0x5714, 0x5702, 0x56ef, 0x56dd, 0x56ca, 0x56b8, 0x56a5, 0x5693, - 0x5680, 0x566e, 0x565b, 0x5649, 0x5636, 0x5624, 0x5611, 0x55fe, - 0x55ec, 0x55d9, 0x55c7, 0x55b4, 0x55a1, 0x558f, 0x557c, 0x5569, - 0x5556, 0x5544, 0x5531, 0x551e, 0x550b, 0x54f9, 0x54e6, 0x54d3, - 0x54c0, 0x54ad, 0x549a, 0x5488, 0x5475, 0x5462, 0x544f, 0x543c, - 0x5429, 0x5416, 0x5403, 0x53f0, 0x53dd, 0x53ca, 0x53b7, 0x53a4, - 0x5391, 0x537e, 0x536b, 0x5358, 0x5345, 0x5332, 0x531f, 0x530c, - 0x52f8, 0x52e5, 0x52d2, 0x52bf, 0x52ac, 0x5299, 0x5285, 0x5272, - 0x525f, 0x524c, 0x5238, 0x5225, 0x5212, 0x51ff, 0x51eb, 0x51d8, - 0x51c5, 0x51b1, 0x519e, 0x518b, 0x5177, 0x5164, 0x5150, 0x513d, - 0x512a, 0x5116, 0x5103, 0x50ef, 0x50dc, 0x50c8, 0x50b5, 0x50a1, - 0x508e, 0x507a, 0x5067, 0x5053, 0x503f, 0x502c, 0x5018, 0x5005, - 0x4ff1, 0x4fdd, 0x4fca, 0x4fb6, 0x4fa2, 0x4f8f, 0x4f7b, 0x4f67, - 0x4f54, 0x4f40, 0x4f2c, 0x4f18, 0x4f05, 0x4ef1, 0x4edd, 0x4ec9, - 0x4eb6, 0x4ea2, 0x4e8e, 0x4e7a, 0x4e66, 0x4e52, 0x4e3e, 0x4e2a, - 0x4e17, 0x4e03, 0x4def, 0x4ddb, 0x4dc7, 0x4db3, 0x4d9f, 0x4d8b, - 0x4d77, 0x4d63, 0x4d4f, 0x4d3b, 0x4d27, 0x4d13, 0x4cff, 0x4ceb, - 0x4cd6, 0x4cc2, 0x4cae, 0x4c9a, 0x4c86, 0x4c72, 0x4c5e, 0x4c49, - 0x4c35, 0x4c21, 0x4c0d, 0x4bf9, 0x4be4, 0x4bd0, 0x4bbc, 0x4ba8, - 0x4b93, 0x4b7f, 0x4b6b, 0x4b56, 0x4b42, 0x4b2e, 0x4b19, 0x4b05, - 0x4af1, 0x4adc, 0x4ac8, 0x4ab4, 0x4a9f, 0x4a8b, 0x4a76, 0x4a62, - 0x4a4d, 0x4a39, 0x4a24, 0x4a10, 0x49fb, 0x49e7, 0x49d2, 0x49be, - 0x49a9, 0x4995, 0x4980, 0x496c, 0x4957, 0x4942, 0x492e, 0x4919, - 0x4905, 0x48f0, 0x48db, 0x48c7, 0x48b2, 0x489d, 0x4888, 0x4874, - 0x485f, 0x484a, 0x4836, 0x4821, 0x480c, 0x47f7, 0x47e2, 0x47ce, - 0x47b9, 0x47a4, 0x478f, 0x477a, 0x4765, 0x4751, 0x473c, 0x4727, - 0x4712, 0x46fd, 0x46e8, 0x46d3, 0x46be, 0x46a9, 0x4694, 0x467f, - 0x466a, 0x4655, 0x4640, 0x462b, 0x4616, 0x4601, 0x45ec, 0x45d7, - 0x45c2, 0x45ad, 0x4598, 0x4583, 0x456e, 0x4559, 0x4544, 0x452e, - 0x4519, 0x4504, 0x44ef, 0x44da, 0x44c5, 0x44af, 0x449a, 0x4485, - 0x4470, 0x445a, 0x4445, 0x4430, 0x441b, 0x4405, 0x43f0, 0x43db, - 0x43c5, 0x43b0, 0x439b, 0x4385, 0x4370, 0x435b, 0x4345, 0x4330, - 0x431b, 0x4305, 0x42f0, 0x42da, 0x42c5, 0x42af, 0x429a, 0x4284, - 0x426f, 0x425a, 0x4244, 0x422f, 0x4219, 0x4203, 0x41ee, 0x41d8, - 0x41c3, 0x41ad, 0x4198, 0x4182, 0x416d, 0x4157, 0x4141, 0x412c, - 0x4116, 0x4100, 0x40eb, 0x40d5, 0x40bf, 0x40aa, 0x4094, 0x407e, - 0x4069, 0x4053, 0x403d, 0x4027, 0x4012, 0x3ffc, 0x3fe6, 0x3fd0, - 0x3fbb, 0x3fa5, 0x3f8f, 0x3f79, 0x3f63, 0x3f4d, 0x3f38, 0x3f22, - 0x3f0c, 0x3ef6, 0x3ee0, 0x3eca, 0x3eb4, 0x3e9e, 0x3e88, 0x3e73, - 0x3e5d, 0x3e47, 0x3e31, 0x3e1b, 0x3e05, 0x3def, 0x3dd9, 0x3dc3, - 0x3dad, 0x3d97, 0x3d81, 0x3d6b, 0x3d55, 0x3d3e, 0x3d28, 0x3d12, - 0x3cfc, 0x3ce6, 0x3cd0, 0x3cba, 0x3ca4, 0x3c8e, 0x3c77, 0x3c61, - 0x3c4b, 0x3c35, 0x3c1f, 0x3c09, 0x3bf2, 0x3bdc, 0x3bc6, 0x3bb0, - 0x3b99, 0x3b83, 0x3b6d, 0x3b57, 0x3b40, 0x3b2a, 0x3b14, 0x3afe, - 0x3ae7, 0x3ad1, 0x3abb, 0x3aa4, 0x3a8e, 0x3a78, 0x3a61, 0x3a4b, - 0x3a34, 0x3a1e, 0x3a08, 0x39f1, 0x39db, 0x39c4, 0x39ae, 0x3998, - 0x3981, 0x396b, 0x3954, 0x393e, 0x3927, 0x3911, 0x38fa, 0x38e4, - 0x38cd, 0x38b7, 0x38a0, 0x388a, 0x3873, 0x385d, 0x3846, 0x382f, - 0x3819, 0x3802, 0x37ec, 0x37d5, 0x37be, 0x37a8, 0x3791, 0x377a, - 0x3764, 0x374d, 0x3736, 0x3720, 0x3709, 0x36f2, 0x36dc, 0x36c5, - 0x36ae, 0x3698, 0x3681, 0x366a, 0x3653, 0x363d, 0x3626, 0x360f, - 0x35f8, 0x35e1, 0x35cb, 0x35b4, 0x359d, 0x3586, 0x356f, 0x3558, - 0x3542, 0x352b, 0x3514, 0x34fd, 0x34e6, 0x34cf, 0x34b8, 0x34a1, - 0x348b, 0x3474, 0x345d, 0x3446, 0x342f, 0x3418, 0x3401, 0x33ea, - 0x33d3, 0x33bc, 0x33a5, 0x338e, 0x3377, 0x3360, 0x3349, 0x3332, - 0x331b, 0x3304, 0x32ed, 0x32d6, 0x32bf, 0x32a8, 0x3290, 0x3279, - 0x3262, 0x324b, 0x3234, 0x321d, 0x3206, 0x31ef, 0x31d8, 0x31c0, - 0x31a9, 0x3192, 0x317b, 0x3164, 0x314c, 0x3135, 0x311e, 0x3107, - 0x30f0, 0x30d8, 0x30c1, 0x30aa, 0x3093, 0x307b, 0x3064, 0x304d, - 0x3036, 0x301e, 0x3007, 0x2ff0, 0x2fd8, 0x2fc1, 0x2faa, 0x2f92, - 0x2f7b, 0x2f64, 0x2f4c, 0x2f35, 0x2f1e, 0x2f06, 0x2eef, 0x2ed8, - 0x2ec0, 0x2ea9, 0x2e91, 0x2e7a, 0x2e63, 0x2e4b, 0x2e34, 0x2e1c, - 0x2e05, 0x2ded, 0x2dd6, 0x2dbe, 0x2da7, 0x2d8f, 0x2d78, 0x2d60, - 0x2d49, 0x2d31, 0x2d1a, 0x2d02, 0x2ceb, 0x2cd3, 0x2cbc, 0x2ca4, - 0x2c8d, 0x2c75, 0x2c5e, 0x2c46, 0x2c2e, 0x2c17, 0x2bff, 0x2be8, - 0x2bd0, 0x2bb8, 0x2ba1, 0x2b89, 0x2b71, 0x2b5a, 0x2b42, 0x2b2b, - 0x2b13, 0x2afb, 0x2ae4, 0x2acc, 0x2ab4, 0x2a9c, 0x2a85, 0x2a6d, - 0x2a55, 0x2a3e, 0x2a26, 0x2a0e, 0x29f6, 0x29df, 0x29c7, 0x29af, - 0x2997, 0x2980, 0x2968, 0x2950, 0x2938, 0x2920, 0x2909, 0x28f1, - 0x28d9, 0x28c1, 0x28a9, 0x2892, 0x287a, 0x2862, 0x284a, 0x2832, - 0x281a, 0x2802, 0x27eb, 0x27d3, 0x27bb, 0x27a3, 0x278b, 0x2773, - 0x275b, 0x2743, 0x272b, 0x2713, 0x26fb, 0x26e4, 0x26cc, 0x26b4, - 0x269c, 0x2684, 0x266c, 0x2654, 0x263c, 0x2624, 0x260c, 0x25f4, - 0x25dc, 0x25c4, 0x25ac, 0x2594, 0x257c, 0x2564, 0x254c, 0x2534, - 0x251c, 0x2503, 0x24eb, 0x24d3, 0x24bb, 0x24a3, 0x248b, 0x2473, - 0x245b, 0x2443, 0x242b, 0x2413, 0x23fa, 0x23e2, 0x23ca, 0x23b2, - 0x239a, 0x2382, 0x236a, 0x2352, 0x2339, 0x2321, 0x2309, 0x22f1, - 0x22d9, 0x22c0, 0x22a8, 0x2290, 0x2278, 0x2260, 0x2247, 0x222f, - 0x2217, 0x21ff, 0x21e7, 0x21ce, 0x21b6, 0x219e, 0x2186, 0x216d, - 0x2155, 0x213d, 0x2125, 0x210c, 0x20f4, 0x20dc, 0x20c3, 0x20ab, - 0x2093, 0x207a, 0x2062, 0x204a, 0x2032, 0x2019, 0x2001, 0x1fe9, - 0x1fd0, 0x1fb8, 0x1f9f, 0x1f87, 0x1f6f, 0x1f56, 0x1f3e, 0x1f26, - 0x1f0d, 0x1ef5, 0x1edd, 0x1ec4, 0x1eac, 0x1e93, 0x1e7b, 0x1e62, - 0x1e4a, 0x1e32, 0x1e19, 0x1e01, 0x1de8, 0x1dd0, 0x1db7, 0x1d9f, - 0x1d87, 0x1d6e, 0x1d56, 0x1d3d, 0x1d25, 0x1d0c, 0x1cf4, 0x1cdb, - 0x1cc3, 0x1caa, 0x1c92, 0x1c79, 0x1c61, 0x1c48, 0x1c30, 0x1c17, - 0x1bff, 0x1be6, 0x1bce, 0x1bb5, 0x1b9d, 0x1b84, 0x1b6c, 0x1b53, - 0x1b3a, 0x1b22, 0x1b09, 0x1af1, 0x1ad8, 0x1ac0, 0x1aa7, 0x1a8e, - 0x1a76, 0x1a5d, 0x1a45, 0x1a2c, 0x1a13, 0x19fb, 0x19e2, 0x19ca, - 0x19b1, 0x1998, 0x1980, 0x1967, 0x194e, 0x1936, 0x191d, 0x1905, - 0x18ec, 0x18d3, 0x18bb, 0x18a2, 0x1889, 0x1871, 0x1858, 0x183f, - 0x1827, 0x180e, 0x17f5, 0x17dd, 0x17c4, 0x17ab, 0x1792, 0x177a, - 0x1761, 0x1748, 0x1730, 0x1717, 0x16fe, 0x16e5, 0x16cd, 0x16b4, - 0x169b, 0x1682, 0x166a, 0x1651, 0x1638, 0x161f, 0x1607, 0x15ee, - 0x15d5, 0x15bc, 0x15a4, 0x158b, 0x1572, 0x1559, 0x1541, 0x1528, - 0x150f, 0x14f6, 0x14dd, 0x14c5, 0x14ac, 0x1493, 0x147a, 0x1461, - 0x1449, 0x1430, 0x1417, 0x13fe, 0x13e5, 0x13cc, 0x13b4, 0x139b, - 0x1382, 0x1369, 0x1350, 0x1337, 0x131f, 0x1306, 0x12ed, 0x12d4, - 0x12bb, 0x12a2, 0x1289, 0x1271, 0x1258, 0x123f, 0x1226, 0x120d, - 0x11f4, 0x11db, 0x11c2, 0x11a9, 0x1191, 0x1178, 0x115f, 0x1146, - 0x112d, 0x1114, 0x10fb, 0x10e2, 0x10c9, 0x10b0, 0x1098, 0x107f, - 0x1066, 0x104d, 0x1034, 0x101b, 0x1002, 0xfe9, 0xfd0, 0xfb7, - 0xf9e, 0xf85, 0xf6c, 0xf53, 0xf3a, 0xf21, 0xf08, 0xef0, - 0xed7, 0xebe, 0xea5, 0xe8c, 0xe73, 0xe5a, 0xe41, 0xe28, - 0xe0f, 0xdf6, 0xddd, 0xdc4, 0xdab, 0xd92, 0xd79, 0xd60, - 0xd47, 0xd2e, 0xd15, 0xcfc, 0xce3, 0xcca, 0xcb1, 0xc98, - 0xc7f, 0xc66, 0xc4d, 0xc34, 0xc1b, 0xc02, 0xbe9, 0xbd0, - 0xbb7, 0xb9e, 0xb85, 0xb6c, 0xb53, 0xb3a, 0xb20, 0xb07, - 0xaee, 0xad5, 0xabc, 0xaa3, 0xa8a, 0xa71, 0xa58, 0xa3f, - 0xa26, 0xa0d, 0x9f4, 0x9db, 0x9c2, 0x9a9, 0x990, 0x977, - 0x95e, 0x944, 0x92b, 0x912, 0x8f9, 0x8e0, 0x8c7, 0x8ae, - 0x895, 0x87c, 0x863, 0x84a, 0x831, 0x818, 0x7fe, 0x7e5, - 0x7cc, 0x7b3, 0x79a, 0x781, 0x768, 0x74f, 0x736, 0x71d, - 0x704, 0x6ea, 0x6d1, 0x6b8, 0x69f, 0x686, 0x66d, 0x654, - 0x63b, 0x622, 0x609, 0x5ef, 0x5d6, 0x5bd, 0x5a4, 0x58b, - 0x572, 0x559, 0x540, 0x527, 0x50d, 0x4f4, 0x4db, 0x4c2, - 0x4a9, 0x490, 0x477, 0x45e, 0x445, 0x42b, 0x412, 0x3f9, - 0x3e0, 0x3c7, 0x3ae, 0x395, 0x37c, 0x362, 0x349, 0x330, - 0x317, 0x2fe, 0x2e5, 0x2cc, 0x2b3, 0x299, 0x280, 0x267, - 0x24e, 0x235, 0x21c, 0x203, 0x1ea, 0x1d0, 0x1b7, 0x19e, - 0x185, 0x16c, 0x153, 0x13a, 0x121, 0x107, 0xee, 0xd5, - 0xbc, 0xa3, 0x8a, 0x71, 0x57, 0x3e, 0x25, 0xc, - -}; - -static const q15_t ALIGN4 cos_factorsQ15_8192[8192] = { - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, 0x7fff, - 0x7fff, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, - 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, 0x7ffe, - 0x7ffe, 0x7ffe, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, - 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffd, 0x7ffc, - 0x7ffc, 0x7ffc, 0x7ffc, 0x7ffc, 0x7ffc, 0x7ffc, 0x7ffc, 0x7ffc, - 0x7ffc, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffb, - 0x7ffb, 0x7ffb, 0x7ffb, 0x7ffa, 0x7ffa, 0x7ffa, 0x7ffa, 0x7ffa, - 0x7ffa, 0x7ffa, 0x7ffa, 0x7ffa, 0x7ff9, 0x7ff9, 0x7ff9, 0x7ff9, - 0x7ff9, 0x7ff9, 0x7ff9, 0x7ff9, 0x7ff8, 0x7ff8, 0x7ff8, 0x7ff8, - 0x7ff8, 0x7ff8, 0x7ff8, 0x7ff7, 0x7ff7, 0x7ff7, 0x7ff7, 0x7ff7, - 0x7ff7, 0x7ff7, 0x7ff6, 0x7ff6, 0x7ff6, 0x7ff6, 0x7ff6, 0x7ff6, - 0x7ff6, 0x7ff5, 0x7ff5, 0x7ff5, 0x7ff5, 0x7ff5, 0x7ff5, 0x7ff4, - 0x7ff4, 0x7ff4, 0x7ff4, 0x7ff4, 0x7ff4, 0x7ff3, 0x7ff3, 0x7ff3, - 0x7ff3, 0x7ff3, 0x7ff3, 0x7ff2, 0x7ff2, 0x7ff2, 0x7ff2, 0x7ff2, - 0x7ff1, 0x7ff1, 0x7ff1, 0x7ff1, 0x7ff1, 0x7ff1, 0x7ff0, 0x7ff0, - 0x7ff0, 0x7ff0, 0x7ff0, 0x7fef, 0x7fef, 0x7fef, 0x7fef, 0x7fef, - 0x7fee, 0x7fee, 0x7fee, 0x7fee, 0x7fee, 0x7fed, 0x7fed, 0x7fed, - 0x7fed, 0x7fed, 0x7fec, 0x7fec, 0x7fec, 0x7fec, 0x7feb, 0x7feb, - 0x7feb, 0x7feb, 0x7feb, 0x7fea, 0x7fea, 0x7fea, 0x7fea, 0x7fe9, - 0x7fe9, 0x7fe9, 0x7fe9, 0x7fe8, 0x7fe8, 0x7fe8, 0x7fe8, 0x7fe8, - 0x7fe7, 0x7fe7, 0x7fe7, 0x7fe7, 0x7fe6, 0x7fe6, 0x7fe6, 0x7fe6, - 0x7fe5, 0x7fe5, 0x7fe5, 0x7fe5, 0x7fe4, 0x7fe4, 0x7fe4, 0x7fe4, - 0x7fe3, 0x7fe3, 0x7fe3, 0x7fe2, 0x7fe2, 0x7fe2, 0x7fe2, 0x7fe1, - 0x7fe1, 0x7fe1, 0x7fe1, 0x7fe0, 0x7fe0, 0x7fe0, 0x7fdf, 0x7fdf, - 0x7fdf, 0x7fdf, 0x7fde, 0x7fde, 0x7fde, 0x7fde, 0x7fdd, 0x7fdd, - 0x7fdd, 0x7fdc, 0x7fdc, 0x7fdc, 0x7fdb, 0x7fdb, 0x7fdb, 0x7fdb, - 0x7fda, 0x7fda, 0x7fda, 0x7fd9, 0x7fd9, 0x7fd9, 0x7fd8, 0x7fd8, - 0x7fd8, 0x7fd8, 0x7fd7, 0x7fd7, 0x7fd7, 0x7fd6, 0x7fd6, 0x7fd6, - 0x7fd5, 0x7fd5, 0x7fd5, 0x7fd4, 0x7fd4, 0x7fd4, 0x7fd3, 0x7fd3, - 0x7fd3, 0x7fd2, 0x7fd2, 0x7fd2, 0x7fd1, 0x7fd1, 0x7fd1, 0x7fd0, - 0x7fd0, 0x7fd0, 0x7fcf, 0x7fcf, 0x7fcf, 0x7fce, 0x7fce, 0x7fce, - 0x7fcd, 0x7fcd, 0x7fcd, 0x7fcc, 0x7fcc, 0x7fcc, 0x7fcb, 0x7fcb, - 0x7fcb, 0x7fca, 0x7fca, 0x7fc9, 0x7fc9, 0x7fc9, 0x7fc8, 0x7fc8, - 0x7fc8, 0x7fc7, 0x7fc7, 0x7fc7, 0x7fc6, 0x7fc6, 0x7fc5, 0x7fc5, - 0x7fc5, 0x7fc4, 0x7fc4, 0x7fc4, 0x7fc3, 0x7fc3, 0x7fc2, 0x7fc2, - 0x7fc2, 0x7fc1, 0x7fc1, 0x7fc0, 0x7fc0, 0x7fc0, 0x7fbf, 0x7fbf, - 0x7fbf, 0x7fbe, 0x7fbe, 0x7fbd, 0x7fbd, 0x7fbd, 0x7fbc, 0x7fbc, - 0x7fbb, 0x7fbb, 0x7fbb, 0x7fba, 0x7fba, 0x7fb9, 0x7fb9, 0x7fb8, - 0x7fb8, 0x7fb8, 0x7fb7, 0x7fb7, 0x7fb6, 0x7fb6, 0x7fb6, 0x7fb5, - 0x7fb5, 0x7fb4, 0x7fb4, 0x7fb3, 0x7fb3, 0x7fb3, 0x7fb2, 0x7fb2, - 0x7fb1, 0x7fb1, 0x7fb0, 0x7fb0, 0x7faf, 0x7faf, 0x7faf, 0x7fae, - 0x7fae, 0x7fad, 0x7fad, 0x7fac, 0x7fac, 0x7fac, 0x7fab, 0x7fab, - 0x7faa, 0x7faa, 0x7fa9, 0x7fa9, 0x7fa8, 0x7fa8, 0x7fa7, 0x7fa7, - 0x7fa6, 0x7fa6, 0x7fa6, 0x7fa5, 0x7fa5, 0x7fa4, 0x7fa4, 0x7fa3, - 0x7fa3, 0x7fa2, 0x7fa2, 0x7fa1, 0x7fa1, 0x7fa0, 0x7fa0, 0x7f9f, - 0x7f9f, 0x7f9e, 0x7f9e, 0x7f9d, 0x7f9d, 0x7f9c, 0x7f9c, 0x7f9c, - 0x7f9b, 0x7f9b, 0x7f9a, 0x7f9a, 0x7f99, 0x7f99, 0x7f98, 0x7f98, - 0x7f97, 0x7f97, 0x7f96, 0x7f96, 0x7f95, 0x7f95, 0x7f94, 0x7f94, - 0x7f93, 0x7f92, 0x7f92, 0x7f91, 0x7f91, 0x7f90, 0x7f90, 0x7f8f, - 0x7f8f, 0x7f8e, 0x7f8e, 0x7f8d, 0x7f8d, 0x7f8c, 0x7f8c, 0x7f8b, - 0x7f8b, 0x7f8a, 0x7f8a, 0x7f89, 0x7f89, 0x7f88, 0x7f87, 0x7f87, - 0x7f86, 0x7f86, 0x7f85, 0x7f85, 0x7f84, 0x7f84, 0x7f83, 0x7f83, - 0x7f82, 0x7f81, 0x7f81, 0x7f80, 0x7f80, 0x7f7f, 0x7f7f, 0x7f7e, - 0x7f7e, 0x7f7d, 0x7f7c, 0x7f7c, 0x7f7b, 0x7f7b, 0x7f7a, 0x7f7a, - 0x7f79, 0x7f79, 0x7f78, 0x7f77, 0x7f77, 0x7f76, 0x7f76, 0x7f75, - 0x7f75, 0x7f74, 0x7f73, 0x7f73, 0x7f72, 0x7f72, 0x7f71, 0x7f70, - 0x7f70, 0x7f6f, 0x7f6f, 0x7f6e, 0x7f6d, 0x7f6d, 0x7f6c, 0x7f6c, - 0x7f6b, 0x7f6b, 0x7f6a, 0x7f69, 0x7f69, 0x7f68, 0x7f68, 0x7f67, - 0x7f66, 0x7f66, 0x7f65, 0x7f64, 0x7f64, 0x7f63, 0x7f63, 0x7f62, - 0x7f61, 0x7f61, 0x7f60, 0x7f60, 0x7f5f, 0x7f5e, 0x7f5e, 0x7f5d, - 0x7f5c, 0x7f5c, 0x7f5b, 0x7f5b, 0x7f5a, 0x7f59, 0x7f59, 0x7f58, - 0x7f57, 0x7f57, 0x7f56, 0x7f55, 0x7f55, 0x7f54, 0x7f54, 0x7f53, - 0x7f52, 0x7f52, 0x7f51, 0x7f50, 0x7f50, 0x7f4f, 0x7f4e, 0x7f4e, - 0x7f4d, 0x7f4c, 0x7f4c, 0x7f4b, 0x7f4a, 0x7f4a, 0x7f49, 0x7f48, - 0x7f48, 0x7f47, 0x7f46, 0x7f46, 0x7f45, 0x7f44, 0x7f44, 0x7f43, - 0x7f42, 0x7f42, 0x7f41, 0x7f40, 0x7f40, 0x7f3f, 0x7f3e, 0x7f3e, - 0x7f3d, 0x7f3c, 0x7f3c, 0x7f3b, 0x7f3a, 0x7f3a, 0x7f39, 0x7f38, - 0x7f37, 0x7f37, 0x7f36, 0x7f35, 0x7f35, 0x7f34, 0x7f33, 0x7f33, - 0x7f32, 0x7f31, 0x7f31, 0x7f30, 0x7f2f, 0x7f2e, 0x7f2e, 0x7f2d, - 0x7f2c, 0x7f2c, 0x7f2b, 0x7f2a, 0x7f29, 0x7f29, 0x7f28, 0x7f27, - 0x7f27, 0x7f26, 0x7f25, 0x7f24, 0x7f24, 0x7f23, 0x7f22, 0x7f21, - 0x7f21, 0x7f20, 0x7f1f, 0x7f1f, 0x7f1e, 0x7f1d, 0x7f1c, 0x7f1c, - 0x7f1b, 0x7f1a, 0x7f19, 0x7f19, 0x7f18, 0x7f17, 0x7f16, 0x7f16, - 0x7f15, 0x7f14, 0x7f13, 0x7f13, 0x7f12, 0x7f11, 0x7f10, 0x7f10, - 0x7f0f, 0x7f0e, 0x7f0d, 0x7f0d, 0x7f0c, 0x7f0b, 0x7f0a, 0x7f09, - 0x7f09, 0x7f08, 0x7f07, 0x7f06, 0x7f06, 0x7f05, 0x7f04, 0x7f03, - 0x7f02, 0x7f02, 0x7f01, 0x7f00, 0x7eff, 0x7eff, 0x7efe, 0x7efd, - 0x7efc, 0x7efb, 0x7efb, 0x7efa, 0x7ef9, 0x7ef8, 0x7ef7, 0x7ef7, - 0x7ef6, 0x7ef5, 0x7ef4, 0x7ef3, 0x7ef3, 0x7ef2, 0x7ef1, 0x7ef0, - 0x7eef, 0x7eef, 0x7eee, 0x7eed, 0x7eec, 0x7eeb, 0x7eeb, 0x7eea, - 0x7ee9, 0x7ee8, 0x7ee7, 0x7ee6, 0x7ee6, 0x7ee5, 0x7ee4, 0x7ee3, - 0x7ee2, 0x7ee2, 0x7ee1, 0x7ee0, 0x7edf, 0x7ede, 0x7edd, 0x7edd, - 0x7edc, 0x7edb, 0x7eda, 0x7ed9, 0x7ed8, 0x7ed8, 0x7ed7, 0x7ed6, - 0x7ed5, 0x7ed4, 0x7ed3, 0x7ed2, 0x7ed2, 0x7ed1, 0x7ed0, 0x7ecf, - 0x7ece, 0x7ecd, 0x7ecc, 0x7ecc, 0x7ecb, 0x7eca, 0x7ec9, 0x7ec8, - 0x7ec7, 0x7ec6, 0x7ec6, 0x7ec5, 0x7ec4, 0x7ec3, 0x7ec2, 0x7ec1, - 0x7ec0, 0x7ebf, 0x7ebf, 0x7ebe, 0x7ebd, 0x7ebc, 0x7ebb, 0x7eba, - 0x7eb9, 0x7eb8, 0x7eb8, 0x7eb7, 0x7eb6, 0x7eb5, 0x7eb4, 0x7eb3, - 0x7eb2, 0x7eb1, 0x7eb0, 0x7eaf, 0x7eaf, 0x7eae, 0x7ead, 0x7eac, - 0x7eab, 0x7eaa, 0x7ea9, 0x7ea8, 0x7ea7, 0x7ea6, 0x7ea6, 0x7ea5, - 0x7ea4, 0x7ea3, 0x7ea2, 0x7ea1, 0x7ea0, 0x7e9f, 0x7e9e, 0x7e9d, - 0x7e9c, 0x7e9b, 0x7e9b, 0x7e9a, 0x7e99, 0x7e98, 0x7e97, 0x7e96, - 0x7e95, 0x7e94, 0x7e93, 0x7e92, 0x7e91, 0x7e90, 0x7e8f, 0x7e8e, - 0x7e8d, 0x7e8d, 0x7e8c, 0x7e8b, 0x7e8a, 0x7e89, 0x7e88, 0x7e87, - 0x7e86, 0x7e85, 0x7e84, 0x7e83, 0x7e82, 0x7e81, 0x7e80, 0x7e7f, - 0x7e7e, 0x7e7d, 0x7e7c, 0x7e7b, 0x7e7a, 0x7e79, 0x7e78, 0x7e77, - 0x7e77, 0x7e76, 0x7e75, 0x7e74, 0x7e73, 0x7e72, 0x7e71, 0x7e70, - 0x7e6f, 0x7e6e, 0x7e6d, 0x7e6c, 0x7e6b, 0x7e6a, 0x7e69, 0x7e68, - 0x7e67, 0x7e66, 0x7e65, 0x7e64, 0x7e63, 0x7e62, 0x7e61, 0x7e60, - 0x7e5f, 0x7e5e, 0x7e5d, 0x7e5c, 0x7e5b, 0x7e5a, 0x7e59, 0x7e58, - 0x7e57, 0x7e56, 0x7e55, 0x7e54, 0x7e53, 0x7e52, 0x7e51, 0x7e50, - 0x7e4f, 0x7e4e, 0x7e4d, 0x7e4c, 0x7e4b, 0x7e4a, 0x7e49, 0x7e48, - 0x7e47, 0x7e46, 0x7e45, 0x7e43, 0x7e42, 0x7e41, 0x7e40, 0x7e3f, - 0x7e3e, 0x7e3d, 0x7e3c, 0x7e3b, 0x7e3a, 0x7e39, 0x7e38, 0x7e37, - 0x7e36, 0x7e35, 0x7e34, 0x7e33, 0x7e32, 0x7e31, 0x7e30, 0x7e2f, - 0x7e2e, 0x7e2d, 0x7e2b, 0x7e2a, 0x7e29, 0x7e28, 0x7e27, 0x7e26, - 0x7e25, 0x7e24, 0x7e23, 0x7e22, 0x7e21, 0x7e20, 0x7e1f, 0x7e1e, - 0x7e1d, 0x7e1b, 0x7e1a, 0x7e19, 0x7e18, 0x7e17, 0x7e16, 0x7e15, - 0x7e14, 0x7e13, 0x7e12, 0x7e11, 0x7e10, 0x7e0e, 0x7e0d, 0x7e0c, - 0x7e0b, 0x7e0a, 0x7e09, 0x7e08, 0x7e07, 0x7e06, 0x7e05, 0x7e04, - 0x7e02, 0x7e01, 0x7e00, 0x7dff, 0x7dfe, 0x7dfd, 0x7dfc, 0x7dfb, - 0x7dfa, 0x7df8, 0x7df7, 0x7df6, 0x7df5, 0x7df4, 0x7df3, 0x7df2, - 0x7df1, 0x7def, 0x7dee, 0x7ded, 0x7dec, 0x7deb, 0x7dea, 0x7de9, - 0x7de8, 0x7de6, 0x7de5, 0x7de4, 0x7de3, 0x7de2, 0x7de1, 0x7de0, - 0x7dde, 0x7ddd, 0x7ddc, 0x7ddb, 0x7dda, 0x7dd9, 0x7dd8, 0x7dd6, - 0x7dd5, 0x7dd4, 0x7dd3, 0x7dd2, 0x7dd1, 0x7dd0, 0x7dce, 0x7dcd, - 0x7dcc, 0x7dcb, 0x7dca, 0x7dc9, 0x7dc7, 0x7dc6, 0x7dc5, 0x7dc4, - 0x7dc3, 0x7dc2, 0x7dc0, 0x7dbf, 0x7dbe, 0x7dbd, 0x7dbc, 0x7dbb, - 0x7db9, 0x7db8, 0x7db7, 0x7db6, 0x7db5, 0x7db3, 0x7db2, 0x7db1, - 0x7db0, 0x7daf, 0x7dae, 0x7dac, 0x7dab, 0x7daa, 0x7da9, 0x7da8, - 0x7da6, 0x7da5, 0x7da4, 0x7da3, 0x7da2, 0x7da0, 0x7d9f, 0x7d9e, - 0x7d9d, 0x7d9c, 0x7d9a, 0x7d99, 0x7d98, 0x7d97, 0x7d95, 0x7d94, - 0x7d93, 0x7d92, 0x7d91, 0x7d8f, 0x7d8e, 0x7d8d, 0x7d8c, 0x7d8a, - 0x7d89, 0x7d88, 0x7d87, 0x7d86, 0x7d84, 0x7d83, 0x7d82, 0x7d81, - 0x7d7f, 0x7d7e, 0x7d7d, 0x7d7c, 0x7d7a, 0x7d79, 0x7d78, 0x7d77, - 0x7d75, 0x7d74, 0x7d73, 0x7d72, 0x7d70, 0x7d6f, 0x7d6e, 0x7d6d, - 0x7d6b, 0x7d6a, 0x7d69, 0x7d68, 0x7d66, 0x7d65, 0x7d64, 0x7d63, - 0x7d61, 0x7d60, 0x7d5f, 0x7d5e, 0x7d5c, 0x7d5b, 0x7d5a, 0x7d59, - 0x7d57, 0x7d56, 0x7d55, 0x7d53, 0x7d52, 0x7d51, 0x7d50, 0x7d4e, - 0x7d4d, 0x7d4c, 0x7d4a, 0x7d49, 0x7d48, 0x7d47, 0x7d45, 0x7d44, - 0x7d43, 0x7d41, 0x7d40, 0x7d3f, 0x7d3e, 0x7d3c, 0x7d3b, 0x7d3a, - 0x7d38, 0x7d37, 0x7d36, 0x7d34, 0x7d33, 0x7d32, 0x7d31, 0x7d2f, - 0x7d2e, 0x7d2d, 0x7d2b, 0x7d2a, 0x7d29, 0x7d27, 0x7d26, 0x7d25, - 0x7d23, 0x7d22, 0x7d21, 0x7d1f, 0x7d1e, 0x7d1d, 0x7d1b, 0x7d1a, - 0x7d19, 0x7d17, 0x7d16, 0x7d15, 0x7d13, 0x7d12, 0x7d11, 0x7d0f, - 0x7d0e, 0x7d0d, 0x7d0b, 0x7d0a, 0x7d09, 0x7d07, 0x7d06, 0x7d05, - 0x7d03, 0x7d02, 0x7d01, 0x7cff, 0x7cfe, 0x7cfd, 0x7cfb, 0x7cfa, - 0x7cf9, 0x7cf7, 0x7cf6, 0x7cf4, 0x7cf3, 0x7cf2, 0x7cf0, 0x7cef, - 0x7cee, 0x7cec, 0x7ceb, 0x7ce9, 0x7ce8, 0x7ce7, 0x7ce5, 0x7ce4, - 0x7ce3, 0x7ce1, 0x7ce0, 0x7cde, 0x7cdd, 0x7cdc, 0x7cda, 0x7cd9, - 0x7cd8, 0x7cd6, 0x7cd5, 0x7cd3, 0x7cd2, 0x7cd1, 0x7ccf, 0x7cce, - 0x7ccc, 0x7ccb, 0x7cca, 0x7cc8, 0x7cc7, 0x7cc5, 0x7cc4, 0x7cc3, - 0x7cc1, 0x7cc0, 0x7cbe, 0x7cbd, 0x7cbc, 0x7cba, 0x7cb9, 0x7cb7, - 0x7cb6, 0x7cb5, 0x7cb3, 0x7cb2, 0x7cb0, 0x7caf, 0x7cad, 0x7cac, - 0x7cab, 0x7ca9, 0x7ca8, 0x7ca6, 0x7ca5, 0x7ca3, 0x7ca2, 0x7ca1, - 0x7c9f, 0x7c9e, 0x7c9c, 0x7c9b, 0x7c99, 0x7c98, 0x7c97, 0x7c95, - 0x7c94, 0x7c92, 0x7c91, 0x7c8f, 0x7c8e, 0x7c8c, 0x7c8b, 0x7c8a, - 0x7c88, 0x7c87, 0x7c85, 0x7c84, 0x7c82, 0x7c81, 0x7c7f, 0x7c7e, - 0x7c7c, 0x7c7b, 0x7c79, 0x7c78, 0x7c77, 0x7c75, 0x7c74, 0x7c72, - 0x7c71, 0x7c6f, 0x7c6e, 0x7c6c, 0x7c6b, 0x7c69, 0x7c68, 0x7c66, - 0x7c65, 0x7c63, 0x7c62, 0x7c60, 0x7c5f, 0x7c5d, 0x7c5c, 0x7c5a, - 0x7c59, 0x7c58, 0x7c56, 0x7c55, 0x7c53, 0x7c52, 0x7c50, 0x7c4f, - 0x7c4d, 0x7c4c, 0x7c4a, 0x7c49, 0x7c47, 0x7c46, 0x7c44, 0x7c43, - 0x7c41, 0x7c3f, 0x7c3e, 0x7c3c, 0x7c3b, 0x7c39, 0x7c38, 0x7c36, - 0x7c35, 0x7c33, 0x7c32, 0x7c30, 0x7c2f, 0x7c2d, 0x7c2c, 0x7c2a, - 0x7c29, 0x7c27, 0x7c26, 0x7c24, 0x7c23, 0x7c21, 0x7c20, 0x7c1e, - 0x7c1c, 0x7c1b, 0x7c19, 0x7c18, 0x7c16, 0x7c15, 0x7c13, 0x7c12, - 0x7c10, 0x7c0f, 0x7c0d, 0x7c0b, 0x7c0a, 0x7c08, 0x7c07, 0x7c05, - 0x7c04, 0x7c02, 0x7c01, 0x7bff, 0x7bfd, 0x7bfc, 0x7bfa, 0x7bf9, - 0x7bf7, 0x7bf6, 0x7bf4, 0x7bf3, 0x7bf1, 0x7bef, 0x7bee, 0x7bec, - 0x7beb, 0x7be9, 0x7be8, 0x7be6, 0x7be4, 0x7be3, 0x7be1, 0x7be0, - 0x7bde, 0x7bdc, 0x7bdb, 0x7bd9, 0x7bd8, 0x7bd6, 0x7bd5, 0x7bd3, - 0x7bd1, 0x7bd0, 0x7bce, 0x7bcd, 0x7bcb, 0x7bc9, 0x7bc8, 0x7bc6, - 0x7bc5, 0x7bc3, 0x7bc1, 0x7bc0, 0x7bbe, 0x7bbd, 0x7bbb, 0x7bb9, - 0x7bb8, 0x7bb6, 0x7bb5, 0x7bb3, 0x7bb1, 0x7bb0, 0x7bae, 0x7bac, - 0x7bab, 0x7ba9, 0x7ba8, 0x7ba6, 0x7ba4, 0x7ba3, 0x7ba1, 0x7b9f, - 0x7b9e, 0x7b9c, 0x7b9b, 0x7b99, 0x7b97, 0x7b96, 0x7b94, 0x7b92, - 0x7b91, 0x7b8f, 0x7b8d, 0x7b8c, 0x7b8a, 0x7b89, 0x7b87, 0x7b85, - 0x7b84, 0x7b82, 0x7b80, 0x7b7f, 0x7b7d, 0x7b7b, 0x7b7a, 0x7b78, - 0x7b76, 0x7b75, 0x7b73, 0x7b71, 0x7b70, 0x7b6e, 0x7b6c, 0x7b6b, - 0x7b69, 0x7b67, 0x7b66, 0x7b64, 0x7b62, 0x7b61, 0x7b5f, 0x7b5d, - 0x7b5c, 0x7b5a, 0x7b58, 0x7b57, 0x7b55, 0x7b53, 0x7b52, 0x7b50, - 0x7b4e, 0x7b4d, 0x7b4b, 0x7b49, 0x7b47, 0x7b46, 0x7b44, 0x7b42, - 0x7b41, 0x7b3f, 0x7b3d, 0x7b3c, 0x7b3a, 0x7b38, 0x7b37, 0x7b35, - 0x7b33, 0x7b31, 0x7b30, 0x7b2e, 0x7b2c, 0x7b2b, 0x7b29, 0x7b27, - 0x7b25, 0x7b24, 0x7b22, 0x7b20, 0x7b1f, 0x7b1d, 0x7b1b, 0x7b19, - 0x7b18, 0x7b16, 0x7b14, 0x7b13, 0x7b11, 0x7b0f, 0x7b0d, 0x7b0c, - 0x7b0a, 0x7b08, 0x7b06, 0x7b05, 0x7b03, 0x7b01, 0x7aff, 0x7afe, - 0x7afc, 0x7afa, 0x7af8, 0x7af7, 0x7af5, 0x7af3, 0x7af2, 0x7af0, - 0x7aee, 0x7aec, 0x7aeb, 0x7ae9, 0x7ae7, 0x7ae5, 0x7ae3, 0x7ae2, - 0x7ae0, 0x7ade, 0x7adc, 0x7adb, 0x7ad9, 0x7ad7, 0x7ad5, 0x7ad4, - 0x7ad2, 0x7ad0, 0x7ace, 0x7acd, 0x7acb, 0x7ac9, 0x7ac7, 0x7ac5, - 0x7ac4, 0x7ac2, 0x7ac0, 0x7abe, 0x7abd, 0x7abb, 0x7ab9, 0x7ab7, - 0x7ab5, 0x7ab4, 0x7ab2, 0x7ab0, 0x7aae, 0x7aac, 0x7aab, 0x7aa9, - 0x7aa7, 0x7aa5, 0x7aa3, 0x7aa2, 0x7aa0, 0x7a9e, 0x7a9c, 0x7a9a, - 0x7a99, 0x7a97, 0x7a95, 0x7a93, 0x7a91, 0x7a90, 0x7a8e, 0x7a8c, - 0x7a8a, 0x7a88, 0x7a87, 0x7a85, 0x7a83, 0x7a81, 0x7a7f, 0x7a7d, - 0x7a7c, 0x7a7a, 0x7a78, 0x7a76, 0x7a74, 0x7a72, 0x7a71, 0x7a6f, - 0x7a6d, 0x7a6b, 0x7a69, 0x7a67, 0x7a66, 0x7a64, 0x7a62, 0x7a60, - 0x7a5e, 0x7a5c, 0x7a5b, 0x7a59, 0x7a57, 0x7a55, 0x7a53, 0x7a51, - 0x7a4f, 0x7a4e, 0x7a4c, 0x7a4a, 0x7a48, 0x7a46, 0x7a44, 0x7a42, - 0x7a41, 0x7a3f, 0x7a3d, 0x7a3b, 0x7a39, 0x7a37, 0x7a35, 0x7a34, - 0x7a32, 0x7a30, 0x7a2e, 0x7a2c, 0x7a2a, 0x7a28, 0x7a26, 0x7a25, - 0x7a23, 0x7a21, 0x7a1f, 0x7a1d, 0x7a1b, 0x7a19, 0x7a17, 0x7a16, - 0x7a14, 0x7a12, 0x7a10, 0x7a0e, 0x7a0c, 0x7a0a, 0x7a08, 0x7a06, - 0x7a04, 0x7a03, 0x7a01, 0x79ff, 0x79fd, 0x79fb, 0x79f9, 0x79f7, - 0x79f5, 0x79f3, 0x79f1, 0x79f0, 0x79ee, 0x79ec, 0x79ea, 0x79e8, - 0x79e6, 0x79e4, 0x79e2, 0x79e0, 0x79de, 0x79dc, 0x79da, 0x79d9, - 0x79d7, 0x79d5, 0x79d3, 0x79d1, 0x79cf, 0x79cd, 0x79cb, 0x79c9, - 0x79c7, 0x79c5, 0x79c3, 0x79c1, 0x79bf, 0x79bd, 0x79bc, 0x79ba, - 0x79b8, 0x79b6, 0x79b4, 0x79b2, 0x79b0, 0x79ae, 0x79ac, 0x79aa, - 0x79a8, 0x79a6, 0x79a4, 0x79a2, 0x79a0, 0x799e, 0x799c, 0x799a, - 0x7998, 0x7996, 0x7994, 0x7992, 0x7991, 0x798f, 0x798d, 0x798b, - 0x7989, 0x7987, 0x7985, 0x7983, 0x7981, 0x797f, 0x797d, 0x797b, - 0x7979, 0x7977, 0x7975, 0x7973, 0x7971, 0x796f, 0x796d, 0x796b, - 0x7969, 0x7967, 0x7965, 0x7963, 0x7961, 0x795f, 0x795d, 0x795b, - 0x7959, 0x7957, 0x7955, 0x7953, 0x7951, 0x794f, 0x794d, 0x794b, - 0x7949, 0x7947, 0x7945, 0x7943, 0x7941, 0x793f, 0x793d, 0x793b, - 0x7939, 0x7937, 0x7935, 0x7933, 0x7931, 0x792f, 0x792d, 0x792b, - 0x7929, 0x7927, 0x7925, 0x7923, 0x7921, 0x791f, 0x791d, 0x791a, - 0x7918, 0x7916, 0x7914, 0x7912, 0x7910, 0x790e, 0x790c, 0x790a, - 0x7908, 0x7906, 0x7904, 0x7902, 0x7900, 0x78fe, 0x78fc, 0x78fa, - 0x78f8, 0x78f6, 0x78f4, 0x78f2, 0x78f0, 0x78ed, 0x78eb, 0x78e9, - 0x78e7, 0x78e5, 0x78e3, 0x78e1, 0x78df, 0x78dd, 0x78db, 0x78d9, - 0x78d7, 0x78d5, 0x78d3, 0x78d1, 0x78ce, 0x78cc, 0x78ca, 0x78c8, - 0x78c6, 0x78c4, 0x78c2, 0x78c0, 0x78be, 0x78bc, 0x78ba, 0x78b8, - 0x78b5, 0x78b3, 0x78b1, 0x78af, 0x78ad, 0x78ab, 0x78a9, 0x78a7, - 0x78a5, 0x78a3, 0x78a0, 0x789e, 0x789c, 0x789a, 0x7898, 0x7896, - 0x7894, 0x7892, 0x7890, 0x788e, 0x788b, 0x7889, 0x7887, 0x7885, - 0x7883, 0x7881, 0x787f, 0x787d, 0x787a, 0x7878, 0x7876, 0x7874, - 0x7872, 0x7870, 0x786e, 0x786c, 0x7869, 0x7867, 0x7865, 0x7863, - 0x7861, 0x785f, 0x785d, 0x785b, 0x7858, 0x7856, 0x7854, 0x7852, - 0x7850, 0x784e, 0x784c, 0x7849, 0x7847, 0x7845, 0x7843, 0x7841, - 0x783f, 0x783c, 0x783a, 0x7838, 0x7836, 0x7834, 0x7832, 0x7830, - 0x782d, 0x782b, 0x7829, 0x7827, 0x7825, 0x7823, 0x7820, 0x781e, - 0x781c, 0x781a, 0x7818, 0x7816, 0x7813, 0x7811, 0x780f, 0x780d, - 0x780b, 0x7808, 0x7806, 0x7804, 0x7802, 0x7800, 0x77fe, 0x77fb, - 0x77f9, 0x77f7, 0x77f5, 0x77f3, 0x77f0, 0x77ee, 0x77ec, 0x77ea, - 0x77e8, 0x77e5, 0x77e3, 0x77e1, 0x77df, 0x77dd, 0x77da, 0x77d8, - 0x77d6, 0x77d4, 0x77d2, 0x77cf, 0x77cd, 0x77cb, 0x77c9, 0x77c6, - 0x77c4, 0x77c2, 0x77c0, 0x77be, 0x77bb, 0x77b9, 0x77b7, 0x77b5, - 0x77b2, 0x77b0, 0x77ae, 0x77ac, 0x77aa, 0x77a7, 0x77a5, 0x77a3, - 0x77a1, 0x779e, 0x779c, 0x779a, 0x7798, 0x7795, 0x7793, 0x7791, - 0x778f, 0x778c, 0x778a, 0x7788, 0x7786, 0x7783, 0x7781, 0x777f, - 0x777d, 0x777a, 0x7778, 0x7776, 0x7774, 0x7771, 0x776f, 0x776d, - 0x776b, 0x7768, 0x7766, 0x7764, 0x7762, 0x775f, 0x775d, 0x775b, - 0x7759, 0x7756, 0x7754, 0x7752, 0x774f, 0x774d, 0x774b, 0x7749, - 0x7746, 0x7744, 0x7742, 0x773f, 0x773d, 0x773b, 0x7739, 0x7736, - 0x7734, 0x7732, 0x772f, 0x772d, 0x772b, 0x7729, 0x7726, 0x7724, - 0x7722, 0x771f, 0x771d, 0x771b, 0x7719, 0x7716, 0x7714, 0x7712, - 0x770f, 0x770d, 0x770b, 0x7708, 0x7706, 0x7704, 0x7701, 0x76ff, - 0x76fd, 0x76fa, 0x76f8, 0x76f6, 0x76f4, 0x76f1, 0x76ef, 0x76ed, - 0x76ea, 0x76e8, 0x76e6, 0x76e3, 0x76e1, 0x76df, 0x76dc, 0x76da, - 0x76d8, 0x76d5, 0x76d3, 0x76d1, 0x76ce, 0x76cc, 0x76ca, 0x76c7, - 0x76c5, 0x76c3, 0x76c0, 0x76be, 0x76bc, 0x76b9, 0x76b7, 0x76b4, - 0x76b2, 0x76b0, 0x76ad, 0x76ab, 0x76a9, 0x76a6, 0x76a4, 0x76a2, - 0x769f, 0x769d, 0x769b, 0x7698, 0x7696, 0x7693, 0x7691, 0x768f, - 0x768c, 0x768a, 0x7688, 0x7685, 0x7683, 0x7681, 0x767e, 0x767c, - 0x7679, 0x7677, 0x7675, 0x7672, 0x7670, 0x766d, 0x766b, 0x7669, - 0x7666, 0x7664, 0x7662, 0x765f, 0x765d, 0x765a, 0x7658, 0x7656, - 0x7653, 0x7651, 0x764e, 0x764c, 0x764a, 0x7647, 0x7645, 0x7642, - 0x7640, 0x763e, 0x763b, 0x7639, 0x7636, 0x7634, 0x7632, 0x762f, - 0x762d, 0x762a, 0x7628, 0x7625, 0x7623, 0x7621, 0x761e, 0x761c, - 0x7619, 0x7617, 0x7615, 0x7612, 0x7610, 0x760d, 0x760b, 0x7608, - 0x7606, 0x7604, 0x7601, 0x75ff, 0x75fc, 0x75fa, 0x75f7, 0x75f5, - 0x75f2, 0x75f0, 0x75ee, 0x75eb, 0x75e9, 0x75e6, 0x75e4, 0x75e1, - 0x75df, 0x75dc, 0x75da, 0x75d8, 0x75d5, 0x75d3, 0x75d0, 0x75ce, - 0x75cb, 0x75c9, 0x75c6, 0x75c4, 0x75c1, 0x75bf, 0x75bc, 0x75ba, - 0x75b8, 0x75b5, 0x75b3, 0x75b0, 0x75ae, 0x75ab, 0x75a9, 0x75a6, - 0x75a4, 0x75a1, 0x759f, 0x759c, 0x759a, 0x7597, 0x7595, 0x7592, - 0x7590, 0x758d, 0x758b, 0x7588, 0x7586, 0x7584, 0x7581, 0x757f, - 0x757c, 0x757a, 0x7577, 0x7575, 0x7572, 0x7570, 0x756d, 0x756b, - 0x7568, 0x7566, 0x7563, 0x7561, 0x755e, 0x755c, 0x7559, 0x7556, - 0x7554, 0x7551, 0x754f, 0x754c, 0x754a, 0x7547, 0x7545, 0x7542, - 0x7540, 0x753d, 0x753b, 0x7538, 0x7536, 0x7533, 0x7531, 0x752e, - 0x752c, 0x7529, 0x7527, 0x7524, 0x7522, 0x751f, 0x751c, 0x751a, - 0x7517, 0x7515, 0x7512, 0x7510, 0x750d, 0x750b, 0x7508, 0x7506, - 0x7503, 0x7501, 0x74fe, 0x74fb, 0x74f9, 0x74f6, 0x74f4, 0x74f1, - 0x74ef, 0x74ec, 0x74ea, 0x74e7, 0x74e4, 0x74e2, 0x74df, 0x74dd, - 0x74da, 0x74d8, 0x74d5, 0x74d2, 0x74d0, 0x74cd, 0x74cb, 0x74c8, - 0x74c6, 0x74c3, 0x74c0, 0x74be, 0x74bb, 0x74b9, 0x74b6, 0x74b4, - 0x74b1, 0x74ae, 0x74ac, 0x74a9, 0x74a7, 0x74a4, 0x74a1, 0x749f, - 0x749c, 0x749a, 0x7497, 0x7495, 0x7492, 0x748f, 0x748d, 0x748a, - 0x7488, 0x7485, 0x7482, 0x7480, 0x747d, 0x747b, 0x7478, 0x7475, - 0x7473, 0x7470, 0x746d, 0x746b, 0x7468, 0x7466, 0x7463, 0x7460, - 0x745e, 0x745b, 0x7459, 0x7456, 0x7453, 0x7451, 0x744e, 0x744b, - 0x7449, 0x7446, 0x7444, 0x7441, 0x743e, 0x743c, 0x7439, 0x7436, - 0x7434, 0x7431, 0x742f, 0x742c, 0x7429, 0x7427, 0x7424, 0x7421, - 0x741f, 0x741c, 0x7419, 0x7417, 0x7414, 0x7411, 0x740f, 0x740c, - 0x740a, 0x7407, 0x7404, 0x7402, 0x73ff, 0x73fc, 0x73fa, 0x73f7, - 0x73f4, 0x73f2, 0x73ef, 0x73ec, 0x73ea, 0x73e7, 0x73e4, 0x73e2, - 0x73df, 0x73dc, 0x73da, 0x73d7, 0x73d4, 0x73d2, 0x73cf, 0x73cc, - 0x73ca, 0x73c7, 0x73c4, 0x73c1, 0x73bf, 0x73bc, 0x73b9, 0x73b7, - 0x73b4, 0x73b1, 0x73af, 0x73ac, 0x73a9, 0x73a7, 0x73a4, 0x73a1, - 0x739f, 0x739c, 0x7399, 0x7396, 0x7394, 0x7391, 0x738e, 0x738c, - 0x7389, 0x7386, 0x7384, 0x7381, 0x737e, 0x737b, 0x7379, 0x7376, - 0x7373, 0x7371, 0x736e, 0x736b, 0x7368, 0x7366, 0x7363, 0x7360, - 0x735e, 0x735b, 0x7358, 0x7355, 0x7353, 0x7350, 0x734d, 0x734a, - 0x7348, 0x7345, 0x7342, 0x7340, 0x733d, 0x733a, 0x7337, 0x7335, - 0x7332, 0x732f, 0x732c, 0x732a, 0x7327, 0x7324, 0x7321, 0x731f, - 0x731c, 0x7319, 0x7316, 0x7314, 0x7311, 0x730e, 0x730b, 0x7309, - 0x7306, 0x7303, 0x7300, 0x72fe, 0x72fb, 0x72f8, 0x72f5, 0x72f3, - 0x72f0, 0x72ed, 0x72ea, 0x72e8, 0x72e5, 0x72e2, 0x72df, 0x72dc, - 0x72da, 0x72d7, 0x72d4, 0x72d1, 0x72cf, 0x72cc, 0x72c9, 0x72c6, - 0x72c3, 0x72c1, 0x72be, 0x72bb, 0x72b8, 0x72b5, 0x72b3, 0x72b0, - 0x72ad, 0x72aa, 0x72a8, 0x72a5, 0x72a2, 0x729f, 0x729c, 0x729a, - 0x7297, 0x7294, 0x7291, 0x728e, 0x728c, 0x7289, 0x7286, 0x7283, - 0x7280, 0x727e, 0x727b, 0x7278, 0x7275, 0x7272, 0x726f, 0x726d, - 0x726a, 0x7267, 0x7264, 0x7261, 0x725f, 0x725c, 0x7259, 0x7256, - 0x7253, 0x7250, 0x724e, 0x724b, 0x7248, 0x7245, 0x7242, 0x723f, - 0x723d, 0x723a, 0x7237, 0x7234, 0x7231, 0x722e, 0x722c, 0x7229, - 0x7226, 0x7223, 0x7220, 0x721d, 0x721b, 0x7218, 0x7215, 0x7212, - 0x720f, 0x720c, 0x7209, 0x7207, 0x7204, 0x7201, 0x71fe, 0x71fb, - 0x71f8, 0x71f5, 0x71f3, 0x71f0, 0x71ed, 0x71ea, 0x71e7, 0x71e4, - 0x71e1, 0x71df, 0x71dc, 0x71d9, 0x71d6, 0x71d3, 0x71d0, 0x71cd, - 0x71ca, 0x71c8, 0x71c5, 0x71c2, 0x71bf, 0x71bc, 0x71b9, 0x71b6, - 0x71b3, 0x71b0, 0x71ae, 0x71ab, 0x71a8, 0x71a5, 0x71a2, 0x719f, - 0x719c, 0x7199, 0x7196, 0x7194, 0x7191, 0x718e, 0x718b, 0x7188, - 0x7185, 0x7182, 0x717f, 0x717c, 0x7179, 0x7177, 0x7174, 0x7171, - 0x716e, 0x716b, 0x7168, 0x7165, 0x7162, 0x715f, 0x715c, 0x7159, - 0x7156, 0x7154, 0x7151, 0x714e, 0x714b, 0x7148, 0x7145, 0x7142, - 0x713f, 0x713c, 0x7139, 0x7136, 0x7133, 0x7130, 0x712d, 0x712b, - 0x7128, 0x7125, 0x7122, 0x711f, 0x711c, 0x7119, 0x7116, 0x7113, - 0x7110, 0x710d, 0x710a, 0x7107, 0x7104, 0x7101, 0x70fe, 0x70fb, - 0x70f8, 0x70f6, 0x70f3, 0x70f0, 0x70ed, 0x70ea, 0x70e7, 0x70e4, - 0x70e1, 0x70de, 0x70db, 0x70d8, 0x70d5, 0x70d2, 0x70cf, 0x70cc, - 0x70c9, 0x70c6, 0x70c3, 0x70c0, 0x70bd, 0x70ba, 0x70b7, 0x70b4, - 0x70b1, 0x70ae, 0x70ab, 0x70a8, 0x70a5, 0x70a2, 0x709f, 0x709c, - 0x7099, 0x7096, 0x7093, 0x7090, 0x708d, 0x708a, 0x7087, 0x7084, - 0x7081, 0x707e, 0x707b, 0x7078, 0x7075, 0x7072, 0x706f, 0x706c, - 0x7069, 0x7066, 0x7063, 0x7060, 0x705d, 0x705a, 0x7057, 0x7054, - 0x7051, 0x704e, 0x704b, 0x7048, 0x7045, 0x7042, 0x703f, 0x703c, - 0x7039, 0x7036, 0x7033, 0x7030, 0x702d, 0x702a, 0x7027, 0x7024, - 0x7021, 0x701e, 0x701b, 0x7018, 0x7015, 0x7012, 0x700f, 0x700c, - 0x7009, 0x7006, 0x7003, 0x7000, 0x6ffd, 0x6ffa, 0x6ff7, 0x6ff3, - 0x6ff0, 0x6fed, 0x6fea, 0x6fe7, 0x6fe4, 0x6fe1, 0x6fde, 0x6fdb, - 0x6fd8, 0x6fd5, 0x6fd2, 0x6fcf, 0x6fcc, 0x6fc9, 0x6fc6, 0x6fc3, - 0x6fc0, 0x6fbc, 0x6fb9, 0x6fb6, 0x6fb3, 0x6fb0, 0x6fad, 0x6faa, - 0x6fa7, 0x6fa4, 0x6fa1, 0x6f9e, 0x6f9b, 0x6f98, 0x6f95, 0x6f91, - 0x6f8e, 0x6f8b, 0x6f88, 0x6f85, 0x6f82, 0x6f7f, 0x6f7c, 0x6f79, - 0x6f76, 0x6f73, 0x6f70, 0x6f6c, 0x6f69, 0x6f66, 0x6f63, 0x6f60, - 0x6f5d, 0x6f5a, 0x6f57, 0x6f54, 0x6f51, 0x6f4d, 0x6f4a, 0x6f47, - 0x6f44, 0x6f41, 0x6f3e, 0x6f3b, 0x6f38, 0x6f35, 0x6f31, 0x6f2e, - 0x6f2b, 0x6f28, 0x6f25, 0x6f22, 0x6f1f, 0x6f1c, 0x6f19, 0x6f15, - 0x6f12, 0x6f0f, 0x6f0c, 0x6f09, 0x6f06, 0x6f03, 0x6f00, 0x6efc, - 0x6ef9, 0x6ef6, 0x6ef3, 0x6ef0, 0x6eed, 0x6eea, 0x6ee7, 0x6ee3, - 0x6ee0, 0x6edd, 0x6eda, 0x6ed7, 0x6ed4, 0x6ed1, 0x6ecd, 0x6eca, - 0x6ec7, 0x6ec4, 0x6ec1, 0x6ebe, 0x6eba, 0x6eb7, 0x6eb4, 0x6eb1, - 0x6eae, 0x6eab, 0x6ea8, 0x6ea4, 0x6ea1, 0x6e9e, 0x6e9b, 0x6e98, - 0x6e95, 0x6e91, 0x6e8e, 0x6e8b, 0x6e88, 0x6e85, 0x6e82, 0x6e7e, - 0x6e7b, 0x6e78, 0x6e75, 0x6e72, 0x6e6f, 0x6e6b, 0x6e68, 0x6e65, - 0x6e62, 0x6e5f, 0x6e5b, 0x6e58, 0x6e55, 0x6e52, 0x6e4f, 0x6e4c, - 0x6e48, 0x6e45, 0x6e42, 0x6e3f, 0x6e3c, 0x6e38, 0x6e35, 0x6e32, - 0x6e2f, 0x6e2c, 0x6e28, 0x6e25, 0x6e22, 0x6e1f, 0x6e1c, 0x6e18, - 0x6e15, 0x6e12, 0x6e0f, 0x6e0c, 0x6e08, 0x6e05, 0x6e02, 0x6dff, - 0x6dfb, 0x6df8, 0x6df5, 0x6df2, 0x6def, 0x6deb, 0x6de8, 0x6de5, - 0x6de2, 0x6ddf, 0x6ddb, 0x6dd8, 0x6dd5, 0x6dd2, 0x6dce, 0x6dcb, - 0x6dc8, 0x6dc5, 0x6dc1, 0x6dbe, 0x6dbb, 0x6db8, 0x6db5, 0x6db1, - 0x6dae, 0x6dab, 0x6da8, 0x6da4, 0x6da1, 0x6d9e, 0x6d9b, 0x6d97, - 0x6d94, 0x6d91, 0x6d8e, 0x6d8a, 0x6d87, 0x6d84, 0x6d81, 0x6d7d, - 0x6d7a, 0x6d77, 0x6d74, 0x6d70, 0x6d6d, 0x6d6a, 0x6d67, 0x6d63, - 0x6d60, 0x6d5d, 0x6d59, 0x6d56, 0x6d53, 0x6d50, 0x6d4c, 0x6d49, - 0x6d46, 0x6d43, 0x6d3f, 0x6d3c, 0x6d39, 0x6d36, 0x6d32, 0x6d2f, - 0x6d2c, 0x6d28, 0x6d25, 0x6d22, 0x6d1f, 0x6d1b, 0x6d18, 0x6d15, - 0x6d11, 0x6d0e, 0x6d0b, 0x6d08, 0x6d04, 0x6d01, 0x6cfe, 0x6cfa, - 0x6cf7, 0x6cf4, 0x6cf0, 0x6ced, 0x6cea, 0x6ce7, 0x6ce3, 0x6ce0, - 0x6cdd, 0x6cd9, 0x6cd6, 0x6cd3, 0x6ccf, 0x6ccc, 0x6cc9, 0x6cc5, - 0x6cc2, 0x6cbf, 0x6cbc, 0x6cb8, 0x6cb5, 0x6cb2, 0x6cae, 0x6cab, - 0x6ca8, 0x6ca4, 0x6ca1, 0x6c9e, 0x6c9a, 0x6c97, 0x6c94, 0x6c90, - 0x6c8d, 0x6c8a, 0x6c86, 0x6c83, 0x6c80, 0x6c7c, 0x6c79, 0x6c76, - 0x6c72, 0x6c6f, 0x6c6c, 0x6c68, 0x6c65, 0x6c62, 0x6c5e, 0x6c5b, - 0x6c58, 0x6c54, 0x6c51, 0x6c4e, 0x6c4a, 0x6c47, 0x6c44, 0x6c40, - 0x6c3d, 0x6c39, 0x6c36, 0x6c33, 0x6c2f, 0x6c2c, 0x6c29, 0x6c25, - 0x6c22, 0x6c1f, 0x6c1b, 0x6c18, 0x6c15, 0x6c11, 0x6c0e, 0x6c0a, - 0x6c07, 0x6c04, 0x6c00, 0x6bfd, 0x6bfa, 0x6bf6, 0x6bf3, 0x6bef, - 0x6bec, 0x6be9, 0x6be5, 0x6be2, 0x6bdf, 0x6bdb, 0x6bd8, 0x6bd4, - 0x6bd1, 0x6bce, 0x6bca, 0x6bc7, 0x6bc3, 0x6bc0, 0x6bbd, 0x6bb9, - 0x6bb6, 0x6bb2, 0x6baf, 0x6bac, 0x6ba8, 0x6ba5, 0x6ba1, 0x6b9e, - 0x6b9b, 0x6b97, 0x6b94, 0x6b90, 0x6b8d, 0x6b8a, 0x6b86, 0x6b83, - 0x6b7f, 0x6b7c, 0x6b79, 0x6b75, 0x6b72, 0x6b6e, 0x6b6b, 0x6b68, - 0x6b64, 0x6b61, 0x6b5d, 0x6b5a, 0x6b56, 0x6b53, 0x6b50, 0x6b4c, - 0x6b49, 0x6b45, 0x6b42, 0x6b3e, 0x6b3b, 0x6b38, 0x6b34, 0x6b31, - 0x6b2d, 0x6b2a, 0x6b26, 0x6b23, 0x6b20, 0x6b1c, 0x6b19, 0x6b15, - 0x6b12, 0x6b0e, 0x6b0b, 0x6b07, 0x6b04, 0x6b01, 0x6afd, 0x6afa, - 0x6af6, 0x6af3, 0x6aef, 0x6aec, 0x6ae8, 0x6ae5, 0x6ae1, 0x6ade, - 0x6adb, 0x6ad7, 0x6ad4, 0x6ad0, 0x6acd, 0x6ac9, 0x6ac6, 0x6ac2, - 0x6abf, 0x6abb, 0x6ab8, 0x6ab4, 0x6ab1, 0x6aae, 0x6aaa, 0x6aa7, - 0x6aa3, 0x6aa0, 0x6a9c, 0x6a99, 0x6a95, 0x6a92, 0x6a8e, 0x6a8b, - 0x6a87, 0x6a84, 0x6a80, 0x6a7d, 0x6a79, 0x6a76, 0x6a72, 0x6a6f, - 0x6a6b, 0x6a68, 0x6a64, 0x6a61, 0x6a5d, 0x6a5a, 0x6a56, 0x6a53, - 0x6a4f, 0x6a4c, 0x6a48, 0x6a45, 0x6a41, 0x6a3e, 0x6a3a, 0x6a37, - 0x6a33, 0x6a30, 0x6a2c, 0x6a29, 0x6a25, 0x6a22, 0x6a1e, 0x6a1b, - 0x6a17, 0x6a14, 0x6a10, 0x6a0d, 0x6a09, 0x6a06, 0x6a02, 0x69ff, - 0x69fb, 0x69f8, 0x69f4, 0x69f1, 0x69ed, 0x69e9, 0x69e6, 0x69e2, - 0x69df, 0x69db, 0x69d8, 0x69d4, 0x69d1, 0x69cd, 0x69ca, 0x69c6, - 0x69c3, 0x69bf, 0x69bc, 0x69b8, 0x69b4, 0x69b1, 0x69ad, 0x69aa, - 0x69a6, 0x69a3, 0x699f, 0x699c, 0x6998, 0x6995, 0x6991, 0x698d, - 0x698a, 0x6986, 0x6983, 0x697f, 0x697c, 0x6978, 0x6975, 0x6971, - 0x696d, 0x696a, 0x6966, 0x6963, 0x695f, 0x695c, 0x6958, 0x6954, - 0x6951, 0x694d, 0x694a, 0x6946, 0x6943, 0x693f, 0x693b, 0x6938, - 0x6934, 0x6931, 0x692d, 0x692a, 0x6926, 0x6922, 0x691f, 0x691b, - 0x6918, 0x6914, 0x6910, 0x690d, 0x6909, 0x6906, 0x6902, 0x68fe, - 0x68fb, 0x68f7, 0x68f4, 0x68f0, 0x68ec, 0x68e9, 0x68e5, 0x68e2, - 0x68de, 0x68da, 0x68d7, 0x68d3, 0x68d0, 0x68cc, 0x68c8, 0x68c5, - 0x68c1, 0x68be, 0x68ba, 0x68b6, 0x68b3, 0x68af, 0x68ac, 0x68a8, - 0x68a4, 0x68a1, 0x689d, 0x6899, 0x6896, 0x6892, 0x688f, 0x688b, - 0x6887, 0x6884, 0x6880, 0x687c, 0x6879, 0x6875, 0x6872, 0x686e, - 0x686a, 0x6867, 0x6863, 0x685f, 0x685c, 0x6858, 0x6854, 0x6851, - 0x684d, 0x684a, 0x6846, 0x6842, 0x683f, 0x683b, 0x6837, 0x6834, - 0x6830, 0x682c, 0x6829, 0x6825, 0x6821, 0x681e, 0x681a, 0x6816, - 0x6813, 0x680f, 0x680b, 0x6808, 0x6804, 0x6800, 0x67fd, 0x67f9, - 0x67f5, 0x67f2, 0x67ee, 0x67ea, 0x67e7, 0x67e3, 0x67df, 0x67dc, - 0x67d8, 0x67d4, 0x67d1, 0x67cd, 0x67c9, 0x67c6, 0x67c2, 0x67be, - 0x67bb, 0x67b7, 0x67b3, 0x67b0, 0x67ac, 0x67a8, 0x67a5, 0x67a1, - 0x679d, 0x679a, 0x6796, 0x6792, 0x678e, 0x678b, 0x6787, 0x6783, - 0x6780, 0x677c, 0x6778, 0x6775, 0x6771, 0x676d, 0x6769, 0x6766, - 0x6762, 0x675e, 0x675b, 0x6757, 0x6753, 0x6750, 0x674c, 0x6748, - 0x6744, 0x6741, 0x673d, 0x6739, 0x6736, 0x6732, 0x672e, 0x672a, - 0x6727, 0x6723, 0x671f, 0x671c, 0x6718, 0x6714, 0x6710, 0x670d, - 0x6709, 0x6705, 0x6701, 0x66fe, 0x66fa, 0x66f6, 0x66f3, 0x66ef, - 0x66eb, 0x66e7, 0x66e4, 0x66e0, 0x66dc, 0x66d8, 0x66d5, 0x66d1, - 0x66cd, 0x66c9, 0x66c6, 0x66c2, 0x66be, 0x66ba, 0x66b7, 0x66b3, - 0x66af, 0x66ab, 0x66a8, 0x66a4, 0x66a0, 0x669c, 0x6699, 0x6695, - 0x6691, 0x668d, 0x668a, 0x6686, 0x6682, 0x667e, 0x667b, 0x6677, - 0x6673, 0x666f, 0x666b, 0x6668, 0x6664, 0x6660, 0x665c, 0x6659, - 0x6655, 0x6651, 0x664d, 0x664a, 0x6646, 0x6642, 0x663e, 0x663a, - 0x6637, 0x6633, 0x662f, 0x662b, 0x6627, 0x6624, 0x6620, 0x661c, - 0x6618, 0x6615, 0x6611, 0x660d, 0x6609, 0x6605, 0x6602, 0x65fe, - 0x65fa, 0x65f6, 0x65f2, 0x65ef, 0x65eb, 0x65e7, 0x65e3, 0x65df, - 0x65dc, 0x65d8, 0x65d4, 0x65d0, 0x65cc, 0x65c9, 0x65c5, 0x65c1, - 0x65bd, 0x65b9, 0x65b5, 0x65b2, 0x65ae, 0x65aa, 0x65a6, 0x65a2, - 0x659f, 0x659b, 0x6597, 0x6593, 0x658f, 0x658b, 0x6588, 0x6584, - 0x6580, 0x657c, 0x6578, 0x6574, 0x6571, 0x656d, 0x6569, 0x6565, - 0x6561, 0x655d, 0x655a, 0x6556, 0x6552, 0x654e, 0x654a, 0x6546, - 0x6543, 0x653f, 0x653b, 0x6537, 0x6533, 0x652f, 0x652c, 0x6528, - 0x6524, 0x6520, 0x651c, 0x6518, 0x6514, 0x6511, 0x650d, 0x6509, - 0x6505, 0x6501, 0x64fd, 0x64f9, 0x64f6, 0x64f2, 0x64ee, 0x64ea, - 0x64e6, 0x64e2, 0x64de, 0x64db, 0x64d7, 0x64d3, 0x64cf, 0x64cb, - 0x64c7, 0x64c3, 0x64bf, 0x64bc, 0x64b8, 0x64b4, 0x64b0, 0x64ac, - 0x64a8, 0x64a4, 0x64a0, 0x649c, 0x6499, 0x6495, 0x6491, 0x648d, - 0x6489, 0x6485, 0x6481, 0x647d, 0x6479, 0x6476, 0x6472, 0x646e, - 0x646a, 0x6466, 0x6462, 0x645e, 0x645a, 0x6456, 0x6453, 0x644f, - 0x644b, 0x6447, 0x6443, 0x643f, 0x643b, 0x6437, 0x6433, 0x642f, - 0x642b, 0x6428, 0x6424, 0x6420, 0x641c, 0x6418, 0x6414, 0x6410, - 0x640c, 0x6408, 0x6404, 0x6400, 0x63fc, 0x63f9, 0x63f5, 0x63f1, - 0x63ed, 0x63e9, 0x63e5, 0x63e1, 0x63dd, 0x63d9, 0x63d5, 0x63d1, - 0x63cd, 0x63c9, 0x63c5, 0x63c1, 0x63be, 0x63ba, 0x63b6, 0x63b2, - 0x63ae, 0x63aa, 0x63a6, 0x63a2, 0x639e, 0x639a, 0x6396, 0x6392, - 0x638e, 0x638a, 0x6386, 0x6382, 0x637e, 0x637a, 0x6377, 0x6373, - 0x636f, 0x636b, 0x6367, 0x6363, 0x635f, 0x635b, 0x6357, 0x6353, - 0x634f, 0x634b, 0x6347, 0x6343, 0x633f, 0x633b, 0x6337, 0x6333, - 0x632f, 0x632b, 0x6327, 0x6323, 0x631f, 0x631b, 0x6317, 0x6313, - 0x630f, 0x630b, 0x6307, 0x6303, 0x62ff, 0x62fb, 0x62f7, 0x62f3, - 0x62f0, 0x62ec, 0x62e8, 0x62e4, 0x62e0, 0x62dc, 0x62d8, 0x62d4, - 0x62d0, 0x62cc, 0x62c8, 0x62c4, 0x62c0, 0x62bc, 0x62b8, 0x62b4, - 0x62b0, 0x62ac, 0x62a8, 0x62a4, 0x62a0, 0x629c, 0x6298, 0x6294, - 0x6290, 0x628c, 0x6288, 0x6284, 0x6280, 0x627c, 0x6278, 0x6273, - 0x626f, 0x626b, 0x6267, 0x6263, 0x625f, 0x625b, 0x6257, 0x6253, - 0x624f, 0x624b, 0x6247, 0x6243, 0x623f, 0x623b, 0x6237, 0x6233, - 0x622f, 0x622b, 0x6227, 0x6223, 0x621f, 0x621b, 0x6217, 0x6213, - 0x620f, 0x620b, 0x6207, 0x6203, 0x61ff, 0x61fb, 0x61f7, 0x61f3, - 0x61ee, 0x61ea, 0x61e6, 0x61e2, 0x61de, 0x61da, 0x61d6, 0x61d2, - 0x61ce, 0x61ca, 0x61c6, 0x61c2, 0x61be, 0x61ba, 0x61b6, 0x61b2, - 0x61ae, 0x61aa, 0x61a6, 0x61a1, 0x619d, 0x6199, 0x6195, 0x6191, - 0x618d, 0x6189, 0x6185, 0x6181, 0x617d, 0x6179, 0x6175, 0x6171, - 0x616d, 0x6168, 0x6164, 0x6160, 0x615c, 0x6158, 0x6154, 0x6150, - 0x614c, 0x6148, 0x6144, 0x6140, 0x613c, 0x6137, 0x6133, 0x612f, - 0x612b, 0x6127, 0x6123, 0x611f, 0x611b, 0x6117, 0x6113, 0x610f, - 0x610a, 0x6106, 0x6102, 0x60fe, 0x60fa, 0x60f6, 0x60f2, 0x60ee, - 0x60ea, 0x60e6, 0x60e1, 0x60dd, 0x60d9, 0x60d5, 0x60d1, 0x60cd, - 0x60c9, 0x60c5, 0x60c1, 0x60bc, 0x60b8, 0x60b4, 0x60b0, 0x60ac, - 0x60a8, 0x60a4, 0x60a0, 0x609c, 0x6097, 0x6093, 0x608f, 0x608b, - 0x6087, 0x6083, 0x607f, 0x607b, 0x6076, 0x6072, 0x606e, 0x606a, - 0x6066, 0x6062, 0x605e, 0x6059, 0x6055, 0x6051, 0x604d, 0x6049, - 0x6045, 0x6041, 0x603c, 0x6038, 0x6034, 0x6030, 0x602c, 0x6028, - 0x6024, 0x601f, 0x601b, 0x6017, 0x6013, 0x600f, 0x600b, 0x6007, - 0x6002, 0x5ffe, 0x5ffa, 0x5ff6, 0x5ff2, 0x5fee, 0x5fe9, 0x5fe5, - 0x5fe1, 0x5fdd, 0x5fd9, 0x5fd5, 0x5fd0, 0x5fcc, 0x5fc8, 0x5fc4, - 0x5fc0, 0x5fbc, 0x5fb7, 0x5fb3, 0x5faf, 0x5fab, 0x5fa7, 0x5fa3, - 0x5f9e, 0x5f9a, 0x5f96, 0x5f92, 0x5f8e, 0x5f8a, 0x5f85, 0x5f81, - 0x5f7d, 0x5f79, 0x5f75, 0x5f70, 0x5f6c, 0x5f68, 0x5f64, 0x5f60, - 0x5f5b, 0x5f57, 0x5f53, 0x5f4f, 0x5f4b, 0x5f46, 0x5f42, 0x5f3e, - 0x5f3a, 0x5f36, 0x5f31, 0x5f2d, 0x5f29, 0x5f25, 0x5f21, 0x5f1c, - 0x5f18, 0x5f14, 0x5f10, 0x5f0c, 0x5f07, 0x5f03, 0x5eff, 0x5efb, - 0x5ef7, 0x5ef2, 0x5eee, 0x5eea, 0x5ee6, 0x5ee2, 0x5edd, 0x5ed9, - 0x5ed5, 0x5ed1, 0x5ecc, 0x5ec8, 0x5ec4, 0x5ec0, 0x5ebc, 0x5eb7, - 0x5eb3, 0x5eaf, 0x5eab, 0x5ea6, 0x5ea2, 0x5e9e, 0x5e9a, 0x5e95, - 0x5e91, 0x5e8d, 0x5e89, 0x5e85, 0x5e80, 0x5e7c, 0x5e78, 0x5e74, - 0x5e6f, 0x5e6b, 0x5e67, 0x5e63, 0x5e5e, 0x5e5a, 0x5e56, 0x5e52, - 0x5e4d, 0x5e49, 0x5e45, 0x5e41, 0x5e3c, 0x5e38, 0x5e34, 0x5e30, - 0x5e2b, 0x5e27, 0x5e23, 0x5e1f, 0x5e1a, 0x5e16, 0x5e12, 0x5e0e, - 0x5e09, 0x5e05, 0x5e01, 0x5dfd, 0x5df8, 0x5df4, 0x5df0, 0x5deb, - 0x5de7, 0x5de3, 0x5ddf, 0x5dda, 0x5dd6, 0x5dd2, 0x5dce, 0x5dc9, - 0x5dc5, 0x5dc1, 0x5dbc, 0x5db8, 0x5db4, 0x5db0, 0x5dab, 0x5da7, - 0x5da3, 0x5d9e, 0x5d9a, 0x5d96, 0x5d92, 0x5d8d, 0x5d89, 0x5d85, - 0x5d80, 0x5d7c, 0x5d78, 0x5d74, 0x5d6f, 0x5d6b, 0x5d67, 0x5d62, - 0x5d5e, 0x5d5a, 0x5d55, 0x5d51, 0x5d4d, 0x5d49, 0x5d44, 0x5d40, - 0x5d3c, 0x5d37, 0x5d33, 0x5d2f, 0x5d2a, 0x5d26, 0x5d22, 0x5d1e, - 0x5d19, 0x5d15, 0x5d11, 0x5d0c, 0x5d08, 0x5d04, 0x5cff, 0x5cfb, - 0x5cf7, 0x5cf2, 0x5cee, 0x5cea, 0x5ce5, 0x5ce1, 0x5cdd, 0x5cd8, - 0x5cd4, 0x5cd0, 0x5ccb, 0x5cc7, 0x5cc3, 0x5cbe, 0x5cba, 0x5cb6, - 0x5cb1, 0x5cad, 0x5ca9, 0x5ca4, 0x5ca0, 0x5c9c, 0x5c97, 0x5c93, - 0x5c8f, 0x5c8a, 0x5c86, 0x5c82, 0x5c7d, 0x5c79, 0x5c75, 0x5c70, - 0x5c6c, 0x5c68, 0x5c63, 0x5c5f, 0x5c5b, 0x5c56, 0x5c52, 0x5c4e, - 0x5c49, 0x5c45, 0x5c41, 0x5c3c, 0x5c38, 0x5c33, 0x5c2f, 0x5c2b, - 0x5c26, 0x5c22, 0x5c1e, 0x5c19, 0x5c15, 0x5c11, 0x5c0c, 0x5c08, - 0x5c03, 0x5bff, 0x5bfb, 0x5bf6, 0x5bf2, 0x5bee, 0x5be9, 0x5be5, - 0x5be0, 0x5bdc, 0x5bd8, 0x5bd3, 0x5bcf, 0x5bcb, 0x5bc6, 0x5bc2, - 0x5bbd, 0x5bb9, 0x5bb5, 0x5bb0, 0x5bac, 0x5ba8, 0x5ba3, 0x5b9f, - 0x5b9a, 0x5b96, 0x5b92, 0x5b8d, 0x5b89, 0x5b84, 0x5b80, 0x5b7c, - 0x5b77, 0x5b73, 0x5b6e, 0x5b6a, 0x5b66, 0x5b61, 0x5b5d, 0x5b58, - 0x5b54, 0x5b50, 0x5b4b, 0x5b47, 0x5b42, 0x5b3e, 0x5b3a, 0x5b35, - 0x5b31, 0x5b2c, 0x5b28, 0x5b24, 0x5b1f, 0x5b1b, 0x5b16, 0x5b12, - 0x5b0e, 0x5b09, 0x5b05, 0x5b00, 0x5afc, 0x5af7, 0x5af3, 0x5aef, - 0x5aea, 0x5ae6, 0x5ae1, 0x5add, 0x5ad8, 0x5ad4, 0x5ad0, 0x5acb, - 0x5ac7, 0x5ac2, 0x5abe, 0x5ab9, 0x5ab5, 0x5ab1, 0x5aac, 0x5aa8, - 0x5aa3, 0x5a9f, 0x5a9a, 0x5a96, 0x5a92, 0x5a8d, 0x5a89, 0x5a84, - 0x5a80, 0x5a7b, 0x5a77, 0x5a72, 0x5a6e, 0x5a6a, 0x5a65, 0x5a61, - 0x5a5c, 0x5a58, 0x5a53, 0x5a4f, 0x5a4a, 0x5a46, 0x5a41, 0x5a3d, - 0x5a39, 0x5a34, 0x5a30, 0x5a2b, 0x5a27, 0x5a22, 0x5a1e, 0x5a19, - 0x5a15, 0x5a10, 0x5a0c, 0x5a07, 0x5a03, 0x59ff, 0x59fa, 0x59f6, - 0x59f1, 0x59ed, 0x59e8, 0x59e4, 0x59df, 0x59db, 0x59d6, 0x59d2, - 0x59cd, 0x59c9, 0x59c4, 0x59c0, 0x59bb, 0x59b7, 0x59b2, 0x59ae, - 0x59a9, 0x59a5, 0x59a1, 0x599c, 0x5998, 0x5993, 0x598f, 0x598a, - 0x5986, 0x5981, 0x597d, 0x5978, 0x5974, 0x596f, 0x596b, 0x5966, - 0x5962, 0x595d, 0x5959, 0x5954, 0x5950, 0x594b, 0x5947, 0x5942, - 0x593e, 0x5939, 0x5935, 0x5930, 0x592c, 0x5927, 0x5923, 0x591e, - 0x591a, 0x5915, 0x5911, 0x590c, 0x5908, 0x5903, 0x58fe, 0x58fa, - 0x58f5, 0x58f1, 0x58ec, 0x58e8, 0x58e3, 0x58df, 0x58da, 0x58d6, - 0x58d1, 0x58cd, 0x58c8, 0x58c4, 0x58bf, 0x58bb, 0x58b6, 0x58b2, - 0x58ad, 0x58a9, 0x58a4, 0x589f, 0x589b, 0x5896, 0x5892, 0x588d, - 0x5889, 0x5884, 0x5880, 0x587b, 0x5877, 0x5872, 0x586e, 0x5869, - 0x5864, 0x5860, 0x585b, 0x5857, 0x5852, 0x584e, 0x5849, 0x5845, - 0x5840, 0x583c, 0x5837, 0x5832, 0x582e, 0x5829, 0x5825, 0x5820, - 0x581c, 0x5817, 0x5813, 0x580e, 0x5809, 0x5805, 0x5800, 0x57fc, - 0x57f7, 0x57f3, 0x57ee, 0x57e9, 0x57e5, 0x57e0, 0x57dc, 0x57d7, - 0x57d3, 0x57ce, 0x57c9, 0x57c5, 0x57c0, 0x57bc, 0x57b7, 0x57b3, - 0x57ae, 0x57a9, 0x57a5, 0x57a0, 0x579c, 0x5797, 0x5793, 0x578e, - 0x5789, 0x5785, 0x5780, 0x577c, 0x5777, 0x5772, 0x576e, 0x5769, - 0x5765, 0x5760, 0x575c, 0x5757, 0x5752, 0x574e, 0x5749, 0x5745, - 0x5740, 0x573b, 0x5737, 0x5732, 0x572e, 0x5729, 0x5724, 0x5720, - 0x571b, 0x5717, 0x5712, 0x570d, 0x5709, 0x5704, 0x56ff, 0x56fb, - 0x56f6, 0x56f2, 0x56ed, 0x56e8, 0x56e4, 0x56df, 0x56db, 0x56d6, - 0x56d1, 0x56cd, 0x56c8, 0x56c4, 0x56bf, 0x56ba, 0x56b6, 0x56b1, - 0x56ac, 0x56a8, 0x56a3, 0x569f, 0x569a, 0x5695, 0x5691, 0x568c, - 0x5687, 0x5683, 0x567e, 0x5679, 0x5675, 0x5670, 0x566c, 0x5667, - 0x5662, 0x565e, 0x5659, 0x5654, 0x5650, 0x564b, 0x5646, 0x5642, - 0x563d, 0x5639, 0x5634, 0x562f, 0x562b, 0x5626, 0x5621, 0x561d, - 0x5618, 0x5613, 0x560f, 0x560a, 0x5605, 0x5601, 0x55fc, 0x55f7, - 0x55f3, 0x55ee, 0x55ea, 0x55e5, 0x55e0, 0x55dc, 0x55d7, 0x55d2, - 0x55ce, 0x55c9, 0x55c4, 0x55c0, 0x55bb, 0x55b6, 0x55b2, 0x55ad, - 0x55a8, 0x55a4, 0x559f, 0x559a, 0x5596, 0x5591, 0x558c, 0x5588, - 0x5583, 0x557e, 0x5579, 0x5575, 0x5570, 0x556b, 0x5567, 0x5562, - 0x555d, 0x5559, 0x5554, 0x554f, 0x554b, 0x5546, 0x5541, 0x553d, - 0x5538, 0x5533, 0x552f, 0x552a, 0x5525, 0x5520, 0x551c, 0x5517, - 0x5512, 0x550e, 0x5509, 0x5504, 0x5500, 0x54fb, 0x54f6, 0x54f2, - 0x54ed, 0x54e8, 0x54e3, 0x54df, 0x54da, 0x54d5, 0x54d1, 0x54cc, - 0x54c7, 0x54c2, 0x54be, 0x54b9, 0x54b4, 0x54b0, 0x54ab, 0x54a6, - 0x54a2, 0x549d, 0x5498, 0x5493, 0x548f, 0x548a, 0x5485, 0x5480, - 0x547c, 0x5477, 0x5472, 0x546e, 0x5469, 0x5464, 0x545f, 0x545b, - 0x5456, 0x5451, 0x544d, 0x5448, 0x5443, 0x543e, 0x543a, 0x5435, - 0x5430, 0x542b, 0x5427, 0x5422, 0x541d, 0x5418, 0x5414, 0x540f, - 0x540a, 0x5406, 0x5401, 0x53fc, 0x53f7, 0x53f3, 0x53ee, 0x53e9, - 0x53e4, 0x53e0, 0x53db, 0x53d6, 0x53d1, 0x53cd, 0x53c8, 0x53c3, - 0x53be, 0x53ba, 0x53b5, 0x53b0, 0x53ab, 0x53a7, 0x53a2, 0x539d, - 0x5398, 0x5394, 0x538f, 0x538a, 0x5385, 0x5380, 0x537c, 0x5377, - 0x5372, 0x536d, 0x5369, 0x5364, 0x535f, 0x535a, 0x5356, 0x5351, - 0x534c, 0x5347, 0x5343, 0x533e, 0x5339, 0x5334, 0x532f, 0x532b, - 0x5326, 0x5321, 0x531c, 0x5318, 0x5313, 0x530e, 0x5309, 0x5304, - 0x5300, 0x52fb, 0x52f6, 0x52f1, 0x52ec, 0x52e8, 0x52e3, 0x52de, - 0x52d9, 0x52d5, 0x52d0, 0x52cb, 0x52c6, 0x52c1, 0x52bd, 0x52b8, - 0x52b3, 0x52ae, 0x52a9, 0x52a5, 0x52a0, 0x529b, 0x5296, 0x5291, - 0x528d, 0x5288, 0x5283, 0x527e, 0x5279, 0x5275, 0x5270, 0x526b, - 0x5266, 0x5261, 0x525d, 0x5258, 0x5253, 0x524e, 0x5249, 0x5244, - 0x5240, 0x523b, 0x5236, 0x5231, 0x522c, 0x5228, 0x5223, 0x521e, - 0x5219, 0x5214, 0x520f, 0x520b, 0x5206, 0x5201, 0x51fc, 0x51f7, - 0x51f3, 0x51ee, 0x51e9, 0x51e4, 0x51df, 0x51da, 0x51d6, 0x51d1, - 0x51cc, 0x51c7, 0x51c2, 0x51bd, 0x51b9, 0x51b4, 0x51af, 0x51aa, - 0x51a5, 0x51a0, 0x519c, 0x5197, 0x5192, 0x518d, 0x5188, 0x5183, - 0x517e, 0x517a, 0x5175, 0x5170, 0x516b, 0x5166, 0x5161, 0x515d, - 0x5158, 0x5153, 0x514e, 0x5149, 0x5144, 0x513f, 0x513b, 0x5136, - 0x5131, 0x512c, 0x5127, 0x5122, 0x511d, 0x5119, 0x5114, 0x510f, - 0x510a, 0x5105, 0x5100, 0x50fb, 0x50f7, 0x50f2, 0x50ed, 0x50e8, - 0x50e3, 0x50de, 0x50d9, 0x50d4, 0x50d0, 0x50cb, 0x50c6, 0x50c1, - 0x50bc, 0x50b7, 0x50b2, 0x50ad, 0x50a9, 0x50a4, 0x509f, 0x509a, - 0x5095, 0x5090, 0x508b, 0x5086, 0x5082, 0x507d, 0x5078, 0x5073, - 0x506e, 0x5069, 0x5064, 0x505f, 0x505a, 0x5056, 0x5051, 0x504c, - 0x5047, 0x5042, 0x503d, 0x5038, 0x5033, 0x502e, 0x5029, 0x5025, - 0x5020, 0x501b, 0x5016, 0x5011, 0x500c, 0x5007, 0x5002, 0x4ffd, - 0x4ff8, 0x4ff4, 0x4fef, 0x4fea, 0x4fe5, 0x4fe0, 0x4fdb, 0x4fd6, - 0x4fd1, 0x4fcc, 0x4fc7, 0x4fc2, 0x4fbe, 0x4fb9, 0x4fb4, 0x4faf, - 0x4faa, 0x4fa5, 0x4fa0, 0x4f9b, 0x4f96, 0x4f91, 0x4f8c, 0x4f87, - 0x4f82, 0x4f7e, 0x4f79, 0x4f74, 0x4f6f, 0x4f6a, 0x4f65, 0x4f60, - 0x4f5b, 0x4f56, 0x4f51, 0x4f4c, 0x4f47, 0x4f42, 0x4f3d, 0x4f39, - 0x4f34, 0x4f2f, 0x4f2a, 0x4f25, 0x4f20, 0x4f1b, 0x4f16, 0x4f11, - 0x4f0c, 0x4f07, 0x4f02, 0x4efd, 0x4ef8, 0x4ef3, 0x4eee, 0x4ee9, - 0x4ee5, 0x4ee0, 0x4edb, 0x4ed6, 0x4ed1, 0x4ecc, 0x4ec7, 0x4ec2, - 0x4ebd, 0x4eb8, 0x4eb3, 0x4eae, 0x4ea9, 0x4ea4, 0x4e9f, 0x4e9a, - 0x4e95, 0x4e90, 0x4e8b, 0x4e86, 0x4e81, 0x4e7c, 0x4e78, 0x4e73, - 0x4e6e, 0x4e69, 0x4e64, 0x4e5f, 0x4e5a, 0x4e55, 0x4e50, 0x4e4b, - 0x4e46, 0x4e41, 0x4e3c, 0x4e37, 0x4e32, 0x4e2d, 0x4e28, 0x4e23, - 0x4e1e, 0x4e19, 0x4e14, 0x4e0f, 0x4e0a, 0x4e05, 0x4e00, 0x4dfb, - 0x4df6, 0x4df1, 0x4dec, 0x4de7, 0x4de2, 0x4ddd, 0x4dd8, 0x4dd3, - 0x4dce, 0x4dc9, 0x4dc4, 0x4dbf, 0x4dba, 0x4db5, 0x4db0, 0x4dab, - 0x4da6, 0x4da1, 0x4d9c, 0x4d97, 0x4d92, 0x4d8d, 0x4d88, 0x4d83, - 0x4d7e, 0x4d79, 0x4d74, 0x4d6f, 0x4d6a, 0x4d65, 0x4d60, 0x4d5b, - 0x4d56, 0x4d51, 0x4d4c, 0x4d47, 0x4d42, 0x4d3d, 0x4d38, 0x4d33, - 0x4d2e, 0x4d29, 0x4d24, 0x4d1f, 0x4d1a, 0x4d15, 0x4d10, 0x4d0b, - 0x4d06, 0x4d01, 0x4cfc, 0x4cf7, 0x4cf2, 0x4ced, 0x4ce8, 0x4ce3, - 0x4cde, 0x4cd9, 0x4cd4, 0x4ccf, 0x4cca, 0x4cc5, 0x4cc0, 0x4cbb, - 0x4cb6, 0x4cb1, 0x4cac, 0x4ca7, 0x4ca2, 0x4c9d, 0x4c98, 0x4c93, - 0x4c8e, 0x4c88, 0x4c83, 0x4c7e, 0x4c79, 0x4c74, 0x4c6f, 0x4c6a, - 0x4c65, 0x4c60, 0x4c5b, 0x4c56, 0x4c51, 0x4c4c, 0x4c47, 0x4c42, - 0x4c3d, 0x4c38, 0x4c33, 0x4c2e, 0x4c29, 0x4c24, 0x4c1f, 0x4c1a, - 0x4c14, 0x4c0f, 0x4c0a, 0x4c05, 0x4c00, 0x4bfb, 0x4bf6, 0x4bf1, - 0x4bec, 0x4be7, 0x4be2, 0x4bdd, 0x4bd8, 0x4bd3, 0x4bce, 0x4bc9, - 0x4bc4, 0x4bbe, 0x4bb9, 0x4bb4, 0x4baf, 0x4baa, 0x4ba5, 0x4ba0, - 0x4b9b, 0x4b96, 0x4b91, 0x4b8c, 0x4b87, 0x4b82, 0x4b7d, 0x4b77, - 0x4b72, 0x4b6d, 0x4b68, 0x4b63, 0x4b5e, 0x4b59, 0x4b54, 0x4b4f, - 0x4b4a, 0x4b45, 0x4b40, 0x4b3b, 0x4b35, 0x4b30, 0x4b2b, 0x4b26, - 0x4b21, 0x4b1c, 0x4b17, 0x4b12, 0x4b0d, 0x4b08, 0x4b03, 0x4afd, - 0x4af8, 0x4af3, 0x4aee, 0x4ae9, 0x4ae4, 0x4adf, 0x4ada, 0x4ad5, - 0x4ad0, 0x4acb, 0x4ac5, 0x4ac0, 0x4abb, 0x4ab6, 0x4ab1, 0x4aac, - 0x4aa7, 0x4aa2, 0x4a9d, 0x4a97, 0x4a92, 0x4a8d, 0x4a88, 0x4a83, - 0x4a7e, 0x4a79, 0x4a74, 0x4a6f, 0x4a6a, 0x4a64, 0x4a5f, 0x4a5a, - 0x4a55, 0x4a50, 0x4a4b, 0x4a46, 0x4a41, 0x4a3b, 0x4a36, 0x4a31, - 0x4a2c, 0x4a27, 0x4a22, 0x4a1d, 0x4a18, 0x4a12, 0x4a0d, 0x4a08, - 0x4a03, 0x49fe, 0x49f9, 0x49f4, 0x49ef, 0x49e9, 0x49e4, 0x49df, - 0x49da, 0x49d5, 0x49d0, 0x49cb, 0x49c6, 0x49c0, 0x49bb, 0x49b6, - 0x49b1, 0x49ac, 0x49a7, 0x49a2, 0x499c, 0x4997, 0x4992, 0x498d, - 0x4988, 0x4983, 0x497e, 0x4978, 0x4973, 0x496e, 0x4969, 0x4964, - 0x495f, 0x495a, 0x4954, 0x494f, 0x494a, 0x4945, 0x4940, 0x493b, - 0x4936, 0x4930, 0x492b, 0x4926, 0x4921, 0x491c, 0x4917, 0x4911, - 0x490c, 0x4907, 0x4902, 0x48fd, 0x48f8, 0x48f2, 0x48ed, 0x48e8, - 0x48e3, 0x48de, 0x48d9, 0x48d3, 0x48ce, 0x48c9, 0x48c4, 0x48bf, - 0x48ba, 0x48b4, 0x48af, 0x48aa, 0x48a5, 0x48a0, 0x489b, 0x4895, - 0x4890, 0x488b, 0x4886, 0x4881, 0x487c, 0x4876, 0x4871, 0x486c, - 0x4867, 0x4862, 0x485c, 0x4857, 0x4852, 0x484d, 0x4848, 0x4843, - 0x483d, 0x4838, 0x4833, 0x482e, 0x4829, 0x4823, 0x481e, 0x4819, - 0x4814, 0x480f, 0x4809, 0x4804, 0x47ff, 0x47fa, 0x47f5, 0x47ef, - 0x47ea, 0x47e5, 0x47e0, 0x47db, 0x47d5, 0x47d0, 0x47cb, 0x47c6, - 0x47c1, 0x47bb, 0x47b6, 0x47b1, 0x47ac, 0x47a7, 0x47a1, 0x479c, - 0x4797, 0x4792, 0x478d, 0x4787, 0x4782, 0x477d, 0x4778, 0x4773, - 0x476d, 0x4768, 0x4763, 0x475e, 0x4758, 0x4753, 0x474e, 0x4749, - 0x4744, 0x473e, 0x4739, 0x4734, 0x472f, 0x4729, 0x4724, 0x471f, - 0x471a, 0x4715, 0x470f, 0x470a, 0x4705, 0x4700, 0x46fa, 0x46f5, - 0x46f0, 0x46eb, 0x46e6, 0x46e0, 0x46db, 0x46d6, 0x46d1, 0x46cb, - 0x46c6, 0x46c1, 0x46bc, 0x46b6, 0x46b1, 0x46ac, 0x46a7, 0x46a1, - 0x469c, 0x4697, 0x4692, 0x468d, 0x4687, 0x4682, 0x467d, 0x4678, - 0x4672, 0x466d, 0x4668, 0x4663, 0x465d, 0x4658, 0x4653, 0x464e, - 0x4648, 0x4643, 0x463e, 0x4639, 0x4633, 0x462e, 0x4629, 0x4624, - 0x461e, 0x4619, 0x4614, 0x460e, 0x4609, 0x4604, 0x45ff, 0x45f9, - 0x45f4, 0x45ef, 0x45ea, 0x45e4, 0x45df, 0x45da, 0x45d5, 0x45cf, - 0x45ca, 0x45c5, 0x45c0, 0x45ba, 0x45b5, 0x45b0, 0x45aa, 0x45a5, - 0x45a0, 0x459b, 0x4595, 0x4590, 0x458b, 0x4586, 0x4580, 0x457b, - 0x4576, 0x4570, 0x456b, 0x4566, 0x4561, 0x455b, 0x4556, 0x4551, - 0x454b, 0x4546, 0x4541, 0x453c, 0x4536, 0x4531, 0x452c, 0x4526, - 0x4521, 0x451c, 0x4517, 0x4511, 0x450c, 0x4507, 0x4501, 0x44fc, - 0x44f7, 0x44f2, 0x44ec, 0x44e7, 0x44e2, 0x44dc, 0x44d7, 0x44d2, - 0x44cd, 0x44c7, 0x44c2, 0x44bd, 0x44b7, 0x44b2, 0x44ad, 0x44a7, - 0x44a2, 0x449d, 0x4497, 0x4492, 0x448d, 0x4488, 0x4482, 0x447d, - 0x4478, 0x4472, 0x446d, 0x4468, 0x4462, 0x445d, 0x4458, 0x4452, - 0x444d, 0x4448, 0x4443, 0x443d, 0x4438, 0x4433, 0x442d, 0x4428, - 0x4423, 0x441d, 0x4418, 0x4413, 0x440d, 0x4408, 0x4403, 0x43fd, - 0x43f8, 0x43f3, 0x43ed, 0x43e8, 0x43e3, 0x43dd, 0x43d8, 0x43d3, - 0x43cd, 0x43c8, 0x43c3, 0x43bd, 0x43b8, 0x43b3, 0x43ad, 0x43a8, - 0x43a3, 0x439d, 0x4398, 0x4393, 0x438d, 0x4388, 0x4383, 0x437d, - 0x4378, 0x4373, 0x436d, 0x4368, 0x4363, 0x435d, 0x4358, 0x4353, - 0x434d, 0x4348, 0x4343, 0x433d, 0x4338, 0x4333, 0x432d, 0x4328, - 0x4323, 0x431d, 0x4318, 0x4313, 0x430d, 0x4308, 0x4302, 0x42fd, - 0x42f8, 0x42f2, 0x42ed, 0x42e8, 0x42e2, 0x42dd, 0x42d8, 0x42d2, - 0x42cd, 0x42c8, 0x42c2, 0x42bd, 0x42b7, 0x42b2, 0x42ad, 0x42a7, - 0x42a2, 0x429d, 0x4297, 0x4292, 0x428d, 0x4287, 0x4282, 0x427c, - 0x4277, 0x4272, 0x426c, 0x4267, 0x4262, 0x425c, 0x4257, 0x4251, - 0x424c, 0x4247, 0x4241, 0x423c, 0x4237, 0x4231, 0x422c, 0x4226, - 0x4221, 0x421c, 0x4216, 0x4211, 0x420c, 0x4206, 0x4201, 0x41fb, - 0x41f6, 0x41f1, 0x41eb, 0x41e6, 0x41e0, 0x41db, 0x41d6, 0x41d0, - 0x41cb, 0x41c6, 0x41c0, 0x41bb, 0x41b5, 0x41b0, 0x41ab, 0x41a5, - 0x41a0, 0x419a, 0x4195, 0x4190, 0x418a, 0x4185, 0x417f, 0x417a, - 0x4175, 0x416f, 0x416a, 0x4164, 0x415f, 0x415a, 0x4154, 0x414f, - 0x4149, 0x4144, 0x413f, 0x4139, 0x4134, 0x412e, 0x4129, 0x4124, - 0x411e, 0x4119, 0x4113, 0x410e, 0x4108, 0x4103, 0x40fe, 0x40f8, - 0x40f3, 0x40ed, 0x40e8, 0x40e3, 0x40dd, 0x40d8, 0x40d2, 0x40cd, - 0x40c8, 0x40c2, 0x40bd, 0x40b7, 0x40b2, 0x40ac, 0x40a7, 0x40a2, - 0x409c, 0x4097, 0x4091, 0x408c, 0x4086, 0x4081, 0x407c, 0x4076, - 0x4071, 0x406b, 0x4066, 0x4060, 0x405b, 0x4056, 0x4050, 0x404b, - 0x4045, 0x4040, 0x403a, 0x4035, 0x4030, 0x402a, 0x4025, 0x401f, - 0x401a, 0x4014, 0x400f, 0x4009, 0x4004, 0x3fff, 0x3ff9, 0x3ff4, - 0x3fee, 0x3fe9, 0x3fe3, 0x3fde, 0x3fd8, 0x3fd3, 0x3fce, 0x3fc8, - 0x3fc3, 0x3fbd, 0x3fb8, 0x3fb2, 0x3fad, 0x3fa7, 0x3fa2, 0x3f9d, - 0x3f97, 0x3f92, 0x3f8c, 0x3f87, 0x3f81, 0x3f7c, 0x3f76, 0x3f71, - 0x3f6b, 0x3f66, 0x3f61, 0x3f5b, 0x3f56, 0x3f50, 0x3f4b, 0x3f45, - 0x3f40, 0x3f3a, 0x3f35, 0x3f2f, 0x3f2a, 0x3f24, 0x3f1f, 0x3f1a, - 0x3f14, 0x3f0f, 0x3f09, 0x3f04, 0x3efe, 0x3ef9, 0x3ef3, 0x3eee, - 0x3ee8, 0x3ee3, 0x3edd, 0x3ed8, 0x3ed2, 0x3ecd, 0x3ec7, 0x3ec2, - 0x3ebd, 0x3eb7, 0x3eb2, 0x3eac, 0x3ea7, 0x3ea1, 0x3e9c, 0x3e96, - 0x3e91, 0x3e8b, 0x3e86, 0x3e80, 0x3e7b, 0x3e75, 0x3e70, 0x3e6a, - 0x3e65, 0x3e5f, 0x3e5a, 0x3e54, 0x3e4f, 0x3e49, 0x3e44, 0x3e3e, - 0x3e39, 0x3e33, 0x3e2e, 0x3e28, 0x3e23, 0x3e1d, 0x3e18, 0x3e12, - 0x3e0d, 0x3e07, 0x3e02, 0x3dfc, 0x3df7, 0x3df1, 0x3dec, 0x3de6, - 0x3de1, 0x3ddb, 0x3dd6, 0x3dd0, 0x3dcb, 0x3dc5, 0x3dc0, 0x3dba, - 0x3db5, 0x3daf, 0x3daa, 0x3da4, 0x3d9f, 0x3d99, 0x3d94, 0x3d8e, - 0x3d89, 0x3d83, 0x3d7e, 0x3d78, 0x3d73, 0x3d6d, 0x3d68, 0x3d62, - 0x3d5d, 0x3d57, 0x3d52, 0x3d4c, 0x3d47, 0x3d41, 0x3d3c, 0x3d36, - 0x3d31, 0x3d2b, 0x3d26, 0x3d20, 0x3d1b, 0x3d15, 0x3d10, 0x3d0a, - 0x3d04, 0x3cff, 0x3cf9, 0x3cf4, 0x3cee, 0x3ce9, 0x3ce3, 0x3cde, - 0x3cd8, 0x3cd3, 0x3ccd, 0x3cc8, 0x3cc2, 0x3cbd, 0x3cb7, 0x3cb2, - 0x3cac, 0x3ca7, 0x3ca1, 0x3c9b, 0x3c96, 0x3c90, 0x3c8b, 0x3c85, - 0x3c80, 0x3c7a, 0x3c75, 0x3c6f, 0x3c6a, 0x3c64, 0x3c5f, 0x3c59, - 0x3c53, 0x3c4e, 0x3c48, 0x3c43, 0x3c3d, 0x3c38, 0x3c32, 0x3c2d, - 0x3c27, 0x3c22, 0x3c1c, 0x3c16, 0x3c11, 0x3c0b, 0x3c06, 0x3c00, - 0x3bfb, 0x3bf5, 0x3bf0, 0x3bea, 0x3be5, 0x3bdf, 0x3bd9, 0x3bd4, - 0x3bce, 0x3bc9, 0x3bc3, 0x3bbe, 0x3bb8, 0x3bb3, 0x3bad, 0x3ba7, - 0x3ba2, 0x3b9c, 0x3b97, 0x3b91, 0x3b8c, 0x3b86, 0x3b80, 0x3b7b, - 0x3b75, 0x3b70, 0x3b6a, 0x3b65, 0x3b5f, 0x3b5a, 0x3b54, 0x3b4e, - 0x3b49, 0x3b43, 0x3b3e, 0x3b38, 0x3b33, 0x3b2d, 0x3b27, 0x3b22, - 0x3b1c, 0x3b17, 0x3b11, 0x3b0c, 0x3b06, 0x3b00, 0x3afb, 0x3af5, - 0x3af0, 0x3aea, 0x3ae4, 0x3adf, 0x3ad9, 0x3ad4, 0x3ace, 0x3ac9, - 0x3ac3, 0x3abd, 0x3ab8, 0x3ab2, 0x3aad, 0x3aa7, 0x3aa2, 0x3a9c, - 0x3a96, 0x3a91, 0x3a8b, 0x3a86, 0x3a80, 0x3a7a, 0x3a75, 0x3a6f, - 0x3a6a, 0x3a64, 0x3a5e, 0x3a59, 0x3a53, 0x3a4e, 0x3a48, 0x3a42, - 0x3a3d, 0x3a37, 0x3a32, 0x3a2c, 0x3a26, 0x3a21, 0x3a1b, 0x3a16, - 0x3a10, 0x3a0b, 0x3a05, 0x39ff, 0x39fa, 0x39f4, 0x39ee, 0x39e9, - 0x39e3, 0x39de, 0x39d8, 0x39d2, 0x39cd, 0x39c7, 0x39c2, 0x39bc, - 0x39b6, 0x39b1, 0x39ab, 0x39a6, 0x39a0, 0x399a, 0x3995, 0x398f, - 0x398a, 0x3984, 0x397e, 0x3979, 0x3973, 0x396d, 0x3968, 0x3962, - 0x395d, 0x3957, 0x3951, 0x394c, 0x3946, 0x3941, 0x393b, 0x3935, - 0x3930, 0x392a, 0x3924, 0x391f, 0x3919, 0x3914, 0x390e, 0x3908, - 0x3903, 0x38fd, 0x38f7, 0x38f2, 0x38ec, 0x38e7, 0x38e1, 0x38db, - 0x38d6, 0x38d0, 0x38ca, 0x38c5, 0x38bf, 0x38ba, 0x38b4, 0x38ae, - 0x38a9, 0x38a3, 0x389d, 0x3898, 0x3892, 0x388c, 0x3887, 0x3881, - 0x387c, 0x3876, 0x3870, 0x386b, 0x3865, 0x385f, 0x385a, 0x3854, - 0x384e, 0x3849, 0x3843, 0x383d, 0x3838, 0x3832, 0x382d, 0x3827, - 0x3821, 0x381c, 0x3816, 0x3810, 0x380b, 0x3805, 0x37ff, 0x37fa, - 0x37f4, 0x37ee, 0x37e9, 0x37e3, 0x37dd, 0x37d8, 0x37d2, 0x37cc, - 0x37c7, 0x37c1, 0x37bc, 0x37b6, 0x37b0, 0x37ab, 0x37a5, 0x379f, - 0x379a, 0x3794, 0x378e, 0x3789, 0x3783, 0x377d, 0x3778, 0x3772, - 0x376c, 0x3767, 0x3761, 0x375b, 0x3756, 0x3750, 0x374a, 0x3745, - 0x373f, 0x3739, 0x3734, 0x372e, 0x3728, 0x3723, 0x371d, 0x3717, - 0x3712, 0x370c, 0x3706, 0x3701, 0x36fb, 0x36f5, 0x36f0, 0x36ea, - 0x36e4, 0x36df, 0x36d9, 0x36d3, 0x36ce, 0x36c8, 0x36c2, 0x36bc, - 0x36b7, 0x36b1, 0x36ab, 0x36a6, 0x36a0, 0x369a, 0x3695, 0x368f, - 0x3689, 0x3684, 0x367e, 0x3678, 0x3673, 0x366d, 0x3667, 0x3662, - 0x365c, 0x3656, 0x3650, 0x364b, 0x3645, 0x363f, 0x363a, 0x3634, - 0x362e, 0x3629, 0x3623, 0x361d, 0x3618, 0x3612, 0x360c, 0x3606, - 0x3601, 0x35fb, 0x35f5, 0x35f0, 0x35ea, 0x35e4, 0x35df, 0x35d9, - 0x35d3, 0x35cd, 0x35c8, 0x35c2, 0x35bc, 0x35b7, 0x35b1, 0x35ab, - 0x35a6, 0x35a0, 0x359a, 0x3594, 0x358f, 0x3589, 0x3583, 0x357e, - 0x3578, 0x3572, 0x356c, 0x3567, 0x3561, 0x355b, 0x3556, 0x3550, - 0x354a, 0x3544, 0x353f, 0x3539, 0x3533, 0x352e, 0x3528, 0x3522, - 0x351c, 0x3517, 0x3511, 0x350b, 0x3506, 0x3500, 0x34fa, 0x34f4, - 0x34ef, 0x34e9, 0x34e3, 0x34de, 0x34d8, 0x34d2, 0x34cc, 0x34c7, - 0x34c1, 0x34bb, 0x34b6, 0x34b0, 0x34aa, 0x34a4, 0x349f, 0x3499, - 0x3493, 0x348d, 0x3488, 0x3482, 0x347c, 0x3476, 0x3471, 0x346b, - 0x3465, 0x3460, 0x345a, 0x3454, 0x344e, 0x3449, 0x3443, 0x343d, - 0x3437, 0x3432, 0x342c, 0x3426, 0x3420, 0x341b, 0x3415, 0x340f, - 0x340a, 0x3404, 0x33fe, 0x33f8, 0x33f3, 0x33ed, 0x33e7, 0x33e1, - 0x33dc, 0x33d6, 0x33d0, 0x33ca, 0x33c5, 0x33bf, 0x33b9, 0x33b3, - 0x33ae, 0x33a8, 0x33a2, 0x339c, 0x3397, 0x3391, 0x338b, 0x3385, - 0x3380, 0x337a, 0x3374, 0x336e, 0x3369, 0x3363, 0x335d, 0x3357, - 0x3352, 0x334c, 0x3346, 0x3340, 0x333b, 0x3335, 0x332f, 0x3329, - 0x3324, 0x331e, 0x3318, 0x3312, 0x330c, 0x3307, 0x3301, 0x32fb, - 0x32f5, 0x32f0, 0x32ea, 0x32e4, 0x32de, 0x32d9, 0x32d3, 0x32cd, - 0x32c7, 0x32c2, 0x32bc, 0x32b6, 0x32b0, 0x32aa, 0x32a5, 0x329f, - 0x3299, 0x3293, 0x328e, 0x3288, 0x3282, 0x327c, 0x3276, 0x3271, - 0x326b, 0x3265, 0x325f, 0x325a, 0x3254, 0x324e, 0x3248, 0x3243, - 0x323d, 0x3237, 0x3231, 0x322b, 0x3226, 0x3220, 0x321a, 0x3214, - 0x320e, 0x3209, 0x3203, 0x31fd, 0x31f7, 0x31f2, 0x31ec, 0x31e6, - 0x31e0, 0x31da, 0x31d5, 0x31cf, 0x31c9, 0x31c3, 0x31bd, 0x31b8, - 0x31b2, 0x31ac, 0x31a6, 0x31a1, 0x319b, 0x3195, 0x318f, 0x3189, - 0x3184, 0x317e, 0x3178, 0x3172, 0x316c, 0x3167, 0x3161, 0x315b, - 0x3155, 0x314f, 0x314a, 0x3144, 0x313e, 0x3138, 0x3132, 0x312d, - 0x3127, 0x3121, 0x311b, 0x3115, 0x3110, 0x310a, 0x3104, 0x30fe, - 0x30f8, 0x30f3, 0x30ed, 0x30e7, 0x30e1, 0x30db, 0x30d6, 0x30d0, - 0x30ca, 0x30c4, 0x30be, 0x30b8, 0x30b3, 0x30ad, 0x30a7, 0x30a1, - 0x309b, 0x3096, 0x3090, 0x308a, 0x3084, 0x307e, 0x3079, 0x3073, - 0x306d, 0x3067, 0x3061, 0x305b, 0x3056, 0x3050, 0x304a, 0x3044, - 0x303e, 0x3039, 0x3033, 0x302d, 0x3027, 0x3021, 0x301b, 0x3016, - 0x3010, 0x300a, 0x3004, 0x2ffe, 0x2ff8, 0x2ff3, 0x2fed, 0x2fe7, - 0x2fe1, 0x2fdb, 0x2fd6, 0x2fd0, 0x2fca, 0x2fc4, 0x2fbe, 0x2fb8, - 0x2fb3, 0x2fad, 0x2fa7, 0x2fa1, 0x2f9b, 0x2f95, 0x2f90, 0x2f8a, - 0x2f84, 0x2f7e, 0x2f78, 0x2f72, 0x2f6d, 0x2f67, 0x2f61, 0x2f5b, - 0x2f55, 0x2f4f, 0x2f4a, 0x2f44, 0x2f3e, 0x2f38, 0x2f32, 0x2f2c, - 0x2f27, 0x2f21, 0x2f1b, 0x2f15, 0x2f0f, 0x2f09, 0x2f03, 0x2efe, - 0x2ef8, 0x2ef2, 0x2eec, 0x2ee6, 0x2ee0, 0x2edb, 0x2ed5, 0x2ecf, - 0x2ec9, 0x2ec3, 0x2ebd, 0x2eb7, 0x2eb2, 0x2eac, 0x2ea6, 0x2ea0, - 0x2e9a, 0x2e94, 0x2e8e, 0x2e89, 0x2e83, 0x2e7d, 0x2e77, 0x2e71, - 0x2e6b, 0x2e65, 0x2e60, 0x2e5a, 0x2e54, 0x2e4e, 0x2e48, 0x2e42, - 0x2e3c, 0x2e37, 0x2e31, 0x2e2b, 0x2e25, 0x2e1f, 0x2e19, 0x2e13, - 0x2e0e, 0x2e08, 0x2e02, 0x2dfc, 0x2df6, 0x2df0, 0x2dea, 0x2de5, - 0x2ddf, 0x2dd9, 0x2dd3, 0x2dcd, 0x2dc7, 0x2dc1, 0x2dbb, 0x2db6, - 0x2db0, 0x2daa, 0x2da4, 0x2d9e, 0x2d98, 0x2d92, 0x2d8d, 0x2d87, - 0x2d81, 0x2d7b, 0x2d75, 0x2d6f, 0x2d69, 0x2d63, 0x2d5e, 0x2d58, - 0x2d52, 0x2d4c, 0x2d46, 0x2d40, 0x2d3a, 0x2d34, 0x2d2f, 0x2d29, - 0x2d23, 0x2d1d, 0x2d17, 0x2d11, 0x2d0b, 0x2d05, 0x2cff, 0x2cfa, - 0x2cf4, 0x2cee, 0x2ce8, 0x2ce2, 0x2cdc, 0x2cd6, 0x2cd0, 0x2ccb, - 0x2cc5, 0x2cbf, 0x2cb9, 0x2cb3, 0x2cad, 0x2ca7, 0x2ca1, 0x2c9b, - 0x2c96, 0x2c90, 0x2c8a, 0x2c84, 0x2c7e, 0x2c78, 0x2c72, 0x2c6c, - 0x2c66, 0x2c61, 0x2c5b, 0x2c55, 0x2c4f, 0x2c49, 0x2c43, 0x2c3d, - 0x2c37, 0x2c31, 0x2c2b, 0x2c26, 0x2c20, 0x2c1a, 0x2c14, 0x2c0e, - 0x2c08, 0x2c02, 0x2bfc, 0x2bf6, 0x2bf0, 0x2beb, 0x2be5, 0x2bdf, - 0x2bd9, 0x2bd3, 0x2bcd, 0x2bc7, 0x2bc1, 0x2bbb, 0x2bb5, 0x2bb0, - 0x2baa, 0x2ba4, 0x2b9e, 0x2b98, 0x2b92, 0x2b8c, 0x2b86, 0x2b80, - 0x2b7a, 0x2b74, 0x2b6f, 0x2b69, 0x2b63, 0x2b5d, 0x2b57, 0x2b51, - 0x2b4b, 0x2b45, 0x2b3f, 0x2b39, 0x2b33, 0x2b2d, 0x2b28, 0x2b22, - 0x2b1c, 0x2b16, 0x2b10, 0x2b0a, 0x2b04, 0x2afe, 0x2af8, 0x2af2, - 0x2aec, 0x2ae6, 0x2ae1, 0x2adb, 0x2ad5, 0x2acf, 0x2ac9, 0x2ac3, - 0x2abd, 0x2ab7, 0x2ab1, 0x2aab, 0x2aa5, 0x2a9f, 0x2a99, 0x2a94, - 0x2a8e, 0x2a88, 0x2a82, 0x2a7c, 0x2a76, 0x2a70, 0x2a6a, 0x2a64, - 0x2a5e, 0x2a58, 0x2a52, 0x2a4c, 0x2a47, 0x2a41, 0x2a3b, 0x2a35, - 0x2a2f, 0x2a29, 0x2a23, 0x2a1d, 0x2a17, 0x2a11, 0x2a0b, 0x2a05, - 0x29ff, 0x29f9, 0x29f3, 0x29ee, 0x29e8, 0x29e2, 0x29dc, 0x29d6, - 0x29d0, 0x29ca, 0x29c4, 0x29be, 0x29b8, 0x29b2, 0x29ac, 0x29a6, - 0x29a0, 0x299a, 0x2994, 0x298e, 0x2989, 0x2983, 0x297d, 0x2977, - 0x2971, 0x296b, 0x2965, 0x295f, 0x2959, 0x2953, 0x294d, 0x2947, - 0x2941, 0x293b, 0x2935, 0x292f, 0x2929, 0x2923, 0x291d, 0x2918, - 0x2912, 0x290c, 0x2906, 0x2900, 0x28fa, 0x28f4, 0x28ee, 0x28e8, - 0x28e2, 0x28dc, 0x28d6, 0x28d0, 0x28ca, 0x28c4, 0x28be, 0x28b8, - 0x28b2, 0x28ac, 0x28a6, 0x28a0, 0x289a, 0x2895, 0x288f, 0x2889, - 0x2883, 0x287d, 0x2877, 0x2871, 0x286b, 0x2865, 0x285f, 0x2859, - 0x2853, 0x284d, 0x2847, 0x2841, 0x283b, 0x2835, 0x282f, 0x2829, - 0x2823, 0x281d, 0x2817, 0x2811, 0x280b, 0x2805, 0x27ff, 0x27f9, - 0x27f3, 0x27ee, 0x27e8, 0x27e2, 0x27dc, 0x27d6, 0x27d0, 0x27ca, - 0x27c4, 0x27be, 0x27b8, 0x27b2, 0x27ac, 0x27a6, 0x27a0, 0x279a, - 0x2794, 0x278e, 0x2788, 0x2782, 0x277c, 0x2776, 0x2770, 0x276a, - 0x2764, 0x275e, 0x2758, 0x2752, 0x274c, 0x2746, 0x2740, 0x273a, - 0x2734, 0x272e, 0x2728, 0x2722, 0x271c, 0x2716, 0x2710, 0x270a, - 0x2704, 0x26fe, 0x26f8, 0x26f2, 0x26ec, 0x26e7, 0x26e1, 0x26db, - 0x26d5, 0x26cf, 0x26c9, 0x26c3, 0x26bd, 0x26b7, 0x26b1, 0x26ab, - 0x26a5, 0x269f, 0x2699, 0x2693, 0x268d, 0x2687, 0x2681, 0x267b, - 0x2675, 0x266f, 0x2669, 0x2663, 0x265d, 0x2657, 0x2651, 0x264b, - 0x2645, 0x263f, 0x2639, 0x2633, 0x262d, 0x2627, 0x2621, 0x261b, - 0x2615, 0x260f, 0x2609, 0x2603, 0x25fd, 0x25f7, 0x25f1, 0x25eb, - 0x25e5, 0x25df, 0x25d9, 0x25d3, 0x25cd, 0x25c7, 0x25c1, 0x25bb, - 0x25b5, 0x25af, 0x25a9, 0x25a3, 0x259d, 0x2597, 0x2591, 0x258b, - 0x2585, 0x257f, 0x2579, 0x2573, 0x256d, 0x2567, 0x2561, 0x255b, - 0x2555, 0x254f, 0x2549, 0x2543, 0x253d, 0x2537, 0x2531, 0x252b, - 0x2525, 0x251f, 0x2519, 0x2513, 0x250c, 0x2506, 0x2500, 0x24fa, - 0x24f4, 0x24ee, 0x24e8, 0x24e2, 0x24dc, 0x24d6, 0x24d0, 0x24ca, - 0x24c4, 0x24be, 0x24b8, 0x24b2, 0x24ac, 0x24a6, 0x24a0, 0x249a, - 0x2494, 0x248e, 0x2488, 0x2482, 0x247c, 0x2476, 0x2470, 0x246a, - 0x2464, 0x245e, 0x2458, 0x2452, 0x244c, 0x2446, 0x2440, 0x243a, - 0x2434, 0x242e, 0x2428, 0x2422, 0x241c, 0x2416, 0x2410, 0x240a, - 0x2404, 0x23fd, 0x23f7, 0x23f1, 0x23eb, 0x23e5, 0x23df, 0x23d9, - 0x23d3, 0x23cd, 0x23c7, 0x23c1, 0x23bb, 0x23b5, 0x23af, 0x23a9, - 0x23a3, 0x239d, 0x2397, 0x2391, 0x238b, 0x2385, 0x237f, 0x2379, - 0x2373, 0x236d, 0x2367, 0x2361, 0x235b, 0x2355, 0x234e, 0x2348, - 0x2342, 0x233c, 0x2336, 0x2330, 0x232a, 0x2324, 0x231e, 0x2318, - 0x2312, 0x230c, 0x2306, 0x2300, 0x22fa, 0x22f4, 0x22ee, 0x22e8, - 0x22e2, 0x22dc, 0x22d6, 0x22d0, 0x22ca, 0x22c4, 0x22bd, 0x22b7, - 0x22b1, 0x22ab, 0x22a5, 0x229f, 0x2299, 0x2293, 0x228d, 0x2287, - 0x2281, 0x227b, 0x2275, 0x226f, 0x2269, 0x2263, 0x225d, 0x2257, - 0x2251, 0x224a, 0x2244, 0x223e, 0x2238, 0x2232, 0x222c, 0x2226, - 0x2220, 0x221a, 0x2214, 0x220e, 0x2208, 0x2202, 0x21fc, 0x21f6, - 0x21f0, 0x21ea, 0x21e4, 0x21dd, 0x21d7, 0x21d1, 0x21cb, 0x21c5, - 0x21bf, 0x21b9, 0x21b3, 0x21ad, 0x21a7, 0x21a1, 0x219b, 0x2195, - 0x218f, 0x2189, 0x2183, 0x217c, 0x2176, 0x2170, 0x216a, 0x2164, - 0x215e, 0x2158, 0x2152, 0x214c, 0x2146, 0x2140, 0x213a, 0x2134, - 0x212e, 0x2128, 0x2121, 0x211b, 0x2115, 0x210f, 0x2109, 0x2103, - 0x20fd, 0x20f7, 0x20f1, 0x20eb, 0x20e5, 0x20df, 0x20d9, 0x20d3, - 0x20cc, 0x20c6, 0x20c0, 0x20ba, 0x20b4, 0x20ae, 0x20a8, 0x20a2, - 0x209c, 0x2096, 0x2090, 0x208a, 0x2084, 0x207e, 0x2077, 0x2071, - 0x206b, 0x2065, 0x205f, 0x2059, 0x2053, 0x204d, 0x2047, 0x2041, - 0x203b, 0x2035, 0x202e, 0x2028, 0x2022, 0x201c, 0x2016, 0x2010, - 0x200a, 0x2004, 0x1ffe, 0x1ff8, 0x1ff2, 0x1fec, 0x1fe5, 0x1fdf, - 0x1fd9, 0x1fd3, 0x1fcd, 0x1fc7, 0x1fc1, 0x1fbb, 0x1fb5, 0x1faf, - 0x1fa9, 0x1fa3, 0x1f9c, 0x1f96, 0x1f90, 0x1f8a, 0x1f84, 0x1f7e, - 0x1f78, 0x1f72, 0x1f6c, 0x1f66, 0x1f60, 0x1f59, 0x1f53, 0x1f4d, - 0x1f47, 0x1f41, 0x1f3b, 0x1f35, 0x1f2f, 0x1f29, 0x1f23, 0x1f1d, - 0x1f16, 0x1f10, 0x1f0a, 0x1f04, 0x1efe, 0x1ef8, 0x1ef2, 0x1eec, - 0x1ee6, 0x1ee0, 0x1ed9, 0x1ed3, 0x1ecd, 0x1ec7, 0x1ec1, 0x1ebb, - 0x1eb5, 0x1eaf, 0x1ea9, 0x1ea3, 0x1e9c, 0x1e96, 0x1e90, 0x1e8a, - 0x1e84, 0x1e7e, 0x1e78, 0x1e72, 0x1e6c, 0x1e66, 0x1e5f, 0x1e59, - 0x1e53, 0x1e4d, 0x1e47, 0x1e41, 0x1e3b, 0x1e35, 0x1e2f, 0x1e29, - 0x1e22, 0x1e1c, 0x1e16, 0x1e10, 0x1e0a, 0x1e04, 0x1dfe, 0x1df8, - 0x1df2, 0x1deb, 0x1de5, 0x1ddf, 0x1dd9, 0x1dd3, 0x1dcd, 0x1dc7, - 0x1dc1, 0x1dbb, 0x1db4, 0x1dae, 0x1da8, 0x1da2, 0x1d9c, 0x1d96, - 0x1d90, 0x1d8a, 0x1d84, 0x1d7d, 0x1d77, 0x1d71, 0x1d6b, 0x1d65, - 0x1d5f, 0x1d59, 0x1d53, 0x1d4c, 0x1d46, 0x1d40, 0x1d3a, 0x1d34, - 0x1d2e, 0x1d28, 0x1d22, 0x1d1c, 0x1d15, 0x1d0f, 0x1d09, 0x1d03, - 0x1cfd, 0x1cf7, 0x1cf1, 0x1ceb, 0x1ce4, 0x1cde, 0x1cd8, 0x1cd2, - 0x1ccc, 0x1cc6, 0x1cc0, 0x1cba, 0x1cb3, 0x1cad, 0x1ca7, 0x1ca1, - 0x1c9b, 0x1c95, 0x1c8f, 0x1c89, 0x1c83, 0x1c7c, 0x1c76, 0x1c70, - 0x1c6a, 0x1c64, 0x1c5e, 0x1c58, 0x1c51, 0x1c4b, 0x1c45, 0x1c3f, - 0x1c39, 0x1c33, 0x1c2d, 0x1c27, 0x1c20, 0x1c1a, 0x1c14, 0x1c0e, - 0x1c08, 0x1c02, 0x1bfc, 0x1bf6, 0x1bef, 0x1be9, 0x1be3, 0x1bdd, - 0x1bd7, 0x1bd1, 0x1bcb, 0x1bc4, 0x1bbe, 0x1bb8, 0x1bb2, 0x1bac, - 0x1ba6, 0x1ba0, 0x1b9a, 0x1b93, 0x1b8d, 0x1b87, 0x1b81, 0x1b7b, - 0x1b75, 0x1b6f, 0x1b68, 0x1b62, 0x1b5c, 0x1b56, 0x1b50, 0x1b4a, - 0x1b44, 0x1b3d, 0x1b37, 0x1b31, 0x1b2b, 0x1b25, 0x1b1f, 0x1b19, - 0x1b13, 0x1b0c, 0x1b06, 0x1b00, 0x1afa, 0x1af4, 0x1aee, 0x1ae8, - 0x1ae1, 0x1adb, 0x1ad5, 0x1acf, 0x1ac9, 0x1ac3, 0x1abd, 0x1ab6, - 0x1ab0, 0x1aaa, 0x1aa4, 0x1a9e, 0x1a98, 0x1a91, 0x1a8b, 0x1a85, - 0x1a7f, 0x1a79, 0x1a73, 0x1a6d, 0x1a66, 0x1a60, 0x1a5a, 0x1a54, - 0x1a4e, 0x1a48, 0x1a42, 0x1a3b, 0x1a35, 0x1a2f, 0x1a29, 0x1a23, - 0x1a1d, 0x1a17, 0x1a10, 0x1a0a, 0x1a04, 0x19fe, 0x19f8, 0x19f2, - 0x19eb, 0x19e5, 0x19df, 0x19d9, 0x19d3, 0x19cd, 0x19c7, 0x19c0, - 0x19ba, 0x19b4, 0x19ae, 0x19a8, 0x19a2, 0x199b, 0x1995, 0x198f, - 0x1989, 0x1983, 0x197d, 0x1977, 0x1970, 0x196a, 0x1964, 0x195e, - 0x1958, 0x1952, 0x194b, 0x1945, 0x193f, 0x1939, 0x1933, 0x192d, - 0x1926, 0x1920, 0x191a, 0x1914, 0x190e, 0x1908, 0x1901, 0x18fb, - 0x18f5, 0x18ef, 0x18e9, 0x18e3, 0x18dc, 0x18d6, 0x18d0, 0x18ca, - 0x18c4, 0x18be, 0x18b8, 0x18b1, 0x18ab, 0x18a5, 0x189f, 0x1899, - 0x1893, 0x188c, 0x1886, 0x1880, 0x187a, 0x1874, 0x186e, 0x1867, - 0x1861, 0x185b, 0x1855, 0x184f, 0x1848, 0x1842, 0x183c, 0x1836, - 0x1830, 0x182a, 0x1823, 0x181d, 0x1817, 0x1811, 0x180b, 0x1805, - 0x17fe, 0x17f8, 0x17f2, 0x17ec, 0x17e6, 0x17e0, 0x17d9, 0x17d3, - 0x17cd, 0x17c7, 0x17c1, 0x17bb, 0x17b4, 0x17ae, 0x17a8, 0x17a2, - 0x179c, 0x1795, 0x178f, 0x1789, 0x1783, 0x177d, 0x1777, 0x1770, - 0x176a, 0x1764, 0x175e, 0x1758, 0x1752, 0x174b, 0x1745, 0x173f, - 0x1739, 0x1733, 0x172c, 0x1726, 0x1720, 0x171a, 0x1714, 0x170e, - 0x1707, 0x1701, 0x16fb, 0x16f5, 0x16ef, 0x16e8, 0x16e2, 0x16dc, - 0x16d6, 0x16d0, 0x16ca, 0x16c3, 0x16bd, 0x16b7, 0x16b1, 0x16ab, - 0x16a4, 0x169e, 0x1698, 0x1692, 0x168c, 0x1686, 0x167f, 0x1679, - 0x1673, 0x166d, 0x1667, 0x1660, 0x165a, 0x1654, 0x164e, 0x1648, - 0x1642, 0x163b, 0x1635, 0x162f, 0x1629, 0x1623, 0x161c, 0x1616, - 0x1610, 0x160a, 0x1604, 0x15fd, 0x15f7, 0x15f1, 0x15eb, 0x15e5, - 0x15de, 0x15d8, 0x15d2, 0x15cc, 0x15c6, 0x15c0, 0x15b9, 0x15b3, - 0x15ad, 0x15a7, 0x15a1, 0x159a, 0x1594, 0x158e, 0x1588, 0x1582, - 0x157b, 0x1575, 0x156f, 0x1569, 0x1563, 0x155c, 0x1556, 0x1550, - 0x154a, 0x1544, 0x153d, 0x1537, 0x1531, 0x152b, 0x1525, 0x151e, - 0x1518, 0x1512, 0x150c, 0x1506, 0x14ff, 0x14f9, 0x14f3, 0x14ed, - 0x14e7, 0x14e0, 0x14da, 0x14d4, 0x14ce, 0x14c8, 0x14c1, 0x14bb, - 0x14b5, 0x14af, 0x14a9, 0x14a2, 0x149c, 0x1496, 0x1490, 0x148a, - 0x1483, 0x147d, 0x1477, 0x1471, 0x146b, 0x1464, 0x145e, 0x1458, - 0x1452, 0x144c, 0x1445, 0x143f, 0x1439, 0x1433, 0x142d, 0x1426, - 0x1420, 0x141a, 0x1414, 0x140e, 0x1407, 0x1401, 0x13fb, 0x13f5, - 0x13ef, 0x13e8, 0x13e2, 0x13dc, 0x13d6, 0x13d0, 0x13c9, 0x13c3, - 0x13bd, 0x13b7, 0x13b1, 0x13aa, 0x13a4, 0x139e, 0x1398, 0x1391, - 0x138b, 0x1385, 0x137f, 0x1379, 0x1372, 0x136c, 0x1366, 0x1360, - 0x135a, 0x1353, 0x134d, 0x1347, 0x1341, 0x133b, 0x1334, 0x132e, - 0x1328, 0x1322, 0x131b, 0x1315, 0x130f, 0x1309, 0x1303, 0x12fc, - 0x12f6, 0x12f0, 0x12ea, 0x12e4, 0x12dd, 0x12d7, 0x12d1, 0x12cb, - 0x12c4, 0x12be, 0x12b8, 0x12b2, 0x12ac, 0x12a5, 0x129f, 0x1299, - 0x1293, 0x128d, 0x1286, 0x1280, 0x127a, 0x1274, 0x126d, 0x1267, - 0x1261, 0x125b, 0x1255, 0x124e, 0x1248, 0x1242, 0x123c, 0x1235, - 0x122f, 0x1229, 0x1223, 0x121d, 0x1216, 0x1210, 0x120a, 0x1204, - 0x11fd, 0x11f7, 0x11f1, 0x11eb, 0x11e5, 0x11de, 0x11d8, 0x11d2, - 0x11cc, 0x11c5, 0x11bf, 0x11b9, 0x11b3, 0x11ad, 0x11a6, 0x11a0, - 0x119a, 0x1194, 0x118d, 0x1187, 0x1181, 0x117b, 0x1175, 0x116e, - 0x1168, 0x1162, 0x115c, 0x1155, 0x114f, 0x1149, 0x1143, 0x113d, - 0x1136, 0x1130, 0x112a, 0x1124, 0x111d, 0x1117, 0x1111, 0x110b, - 0x1105, 0x10fe, 0x10f8, 0x10f2, 0x10ec, 0x10e5, 0x10df, 0x10d9, - 0x10d3, 0x10cc, 0x10c6, 0x10c0, 0x10ba, 0x10b4, 0x10ad, 0x10a7, - 0x10a1, 0x109b, 0x1094, 0x108e, 0x1088, 0x1082, 0x107b, 0x1075, - 0x106f, 0x1069, 0x1063, 0x105c, 0x1056, 0x1050, 0x104a, 0x1043, - 0x103d, 0x1037, 0x1031, 0x102a, 0x1024, 0x101e, 0x1018, 0x1012, - 0x100b, 0x1005, 0xfff, 0xff9, 0xff2, 0xfec, 0xfe6, 0xfe0, - 0xfd9, 0xfd3, 0xfcd, 0xfc7, 0xfc0, 0xfba, 0xfb4, 0xfae, - 0xfa8, 0xfa1, 0xf9b, 0xf95, 0xf8f, 0xf88, 0xf82, 0xf7c, - 0xf76, 0xf6f, 0xf69, 0xf63, 0xf5d, 0xf56, 0xf50, 0xf4a, - 0xf44, 0xf3e, 0xf37, 0xf31, 0xf2b, 0xf25, 0xf1e, 0xf18, - 0xf12, 0xf0c, 0xf05, 0xeff, 0xef9, 0xef3, 0xeec, 0xee6, - 0xee0, 0xeda, 0xed3, 0xecd, 0xec7, 0xec1, 0xeba, 0xeb4, - 0xeae, 0xea8, 0xea1, 0xe9b, 0xe95, 0xe8f, 0xe89, 0xe82, - 0xe7c, 0xe76, 0xe70, 0xe69, 0xe63, 0xe5d, 0xe57, 0xe50, - 0xe4a, 0xe44, 0xe3e, 0xe37, 0xe31, 0xe2b, 0xe25, 0xe1e, - 0xe18, 0xe12, 0xe0c, 0xe05, 0xdff, 0xdf9, 0xdf3, 0xdec, - 0xde6, 0xde0, 0xdda, 0xdd3, 0xdcd, 0xdc7, 0xdc1, 0xdba, - 0xdb4, 0xdae, 0xda8, 0xda1, 0xd9b, 0xd95, 0xd8f, 0xd88, - 0xd82, 0xd7c, 0xd76, 0xd6f, 0xd69, 0xd63, 0xd5d, 0xd56, - 0xd50, 0xd4a, 0xd44, 0xd3d, 0xd37, 0xd31, 0xd2b, 0xd24, - 0xd1e, 0xd18, 0xd12, 0xd0b, 0xd05, 0xcff, 0xcf9, 0xcf2, - 0xcec, 0xce6, 0xce0, 0xcd9, 0xcd3, 0xccd, 0xcc7, 0xcc0, - 0xcba, 0xcb4, 0xcae, 0xca7, 0xca1, 0xc9b, 0xc95, 0xc8e, - 0xc88, 0xc82, 0xc7c, 0xc75, 0xc6f, 0xc69, 0xc63, 0xc5c, - 0xc56, 0xc50, 0xc4a, 0xc43, 0xc3d, 0xc37, 0xc31, 0xc2a, - 0xc24, 0xc1e, 0xc18, 0xc11, 0xc0b, 0xc05, 0xbff, 0xbf8, - 0xbf2, 0xbec, 0xbe6, 0xbdf, 0xbd9, 0xbd3, 0xbcd, 0xbc6, - 0xbc0, 0xbba, 0xbb4, 0xbad, 0xba7, 0xba1, 0xb9b, 0xb94, - 0xb8e, 0xb88, 0xb81, 0xb7b, 0xb75, 0xb6f, 0xb68, 0xb62, - 0xb5c, 0xb56, 0xb4f, 0xb49, 0xb43, 0xb3d, 0xb36, 0xb30, - 0xb2a, 0xb24, 0xb1d, 0xb17, 0xb11, 0xb0b, 0xb04, 0xafe, - 0xaf8, 0xaf2, 0xaeb, 0xae5, 0xadf, 0xad8, 0xad2, 0xacc, - 0xac6, 0xabf, 0xab9, 0xab3, 0xaad, 0xaa6, 0xaa0, 0xa9a, - 0xa94, 0xa8d, 0xa87, 0xa81, 0xa7b, 0xa74, 0xa6e, 0xa68, - 0xa62, 0xa5b, 0xa55, 0xa4f, 0xa48, 0xa42, 0xa3c, 0xa36, - 0xa2f, 0xa29, 0xa23, 0xa1d, 0xa16, 0xa10, 0xa0a, 0xa04, - 0x9fd, 0x9f7, 0x9f1, 0x9eb, 0x9e4, 0x9de, 0x9d8, 0x9d1, - 0x9cb, 0x9c5, 0x9bf, 0x9b8, 0x9b2, 0x9ac, 0x9a6, 0x99f, - 0x999, 0x993, 0x98d, 0x986, 0x980, 0x97a, 0x973, 0x96d, - 0x967, 0x961, 0x95a, 0x954, 0x94e, 0x948, 0x941, 0x93b, - 0x935, 0x92f, 0x928, 0x922, 0x91c, 0x915, 0x90f, 0x909, - 0x903, 0x8fc, 0x8f6, 0x8f0, 0x8ea, 0x8e3, 0x8dd, 0x8d7, - 0x8d1, 0x8ca, 0x8c4, 0x8be, 0x8b7, 0x8b1, 0x8ab, 0x8a5, - 0x89e, 0x898, 0x892, 0x88c, 0x885, 0x87f, 0x879, 0x872, - 0x86c, 0x866, 0x860, 0x859, 0x853, 0x84d, 0x847, 0x840, - 0x83a, 0x834, 0x82e, 0x827, 0x821, 0x81b, 0x814, 0x80e, - 0x808, 0x802, 0x7fb, 0x7f5, 0x7ef, 0x7e9, 0x7e2, 0x7dc, - 0x7d6, 0x7cf, 0x7c9, 0x7c3, 0x7bd, 0x7b6, 0x7b0, 0x7aa, - 0x7a4, 0x79d, 0x797, 0x791, 0x78a, 0x784, 0x77e, 0x778, - 0x771, 0x76b, 0x765, 0x75f, 0x758, 0x752, 0x74c, 0x745, - 0x73f, 0x739, 0x733, 0x72c, 0x726, 0x720, 0x71a, 0x713, - 0x70d, 0x707, 0x700, 0x6fa, 0x6f4, 0x6ee, 0x6e7, 0x6e1, - 0x6db, 0x6d5, 0x6ce, 0x6c8, 0x6c2, 0x6bb, 0x6b5, 0x6af, - 0x6a9, 0x6a2, 0x69c, 0x696, 0x690, 0x689, 0x683, 0x67d, - 0x676, 0x670, 0x66a, 0x664, 0x65d, 0x657, 0x651, 0x64a, - 0x644, 0x63e, 0x638, 0x631, 0x62b, 0x625, 0x61f, 0x618, - 0x612, 0x60c, 0x605, 0x5ff, 0x5f9, 0x5f3, 0x5ec, 0x5e6, - 0x5e0, 0x5da, 0x5d3, 0x5cd, 0x5c7, 0x5c0, 0x5ba, 0x5b4, - 0x5ae, 0x5a7, 0x5a1, 0x59b, 0x594, 0x58e, 0x588, 0x582, - 0x57b, 0x575, 0x56f, 0x569, 0x562, 0x55c, 0x556, 0x54f, - 0x549, 0x543, 0x53d, 0x536, 0x530, 0x52a, 0x523, 0x51d, - 0x517, 0x511, 0x50a, 0x504, 0x4fe, 0x4f8, 0x4f1, 0x4eb, - 0x4e5, 0x4de, 0x4d8, 0x4d2, 0x4cc, 0x4c5, 0x4bf, 0x4b9, - 0x4b2, 0x4ac, 0x4a6, 0x4a0, 0x499, 0x493, 0x48d, 0x487, - 0x480, 0x47a, 0x474, 0x46d, 0x467, 0x461, 0x45b, 0x454, - 0x44e, 0x448, 0x441, 0x43b, 0x435, 0x42f, 0x428, 0x422, - 0x41c, 0x415, 0x40f, 0x409, 0x403, 0x3fc, 0x3f6, 0x3f0, - 0x3ea, 0x3e3, 0x3dd, 0x3d7, 0x3d0, 0x3ca, 0x3c4, 0x3be, - 0x3b7, 0x3b1, 0x3ab, 0x3a4, 0x39e, 0x398, 0x392, 0x38b, - 0x385, 0x37f, 0x378, 0x372, 0x36c, 0x366, 0x35f, 0x359, - 0x353, 0x34c, 0x346, 0x340, 0x33a, 0x333, 0x32d, 0x327, - 0x321, 0x31a, 0x314, 0x30e, 0x307, 0x301, 0x2fb, 0x2f5, - 0x2ee, 0x2e8, 0x2e2, 0x2db, 0x2d5, 0x2cf, 0x2c9, 0x2c2, - 0x2bc, 0x2b6, 0x2af, 0x2a9, 0x2a3, 0x29d, 0x296, 0x290, - 0x28a, 0x283, 0x27d, 0x277, 0x271, 0x26a, 0x264, 0x25e, - 0x258, 0x251, 0x24b, 0x245, 0x23e, 0x238, 0x232, 0x22c, - 0x225, 0x21f, 0x219, 0x212, 0x20c, 0x206, 0x200, 0x1f9, - 0x1f3, 0x1ed, 0x1e6, 0x1e0, 0x1da, 0x1d4, 0x1cd, 0x1c7, - 0x1c1, 0x1ba, 0x1b4, 0x1ae, 0x1a8, 0x1a1, 0x19b, 0x195, - 0x18e, 0x188, 0x182, 0x17c, 0x175, 0x16f, 0x169, 0x162, - 0x15c, 0x156, 0x150, 0x149, 0x143, 0x13d, 0x137, 0x130, - 0x12a, 0x124, 0x11d, 0x117, 0x111, 0x10b, 0x104, 0xfe, - 0xf8, 0xf1, 0xeb, 0xe5, 0xdf, 0xd8, 0xd2, 0xcc, - 0xc5, 0xbf, 0xb9, 0xb3, 0xac, 0xa6, 0xa0, 0x99, - 0x93, 0x8d, 0x87, 0x80, 0x7a, 0x74, 0x6d, 0x67, - 0x61, 0x5b, 0x54, 0x4e, 0x48, 0x41, 0x3b, 0x35, - 0x2f, 0x28, 0x22, 0x1c, 0x15, 0xf, 0x9, 0x3, -}; - -/** - * @brief Initialization function for the Q15 DCT4/IDCT4. - * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure. - * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Normalizing factors in 1.15 format are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingQ15Table.gif - */ - -arm_status arm_dct4_init_q15( - arm_dct4_instance_q15 * S, - arm_rfft_instance_q15 * S_RFFT, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q15_t normalize) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - q15_t *twiddlePtr[4] = { (q15_t *) WeightsQ15_128, (q15_t *) WeightsQ15_512, - (q15_t *) WeightsQ15_2048, (q15_t *) WeightsQ15_8192 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - q15_t *pCosFactor[4] = - { (q15_t *) cos_factorsQ15_128, (q15_t *) cos_factorsQ15_512, - (q15_t *) cos_factorsQ15_2048, (q15_t *) cos_factorsQ15_8192 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 8192u: - S->pTwiddle = twiddlePtr[3]; - S->pCosFactor = pCosFactor[3]; - break; - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT */ - arm_rfft_init_q15(S->pRfft, S->pCfft, S->N, 0u, 1u); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c deleted file mode 100644 index 211cdadf38..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_init_q31.c +++ /dev/null @@ -1,8356 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_init_q31.c -* -* Description: Initialization function of DCT-4 & IDCT4 Q31 -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/* -* @brief Weights Table -*/ - -/** -* \par -* Weights tables are generated using the formula :
weights[n] = e^(-j*n*pi/(2*N))
-* \par -* C command to generate the table -*
    
-* for(i = 0; i< N; i++)    
-* {    
-*   weights[2*i]= cos(i*c);    
-*   weights[(2*i)+1]= -sin(i * c);    
-* } 
-* \par -* where N is the Number of weights to be calculated and c is pi/(2*N) -* \par -* Convert the output to q31 format by multiplying with 2^31 and saturated if required. -* \par -* In the tables below the real and imaginary values are placed alternatively, hence the -* array length is 2*N. -*/ - -static const q31_t WeightsQ31_128[256] = { - 0x7fffffff, 0x0, 0x7ffd885a, 0xfe6de2e0, 0x7ff62182, 0xfcdbd541, 0x7fe9cbc0, - 0xfb49e6a3, - 0x7fd8878e, 0xf9b82684, 0x7fc25596, 0xf826a462, 0x7fa736b4, 0xf6956fb7, - 0x7f872bf3, 0xf50497fb, - 0x7f62368f, 0xf3742ca2, 0x7f3857f6, 0xf1e43d1c, 0x7f0991c4, 0xf054d8d5, - 0x7ed5e5c6, 0xeec60f31, - 0x7e9d55fc, 0xed37ef91, 0x7e5fe493, 0xebaa894f, 0x7e1d93ea, 0xea1debbb, - 0x7dd6668f, 0xe8922622, - 0x7d8a5f40, 0xe70747c4, 0x7d3980ec, 0xe57d5fda, 0x7ce3ceb2, 0xe3f47d96, - 0x7c894bde, 0xe26cb01b, - 0x7c29fbee, 0xe0e60685, 0x7bc5e290, 0xdf608fe4, 0x7b5d039e, 0xdddc5b3b, - 0x7aef6323, 0xdc597781, - 0x7a7d055b, 0xdad7f3a2, 0x7a05eead, 0xd957de7a, 0x798a23b1, 0xd7d946d8, - 0x7909a92d, 0xd65c3b7b, - 0x78848414, 0xd4e0cb15, 0x77fab989, 0xd3670446, 0x776c4edb, 0xd1eef59e, - 0x76d94989, 0xd078ad9e, - 0x7641af3d, 0xcf043ab3, 0x75a585cf, 0xcd91ab39, 0x7504d345, 0xcc210d79, - 0x745f9dd1, 0xcab26fa9, - 0x73b5ebd1, 0xc945dfec, 0x7307c3d0, 0xc7db6c50, 0x72552c85, 0xc67322ce, - 0x719e2cd2, 0xc50d1149, - 0x70e2cbc6, 0xc3a94590, 0x7023109a, 0xc247cd5a, 0x6f5f02b2, 0xc0e8b648, - 0x6e96a99d, 0xbf8c0de3, - 0x6dca0d14, 0xbe31e19b, 0x6cf934fc, 0xbcda3ecb, 0x6c242960, 0xbb8532b0, - 0x6b4af279, 0xba32ca71, - 0x6a6d98a4, 0xb8e31319, 0x698c246c, 0xb796199b, 0x68a69e81, 0xb64beacd, - 0x67bd0fbd, 0xb5049368, - 0x66cf8120, 0xb3c0200c, 0x65ddfbd3, 0xb27e9d3c, 0x64e88926, 0xb140175b, - 0x63ef3290, 0xb0049ab3, - 0x62f201ac, 0xaecc336c, 0x61f1003f, 0xad96ed92, 0x60ec3830, 0xac64d510, - 0x5fe3b38d, 0xab35f5b5, - 0x5ed77c8a, 0xaa0a5b2e, 0x5dc79d7c, 0xa8e21106, 0x5cb420e0, 0xa7bd22ac, - 0x5b9d1154, 0xa69b9b68, - 0x5a82799a, 0xa57d8666, 0x59646498, 0xa462eeac, 0x5842dd54, 0xa34bdf20, - 0x571deefa, 0xa2386284, - 0x55f5a4d2, 0xa1288376, 0x54ca0a4b, 0xa01c4c73, 0x539b2af0, 0x9f13c7d0, - 0x5269126e, 0x9e0effc1, - 0x5133cc94, 0x9d0dfe54, 0x4ffb654d, 0x9c10cd70, 0x4ebfe8a5, 0x9b1776da, - 0x4d8162c4, 0x9a22042d, - 0x4c3fdff4, 0x99307ee0, 0x4afb6c98, 0x9842f043, 0x49b41533, 0x9759617f, - 0x4869e665, 0x9673db94, - 0x471cece7, 0x9592675c, 0x45cd358f, 0x94b50d87, 0x447acd50, 0x93dbd6a0, - 0x4325c135, 0x9306cb04, - 0x41ce1e65, 0x9235f2ec, 0x4073f21d, 0x91695663, 0x3f1749b8, 0x90a0fd4e, - 0x3db832a6, 0x8fdcef66, - 0x3c56ba70, 0x8f1d343a, 0x3af2eeb7, 0x8e61d32e, 0x398cdd32, 0x8daad37b, - 0x382493b0, 0x8cf83c30, - 0x36ba2014, 0x8c4a142f, 0x354d9057, 0x8ba0622f, 0x33def287, 0x8afb2cbb, - 0x326e54c7, 0x8a5a7a31, - 0x30fbc54d, 0x89be50c3, 0x2f875262, 0x8926b677, 0x2e110a62, 0x8893b125, - 0x2c98fbba, 0x88054677, - 0x2b1f34eb, 0x877b7bec, 0x29a3c485, 0x86f656d3, 0x2826b928, 0x8675dc4f, - 0x26a82186, 0x85fa1153, - 0x25280c5e, 0x8582faa5, 0x23a6887f, 0x85109cdd, 0x2223a4c5, 0x84a2fc62, - 0x209f701c, 0x843a1d70, - 0x1f19f97b, 0x83d60412, 0x1d934fe5, 0x8376b422, 0x1c0b826a, 0x831c314e, - 0x1a82a026, 0x82c67f14, - 0x18f8b83c, 0x8275a0c0, 0x176dd9de, 0x82299971, 0x15e21445, 0x81e26c16, - 0x145576b1, 0x81a01b6d, - 0x12c8106f, 0x8162aa04, 0x1139f0cf, 0x812a1a3a, 0xfab272b, 0x80f66e3c, - 0xe1bc2e4, 0x80c7a80a, - 0xc8bd35e, 0x809dc971, 0xafb6805, 0x8078d40d, 0x96a9049, 0x8058c94c, - 0x7d95b9e, 0x803daa6a, - 0x647d97c, 0x80277872, 0x4b6195d, 0x80163440, 0x3242abf, 0x8009de7e, - 0x1921d20, 0x800277a6, -}; - -static const q31_t WeightsQ31_512[1024] = { - 0x7fffffff, 0x0, 0x7fffd886, 0xff9b781d, 0x7fff6216, 0xff36f078, 0x7ffe9cb2, - 0xfed2694f, - 0x7ffd885a, 0xfe6de2e0, 0x7ffc250f, 0xfe095d69, 0x7ffa72d1, 0xfda4d929, - 0x7ff871a2, 0xfd40565c, - 0x7ff62182, 0xfcdbd541, 0x7ff38274, 0xfc775616, 0x7ff09478, 0xfc12d91a, - 0x7fed5791, 0xfbae5e89, - 0x7fe9cbc0, 0xfb49e6a3, 0x7fe5f108, 0xfae571a4, 0x7fe1c76b, 0xfa80ffcb, - 0x7fdd4eec, 0xfa1c9157, - 0x7fd8878e, 0xf9b82684, 0x7fd37153, 0xf953bf91, 0x7fce0c3e, 0xf8ef5cbb, - 0x7fc85854, 0xf88afe42, - 0x7fc25596, 0xf826a462, 0x7fbc040a, 0xf7c24f59, 0x7fb563b3, 0xf75dff66, - 0x7fae7495, 0xf6f9b4c6, - 0x7fa736b4, 0xf6956fb7, 0x7f9faa15, 0xf6313077, 0x7f97cebd, 0xf5ccf743, - 0x7f8fa4b0, 0xf568c45b, - 0x7f872bf3, 0xf50497fb, 0x7f7e648c, 0xf4a07261, 0x7f754e80, 0xf43c53cb, - 0x7f6be9d4, 0xf3d83c77, - 0x7f62368f, 0xf3742ca2, 0x7f5834b7, 0xf310248a, 0x7f4de451, 0xf2ac246e, - 0x7f434563, 0xf2482c8a, - 0x7f3857f6, 0xf1e43d1c, 0x7f2d1c0e, 0xf1805662, 0x7f2191b4, 0xf11c789a, - 0x7f15b8ee, 0xf0b8a401, - 0x7f0991c4, 0xf054d8d5, 0x7efd1c3c, 0xeff11753, 0x7ef05860, 0xef8d5fb8, - 0x7ee34636, 0xef29b243, - 0x7ed5e5c6, 0xeec60f31, 0x7ec8371a, 0xee6276bf, 0x7eba3a39, 0xedfee92b, - 0x7eabef2c, 0xed9b66b2, - 0x7e9d55fc, 0xed37ef91, 0x7e8e6eb2, 0xecd48407, 0x7e7f3957, 0xec71244f, - 0x7e6fb5f4, 0xec0dd0a8, - 0x7e5fe493, 0xebaa894f, 0x7e4fc53e, 0xeb474e81, 0x7e3f57ff, 0xeae4207a, - 0x7e2e9cdf, 0xea80ff7a, - 0x7e1d93ea, 0xea1debbb, 0x7e0c3d29, 0xe9bae57d, 0x7dfa98a8, 0xe957ecfb, - 0x7de8a670, 0xe8f50273, - 0x7dd6668f, 0xe8922622, 0x7dc3d90d, 0xe82f5844, 0x7db0fdf8, 0xe7cc9917, - 0x7d9dd55a, 0xe769e8d8, - 0x7d8a5f40, 0xe70747c4, 0x7d769bb5, 0xe6a4b616, 0x7d628ac6, 0xe642340d, - 0x7d4e2c7f, 0xe5dfc1e5, - 0x7d3980ec, 0xe57d5fda, 0x7d24881b, 0xe51b0e2a, 0x7d0f4218, 0xe4b8cd11, - 0x7cf9aef0, 0xe4569ccb, - 0x7ce3ceb2, 0xe3f47d96, 0x7ccda169, 0xe3926fad, 0x7cb72724, 0xe330734d, - 0x7ca05ff1, 0xe2ce88b3, - 0x7c894bde, 0xe26cb01b, 0x7c71eaf9, 0xe20ae9c1, 0x7c5a3d50, 0xe1a935e2, - 0x7c4242f2, 0xe14794ba, - 0x7c29fbee, 0xe0e60685, 0x7c116853, 0xe0848b7f, 0x7bf88830, 0xe02323e5, - 0x7bdf5b94, 0xdfc1cff3, - 0x7bc5e290, 0xdf608fe4, 0x7bac1d31, 0xdeff63f4, 0x7b920b89, 0xde9e4c60, - 0x7b77ada8, 0xde3d4964, - 0x7b5d039e, 0xdddc5b3b, 0x7b420d7a, 0xdd7b8220, 0x7b26cb4f, 0xdd1abe51, - 0x7b0b3d2c, 0xdcba1008, - 0x7aef6323, 0xdc597781, 0x7ad33d45, 0xdbf8f4f8, 0x7ab6cba4, 0xdb9888a8, - 0x7a9a0e50, 0xdb3832cd, - 0x7a7d055b, 0xdad7f3a2, 0x7a5fb0d8, 0xda77cb63, 0x7a4210d8, 0xda17ba4a, - 0x7a24256f, 0xd9b7c094, - 0x7a05eead, 0xd957de7a, 0x79e76ca7, 0xd8f81439, 0x79c89f6e, 0xd898620c, - 0x79a98715, 0xd838c82d, - 0x798a23b1, 0xd7d946d8, 0x796a7554, 0xd779de47, 0x794a7c12, 0xd71a8eb5, - 0x792a37fe, 0xd6bb585e, - 0x7909a92d, 0xd65c3b7b, 0x78e8cfb2, 0xd5fd3848, 0x78c7aba2, 0xd59e4eff, - 0x78a63d11, 0xd53f7fda, - 0x78848414, 0xd4e0cb15, 0x786280bf, 0xd48230e9, 0x78403329, 0xd423b191, - 0x781d9b65, 0xd3c54d47, - 0x77fab989, 0xd3670446, 0x77d78daa, 0xd308d6c7, 0x77b417df, 0xd2aac504, - 0x7790583e, 0xd24ccf39, - 0x776c4edb, 0xd1eef59e, 0x7747fbce, 0xd191386e, 0x77235f2d, 0xd13397e2, - 0x76fe790e, 0xd0d61434, - 0x76d94989, 0xd078ad9e, 0x76b3d0b4, 0xd01b6459, 0x768e0ea6, 0xcfbe389f, - 0x76680376, 0xcf612aaa, - 0x7641af3d, 0xcf043ab3, 0x761b1211, 0xcea768f2, 0x75f42c0b, 0xce4ab5a2, - 0x75ccfd42, 0xcdee20fc, - 0x75a585cf, 0xcd91ab39, 0x757dc5ca, 0xcd355491, 0x7555bd4c, 0xccd91d3d, - 0x752d6c6c, 0xcc7d0578, - 0x7504d345, 0xcc210d79, 0x74dbf1ef, 0xcbc53579, 0x74b2c884, 0xcb697db0, - 0x7489571c, 0xcb0de658, - 0x745f9dd1, 0xcab26fa9, 0x74359cbd, 0xca5719db, 0x740b53fb, 0xc9fbe527, - 0x73e0c3a3, 0xc9a0d1c5, - 0x73b5ebd1, 0xc945dfec, 0x738acc9e, 0xc8eb0fd6, 0x735f6626, 0xc89061ba, - 0x7333b883, 0xc835d5d0, - 0x7307c3d0, 0xc7db6c50, 0x72db8828, 0xc7812572, 0x72af05a7, 0xc727016d, - 0x72823c67, 0xc6cd0079, - 0x72552c85, 0xc67322ce, 0x7227d61c, 0xc61968a2, 0x71fa3949, 0xc5bfd22e, - 0x71cc5626, 0xc5665fa9, - 0x719e2cd2, 0xc50d1149, 0x716fbd68, 0xc4b3e746, 0x71410805, 0xc45ae1d7, - 0x71120cc5, 0xc4020133, - 0x70e2cbc6, 0xc3a94590, 0x70b34525, 0xc350af26, 0x708378ff, 0xc2f83e2a, - 0x70536771, 0xc29ff2d4, - 0x7023109a, 0xc247cd5a, 0x6ff27497, 0xc1efcdf3, 0x6fc19385, 0xc197f4d4, - 0x6f906d84, 0xc1404233, - 0x6f5f02b2, 0xc0e8b648, 0x6f2d532c, 0xc0915148, 0x6efb5f12, 0xc03a1368, - 0x6ec92683, 0xbfe2fcdf, - 0x6e96a99d, 0xbf8c0de3, 0x6e63e87f, 0xbf3546a8, 0x6e30e34a, 0xbedea765, - 0x6dfd9a1c, 0xbe88304f, - 0x6dca0d14, 0xbe31e19b, 0x6d963c54, 0xbddbbb7f, 0x6d6227fa, 0xbd85be30, - 0x6d2dd027, 0xbd2fe9e2, - 0x6cf934fc, 0xbcda3ecb, 0x6cc45698, 0xbc84bd1f, 0x6c8f351c, 0xbc2f6513, - 0x6c59d0a9, 0xbbda36dd, - 0x6c242960, 0xbb8532b0, 0x6bee3f62, 0xbb3058c0, 0x6bb812d1, 0xbadba943, - 0x6b81a3cd, 0xba87246d, - 0x6b4af279, 0xba32ca71, 0x6b13fef5, 0xb9de9b83, 0x6adcc964, 0xb98a97d8, - 0x6aa551e9, 0xb936bfa4, - 0x6a6d98a4, 0xb8e31319, 0x6a359db9, 0xb88f926d, 0x69fd614a, 0xb83c3dd1, - 0x69c4e37a, 0xb7e9157a, - 0x698c246c, 0xb796199b, 0x69532442, 0xb7434a67, 0x6919e320, 0xb6f0a812, - 0x68e06129, 0xb69e32cd, - 0x68a69e81, 0xb64beacd, 0x686c9b4b, 0xb5f9d043, 0x683257ab, 0xb5a7e362, - 0x67f7d3c5, 0xb556245e, - 0x67bd0fbd, 0xb5049368, 0x67820bb7, 0xb4b330b3, 0x6746c7d8, 0xb461fc70, - 0x670b4444, 0xb410f6d3, - 0x66cf8120, 0xb3c0200c, 0x66937e91, 0xb36f784f, 0x66573cbb, 0xb31effcc, - 0x661abbc5, 0xb2ceb6b5, - 0x65ddfbd3, 0xb27e9d3c, 0x65a0fd0b, 0xb22eb392, 0x6563bf92, 0xb1def9e9, - 0x6526438f, 0xb18f7071, - 0x64e88926, 0xb140175b, 0x64aa907f, 0xb0f0eeda, 0x646c59bf, 0xb0a1f71d, - 0x642de50d, 0xb0533055, - 0x63ef3290, 0xb0049ab3, 0x63b0426d, 0xafb63667, 0x637114cc, 0xaf6803a2, - 0x6331a9d4, 0xaf1a0293, - 0x62f201ac, 0xaecc336c, 0x62b21c7b, 0xae7e965b, 0x6271fa69, 0xae312b92, - 0x62319b9d, 0xade3f33e, - 0x61f1003f, 0xad96ed92, 0x61b02876, 0xad4a1aba, 0x616f146c, 0xacfd7ae8, - 0x612dc447, 0xacb10e4b, - 0x60ec3830, 0xac64d510, 0x60aa7050, 0xac18cf69, 0x60686ccf, 0xabccfd83, - 0x60262dd6, 0xab815f8d, - 0x5fe3b38d, 0xab35f5b5, 0x5fa0fe1f, 0xaaeac02c, 0x5f5e0db3, 0xaa9fbf1e, - 0x5f1ae274, 0xaa54f2ba, - 0x5ed77c8a, 0xaa0a5b2e, 0x5e93dc1f, 0xa9bff8a8, 0x5e50015d, 0xa975cb57, - 0x5e0bec6e, 0xa92bd367, - 0x5dc79d7c, 0xa8e21106, 0x5d8314b1, 0xa8988463, 0x5d3e5237, 0xa84f2daa, - 0x5cf95638, 0xa8060d08, - 0x5cb420e0, 0xa7bd22ac, 0x5c6eb258, 0xa7746ec0, 0x5c290acc, 0xa72bf174, - 0x5be32a67, 0xa6e3aaf2, - 0x5b9d1154, 0xa69b9b68, 0x5b56bfbd, 0xa653c303, 0x5b1035cf, 0xa60c21ee, - 0x5ac973b5, 0xa5c4b855, - 0x5a82799a, 0xa57d8666, 0x5a3b47ab, 0xa5368c4b, 0x59f3de12, 0xa4efca31, - 0x59ac3cfd, 0xa4a94043, - 0x59646498, 0xa462eeac, 0x591c550e, 0xa41cd599, 0x58d40e8c, 0xa3d6f534, - 0x588b9140, 0xa3914da8, - 0x5842dd54, 0xa34bdf20, 0x57f9f2f8, 0xa306a9c8, 0x57b0d256, 0xa2c1adc9, - 0x57677b9d, 0xa27ceb4f, - 0x571deefa, 0xa2386284, 0x56d42c99, 0xa1f41392, 0x568a34a9, 0xa1affea3, - 0x56400758, 0xa16c23e1, - 0x55f5a4d2, 0xa1288376, 0x55ab0d46, 0xa0e51d8c, 0x556040e2, 0xa0a1f24d, - 0x55153fd4, 0xa05f01e1, - 0x54ca0a4b, 0xa01c4c73, 0x547ea073, 0x9fd9d22a, 0x5433027d, 0x9f979331, - 0x53e73097, 0x9f558fb0, - 0x539b2af0, 0x9f13c7d0, 0x534ef1b5, 0x9ed23bb9, 0x53028518, 0x9e90eb94, - 0x52b5e546, 0x9e4fd78a, - 0x5269126e, 0x9e0effc1, 0x521c0cc2, 0x9dce6463, 0x51ced46e, 0x9d8e0597, - 0x518169a5, 0x9d4de385, - 0x5133cc94, 0x9d0dfe54, 0x50e5fd6d, 0x9cce562c, 0x5097fc5e, 0x9c8eeb34, - 0x5049c999, 0x9c4fbd93, - 0x4ffb654d, 0x9c10cd70, 0x4faccfab, 0x9bd21af3, 0x4f5e08e3, 0x9b93a641, - 0x4f0f1126, 0x9b556f81, - 0x4ebfe8a5, 0x9b1776da, 0x4e708f8f, 0x9ad9bc71, 0x4e210617, 0x9a9c406e, - 0x4dd14c6e, 0x9a5f02f5, - 0x4d8162c4, 0x9a22042d, 0x4d31494b, 0x99e5443b, 0x4ce10034, 0x99a8c345, - 0x4c9087b1, 0x996c816f, - 0x4c3fdff4, 0x99307ee0, 0x4bef092d, 0x98f4bbbc, 0x4b9e0390, 0x98b93828, - 0x4b4ccf4d, 0x987df449, - 0x4afb6c98, 0x9842f043, 0x4aa9dba2, 0x98082c3b, 0x4a581c9e, 0x97cda855, - 0x4a062fbd, 0x979364b5, - 0x49b41533, 0x9759617f, 0x4961cd33, 0x971f9ed7, 0x490f57ee, 0x96e61ce0, - 0x48bcb599, 0x96acdbbe, - 0x4869e665, 0x9673db94, 0x4816ea86, 0x963b1c86, 0x47c3c22f, 0x96029eb6, - 0x47706d93, 0x95ca6247, - 0x471cece7, 0x9592675c, 0x46c9405c, 0x955aae17, 0x46756828, 0x9523369c, - 0x4621647d, 0x94ec010b, - 0x45cd358f, 0x94b50d87, 0x4578db93, 0x947e5c33, 0x452456bd, 0x9447ed2f, - 0x44cfa740, 0x9411c09e, - 0x447acd50, 0x93dbd6a0, 0x4425c923, 0x93a62f57, 0x43d09aed, 0x9370cae4, - 0x437b42e1, 0x933ba968, - 0x4325c135, 0x9306cb04, 0x42d0161e, 0x92d22fd9, 0x427a41d0, 0x929dd806, - 0x42244481, 0x9269c3ac, - 0x41ce1e65, 0x9235f2ec, 0x4177cfb1, 0x920265e4, 0x4121589b, 0x91cf1cb6, - 0x40cab958, 0x919c1781, - 0x4073f21d, 0x91695663, 0x401d0321, 0x9136d97d, 0x3fc5ec98, 0x9104a0ee, - 0x3f6eaeb8, 0x90d2acd4, - 0x3f1749b8, 0x90a0fd4e, 0x3ebfbdcd, 0x906f927c, 0x3e680b2c, 0x903e6c7b, - 0x3e10320d, 0x900d8b69, - 0x3db832a6, 0x8fdcef66, 0x3d600d2c, 0x8fac988f, 0x3d07c1d6, 0x8f7c8701, - 0x3caf50da, 0x8f4cbadb, - 0x3c56ba70, 0x8f1d343a, 0x3bfdfecd, 0x8eedf33b, 0x3ba51e29, 0x8ebef7fb, - 0x3b4c18ba, 0x8e904298, - 0x3af2eeb7, 0x8e61d32e, 0x3a99a057, 0x8e33a9da, 0x3a402dd2, 0x8e05c6b7, - 0x39e6975e, 0x8dd829e4, - 0x398cdd32, 0x8daad37b, 0x3932ff87, 0x8d7dc399, 0x38d8fe93, 0x8d50fa59, - 0x387eda8e, 0x8d2477d8, - 0x382493b0, 0x8cf83c30, 0x37ca2a30, 0x8ccc477d, 0x376f9e46, 0x8ca099da, - 0x3714f02a, 0x8c753362, - 0x36ba2014, 0x8c4a142f, 0x365f2e3b, 0x8c1f3c5d, 0x36041ad9, 0x8bf4ac05, - 0x35a8e625, 0x8bca6343, - 0x354d9057, 0x8ba0622f, 0x34f219a8, 0x8b76a8e4, 0x34968250, 0x8b4d377c, - 0x343aca87, 0x8b240e11, - 0x33def287, 0x8afb2cbb, 0x3382fa88, 0x8ad29394, 0x3326e2c3, 0x8aaa42b4, - 0x32caab6f, 0x8a823a36, - 0x326e54c7, 0x8a5a7a31, 0x3211df04, 0x8a3302be, 0x31b54a5e, 0x8a0bd3f5, - 0x3158970e, 0x89e4edef, - 0x30fbc54d, 0x89be50c3, 0x309ed556, 0x8997fc8a, 0x3041c761, 0x8971f15a, - 0x2fe49ba7, 0x894c2f4c, - 0x2f875262, 0x8926b677, 0x2f29ebcc, 0x890186f2, 0x2ecc681e, 0x88dca0d3, - 0x2e6ec792, 0x88b80432, - 0x2e110a62, 0x8893b125, 0x2db330c7, 0x886fa7c2, 0x2d553afc, 0x884be821, - 0x2cf72939, 0x88287256, - 0x2c98fbba, 0x88054677, 0x2c3ab2b9, 0x87e2649b, 0x2bdc4e6f, 0x87bfccd7, - 0x2b7dcf17, 0x879d7f41, - 0x2b1f34eb, 0x877b7bec, 0x2ac08026, 0x8759c2ef, 0x2a61b101, 0x8738545e, - 0x2a02c7b8, 0x8717304e, - 0x29a3c485, 0x86f656d3, 0x2944a7a2, 0x86d5c802, 0x28e5714b, 0x86b583ee, - 0x288621b9, 0x86958aac, - 0x2826b928, 0x8675dc4f, 0x27c737d3, 0x865678eb, 0x27679df4, 0x86376092, - 0x2707ebc7, 0x86189359, - 0x26a82186, 0x85fa1153, 0x26483f6c, 0x85dbda91, 0x25e845b6, 0x85bdef28, - 0x2588349d, 0x85a04f28, - 0x25280c5e, 0x8582faa5, 0x24c7cd33, 0x8565f1b0, 0x24677758, 0x8549345c, - 0x24070b08, 0x852cc2bb, - 0x23a6887f, 0x85109cdd, 0x2345eff8, 0x84f4c2d4, 0x22e541af, 0x84d934b1, - 0x22847de0, 0x84bdf286, - 0x2223a4c5, 0x84a2fc62, 0x21c2b69c, 0x84885258, 0x2161b3a0, 0x846df477, - 0x21009c0c, 0x8453e2cf, - 0x209f701c, 0x843a1d70, 0x203e300d, 0x8420a46c, 0x1fdcdc1b, 0x840777d0, - 0x1f7b7481, 0x83ee97ad, - 0x1f19f97b, 0x83d60412, 0x1eb86b46, 0x83bdbd0e, 0x1e56ca1e, 0x83a5c2b0, - 0x1df5163f, 0x838e1507, - 0x1d934fe5, 0x8376b422, 0x1d31774d, 0x835fa00f, 0x1ccf8cb3, 0x8348d8dc, - 0x1c6d9053, 0x83325e97, - 0x1c0b826a, 0x831c314e, 0x1ba96335, 0x83065110, 0x1b4732ef, 0x82f0bde8, - 0x1ae4f1d6, 0x82db77e5, - 0x1a82a026, 0x82c67f14, 0x1a203e1b, 0x82b1d381, 0x19bdcbf3, 0x829d753a, - 0x195b49ea, 0x8289644b, - 0x18f8b83c, 0x8275a0c0, 0x18961728, 0x82622aa6, 0x183366e9, 0x824f0208, - 0x17d0a7bc, 0x823c26f3, - 0x176dd9de, 0x82299971, 0x170afd8d, 0x82175990, 0x16a81305, 0x82056758, - 0x16451a83, 0x81f3c2d7, - 0x15e21445, 0x81e26c16, 0x157f0086, 0x81d16321, 0x151bdf86, 0x81c0a801, - 0x14b8b17f, 0x81b03ac2, - 0x145576b1, 0x81a01b6d, 0x13f22f58, 0x81904a0c, 0x138edbb1, 0x8180c6a9, - 0x132b7bf9, 0x8171914e, - 0x12c8106f, 0x8162aa04, 0x1264994e, 0x815410d4, 0x120116d5, 0x8145c5c7, - 0x119d8941, 0x8137c8e6, - 0x1139f0cf, 0x812a1a3a, 0x10d64dbd, 0x811cb9ca, 0x1072a048, 0x810fa7a0, - 0x100ee8ad, 0x8102e3c4, - 0xfab272b, 0x80f66e3c, 0xf475bff, 0x80ea4712, 0xee38766, 0x80de6e4c, - 0xe7fa99e, 0x80d2e3f2, - 0xe1bc2e4, 0x80c7a80a, 0xdb7d376, 0x80bcba9d, 0xd53db92, 0x80b21baf, - 0xcefdb76, 0x80a7cb49, - 0xc8bd35e, 0x809dc971, 0xc27c389, 0x8094162c, 0xbc3ac35, 0x808ab180, - 0xb5f8d9f, 0x80819b74, - 0xafb6805, 0x8078d40d, 0xa973ba5, 0x80705b50, 0xa3308bd, 0x80683143, - 0x9cecf89, 0x806055eb, - 0x96a9049, 0x8058c94c, 0x9064b3a, 0x80518b6b, 0x8a2009a, 0x804a9c4d, - 0x83db0a7, 0x8043fbf6, - 0x7d95b9e, 0x803daa6a, 0x77501be, 0x8037a7ac, 0x710a345, 0x8031f3c2, - 0x6ac406f, 0x802c8ead, - 0x647d97c, 0x80277872, 0x5e36ea9, 0x8022b114, 0x57f0035, 0x801e3895, - 0x51a8e5c, 0x801a0ef8, - 0x4b6195d, 0x80163440, 0x451a177, 0x8012a86f, 0x3ed26e6, 0x800f6b88, - 0x388a9ea, 0x800c7d8c, - 0x3242abf, 0x8009de7e, 0x2bfa9a4, 0x80078e5e, 0x25b26d7, 0x80058d2f, - 0x1f6a297, 0x8003daf1, - 0x1921d20, 0x800277a6, 0x12d96b1, 0x8001634e, 0xc90f88, 0x80009dea, - 0x6487e3, 0x8000277a, -}; - -static const q31_t WeightsQ31_2048[4096] = { - 0x7fffffff, 0x0, 0x7ffffd88, 0xffe6de05, 0x7ffff621, 0xffcdbc0b, 0x7fffe9cb, - 0xffb49a12, - 0x7fffd886, 0xff9b781d, 0x7fffc251, 0xff82562c, 0x7fffa72c, 0xff69343f, - 0x7fff8719, 0xff501258, - 0x7fff6216, 0xff36f078, 0x7fff3824, 0xff1dcea0, 0x7fff0943, 0xff04acd0, - 0x7ffed572, 0xfeeb8b0a, - 0x7ffe9cb2, 0xfed2694f, 0x7ffe5f03, 0xfeb947a0, 0x7ffe1c65, 0xfea025fd, - 0x7ffdd4d7, 0xfe870467, - 0x7ffd885a, 0xfe6de2e0, 0x7ffd36ee, 0xfe54c169, 0x7ffce093, 0xfe3ba002, - 0x7ffc8549, 0xfe227eac, - 0x7ffc250f, 0xfe095d69, 0x7ffbbfe6, 0xfdf03c3a, 0x7ffb55ce, 0xfdd71b1e, - 0x7ffae6c7, 0xfdbdfa18, - 0x7ffa72d1, 0xfda4d929, 0x7ff9f9ec, 0xfd8bb850, 0x7ff97c18, 0xfd729790, - 0x7ff8f954, 0xfd5976e9, - 0x7ff871a2, 0xfd40565c, 0x7ff7e500, 0xfd2735ea, 0x7ff75370, 0xfd0e1594, - 0x7ff6bcf0, 0xfcf4f55c, - 0x7ff62182, 0xfcdbd541, 0x7ff58125, 0xfcc2b545, 0x7ff4dbd9, 0xfca9956a, - 0x7ff4319d, 0xfc9075af, - 0x7ff38274, 0xfc775616, 0x7ff2ce5b, 0xfc5e36a0, 0x7ff21553, 0xfc45174e, - 0x7ff1575d, 0xfc2bf821, - 0x7ff09478, 0xfc12d91a, 0x7fefcca4, 0xfbf9ba39, 0x7feeffe1, 0xfbe09b80, - 0x7fee2e30, 0xfbc77cf0, - 0x7fed5791, 0xfbae5e89, 0x7fec7c02, 0xfb95404d, 0x7feb9b85, 0xfb7c223d, - 0x7feab61a, 0xfb630459, - 0x7fe9cbc0, 0xfb49e6a3, 0x7fe8dc78, 0xfb30c91b, 0x7fe7e841, 0xfb17abc2, - 0x7fe6ef1c, 0xfafe8e9b, - 0x7fe5f108, 0xfae571a4, 0x7fe4ee06, 0xfacc54e0, 0x7fe3e616, 0xfab3384f, - 0x7fe2d938, 0xfa9a1bf3, - 0x7fe1c76b, 0xfa80ffcb, 0x7fe0b0b1, 0xfa67e3da, 0x7fdf9508, 0xfa4ec821, - 0x7fde7471, 0xfa35ac9f, - 0x7fdd4eec, 0xfa1c9157, 0x7fdc247a, 0xfa037648, 0x7fdaf519, 0xf9ea5b75, - 0x7fd9c0ca, 0xf9d140de, - 0x7fd8878e, 0xf9b82684, 0x7fd74964, 0xf99f0c68, 0x7fd6064c, 0xf985f28a, - 0x7fd4be46, 0xf96cd8ed, - 0x7fd37153, 0xf953bf91, 0x7fd21f72, 0xf93aa676, 0x7fd0c8a3, 0xf9218d9e, - 0x7fcf6ce8, 0xf908750a, - 0x7fce0c3e, 0xf8ef5cbb, 0x7fcca6a7, 0xf8d644b2, 0x7fcb3c23, 0xf8bd2cef, - 0x7fc9ccb2, 0xf8a41574, - 0x7fc85854, 0xf88afe42, 0x7fc6df08, 0xf871e759, 0x7fc560cf, 0xf858d0bb, - 0x7fc3dda9, 0xf83fba68, - 0x7fc25596, 0xf826a462, 0x7fc0c896, 0xf80d8ea9, 0x7fbf36aa, 0xf7f4793e, - 0x7fbd9fd0, 0xf7db6423, - 0x7fbc040a, 0xf7c24f59, 0x7fba6357, 0xf7a93ae0, 0x7fb8bdb8, 0xf79026b9, - 0x7fb7132b, 0xf77712e5, - 0x7fb563b3, 0xf75dff66, 0x7fb3af4e, 0xf744ec3b, 0x7fb1f5fc, 0xf72bd967, - 0x7fb037bf, 0xf712c6ea, - 0x7fae7495, 0xf6f9b4c6, 0x7facac7f, 0xf6e0a2fa, 0x7faadf7c, 0xf6c79188, - 0x7fa90d8e, 0xf6ae8071, - 0x7fa736b4, 0xf6956fb7, 0x7fa55aee, 0xf67c5f59, 0x7fa37a3c, 0xf6634f59, - 0x7fa1949e, 0xf64a3fb8, - 0x7f9faa15, 0xf6313077, 0x7f9dbaa0, 0xf6182196, 0x7f9bc640, 0xf5ff1318, - 0x7f99ccf4, 0xf5e604fc, - 0x7f97cebd, 0xf5ccf743, 0x7f95cb9a, 0xf5b3e9f0, 0x7f93c38c, 0xf59add02, - 0x7f91b694, 0xf581d07b, - 0x7f8fa4b0, 0xf568c45b, 0x7f8d8de1, 0xf54fb8a4, 0x7f8b7227, 0xf536ad56, - 0x7f895182, 0xf51da273, - 0x7f872bf3, 0xf50497fb, 0x7f850179, 0xf4eb8def, 0x7f82d214, 0xf4d28451, - 0x7f809dc5, 0xf4b97b21, - 0x7f7e648c, 0xf4a07261, 0x7f7c2668, 0xf4876a10, 0x7f79e35a, 0xf46e6231, - 0x7f779b62, 0xf4555ac5, - 0x7f754e80, 0xf43c53cb, 0x7f72fcb4, 0xf4234d45, 0x7f70a5fe, 0xf40a4735, - 0x7f6e4a5e, 0xf3f1419a, - 0x7f6be9d4, 0xf3d83c77, 0x7f698461, 0xf3bf37cb, 0x7f671a05, 0xf3a63398, - 0x7f64aabf, 0xf38d2fe0, - 0x7f62368f, 0xf3742ca2, 0x7f5fbd77, 0xf35b29e0, 0x7f5d3f75, 0xf342279b, - 0x7f5abc8a, 0xf32925d3, - 0x7f5834b7, 0xf310248a, 0x7f55a7fa, 0xf2f723c1, 0x7f531655, 0xf2de2379, - 0x7f507fc7, 0xf2c523b2, - 0x7f4de451, 0xf2ac246e, 0x7f4b43f2, 0xf29325ad, 0x7f489eaa, 0xf27a2771, - 0x7f45f47b, 0xf26129ba, - 0x7f434563, 0xf2482c8a, 0x7f409164, 0xf22f2fe1, 0x7f3dd87c, 0xf21633c0, - 0x7f3b1aad, 0xf1fd3829, - 0x7f3857f6, 0xf1e43d1c, 0x7f359057, 0xf1cb429a, 0x7f32c3d1, 0xf1b248a5, - 0x7f2ff263, 0xf1994f3d, - 0x7f2d1c0e, 0xf1805662, 0x7f2a40d2, 0xf1675e17, 0x7f2760af, 0xf14e665c, - 0x7f247ba5, 0xf1356f32, - 0x7f2191b4, 0xf11c789a, 0x7f1ea2dc, 0xf1038295, 0x7f1baf1e, 0xf0ea8d24, - 0x7f18b679, 0xf0d19848, - 0x7f15b8ee, 0xf0b8a401, 0x7f12b67c, 0xf09fb051, 0x7f0faf25, 0xf086bd39, - 0x7f0ca2e7, 0xf06dcaba, - 0x7f0991c4, 0xf054d8d5, 0x7f067bba, 0xf03be78a, 0x7f0360cb, 0xf022f6da, - 0x7f0040f6, 0xf00a06c8, - 0x7efd1c3c, 0xeff11753, 0x7ef9f29d, 0xefd8287c, 0x7ef6c418, 0xefbf3a45, - 0x7ef390ae, 0xefa64cae, - 0x7ef05860, 0xef8d5fb8, 0x7eed1b2c, 0xef747365, 0x7ee9d914, 0xef5b87b5, - 0x7ee69217, 0xef429caa, - 0x7ee34636, 0xef29b243, 0x7edff570, 0xef10c883, 0x7edc9fc6, 0xeef7df6a, - 0x7ed94538, 0xeedef6f9, - 0x7ed5e5c6, 0xeec60f31, 0x7ed28171, 0xeead2813, 0x7ecf1837, 0xee9441a0, - 0x7ecbaa1a, 0xee7b5bd9, - 0x7ec8371a, 0xee6276bf, 0x7ec4bf36, 0xee499253, 0x7ec14270, 0xee30ae96, - 0x7ebdc0c6, 0xee17cb88, - 0x7eba3a39, 0xedfee92b, 0x7eb6aeca, 0xede60780, 0x7eb31e78, 0xedcd2687, - 0x7eaf8943, 0xedb44642, - 0x7eabef2c, 0xed9b66b2, 0x7ea85033, 0xed8287d7, 0x7ea4ac58, 0xed69a9b3, - 0x7ea1039b, 0xed50cc46, - 0x7e9d55fc, 0xed37ef91, 0x7e99a37c, 0xed1f1396, 0x7e95ec1a, 0xed063856, - 0x7e922fd6, 0xeced5dd0, - 0x7e8e6eb2, 0xecd48407, 0x7e8aa8ac, 0xecbbaafb, 0x7e86ddc6, 0xeca2d2ad, - 0x7e830dff, 0xec89fb1e, - 0x7e7f3957, 0xec71244f, 0x7e7b5fce, 0xec584e41, 0x7e778166, 0xec3f78f6, - 0x7e739e1d, 0xec26a46d, - 0x7e6fb5f4, 0xec0dd0a8, 0x7e6bc8eb, 0xebf4fda8, 0x7e67d703, 0xebdc2b6e, - 0x7e63e03b, 0xebc359fb, - 0x7e5fe493, 0xebaa894f, 0x7e5be40c, 0xeb91b96c, 0x7e57dea7, 0xeb78ea52, - 0x7e53d462, 0xeb601c04, - 0x7e4fc53e, 0xeb474e81, 0x7e4bb13c, 0xeb2e81ca, 0x7e47985b, 0xeb15b5e1, - 0x7e437a9c, 0xeafceac6, - 0x7e3f57ff, 0xeae4207a, 0x7e3b3083, 0xeacb56ff, 0x7e37042a, 0xeab28e56, - 0x7e32d2f4, 0xea99c67e, - 0x7e2e9cdf, 0xea80ff7a, 0x7e2a61ed, 0xea683949, 0x7e26221f, 0xea4f73ee, - 0x7e21dd73, 0xea36af69, - 0x7e1d93ea, 0xea1debbb, 0x7e194584, 0xea0528e5, 0x7e14f242, 0xe9ec66e8, - 0x7e109a24, 0xe9d3a5c5, - 0x7e0c3d29, 0xe9bae57d, 0x7e07db52, 0xe9a22610, 0x7e0374a0, 0xe9896781, - 0x7dff0911, 0xe970a9ce, - 0x7dfa98a8, 0xe957ecfb, 0x7df62362, 0xe93f3107, 0x7df1a942, 0xe92675f4, - 0x7ded2a47, 0xe90dbbc2, - 0x7de8a670, 0xe8f50273, 0x7de41dc0, 0xe8dc4a07, 0x7ddf9034, 0xe8c39280, - 0x7ddafdce, 0xe8aadbde, - 0x7dd6668f, 0xe8922622, 0x7dd1ca75, 0xe879714d, 0x7dcd2981, 0xe860bd61, - 0x7dc883b4, 0xe8480a5d, - 0x7dc3d90d, 0xe82f5844, 0x7dbf298d, 0xe816a716, 0x7dba7534, 0xe7fdf6d4, - 0x7db5bc02, 0xe7e5477f, - 0x7db0fdf8, 0xe7cc9917, 0x7dac3b15, 0xe7b3eb9f, 0x7da77359, 0xe79b3f16, - 0x7da2a6c6, 0xe782937e, - 0x7d9dd55a, 0xe769e8d8, 0x7d98ff17, 0xe7513f25, 0x7d9423fc, 0xe7389665, - 0x7d8f4409, 0xe71fee99, - 0x7d8a5f40, 0xe70747c4, 0x7d85759f, 0xe6eea1e4, 0x7d808728, 0xe6d5fcfc, - 0x7d7b93da, 0xe6bd590d, - 0x7d769bb5, 0xe6a4b616, 0x7d719eba, 0xe68c141a, 0x7d6c9ce9, 0xe6737319, - 0x7d679642, 0xe65ad315, - 0x7d628ac6, 0xe642340d, 0x7d5d7a74, 0xe6299604, 0x7d58654d, 0xe610f8f9, - 0x7d534b50, 0xe5f85cef, - 0x7d4e2c7f, 0xe5dfc1e5, 0x7d4908d9, 0xe5c727dd, 0x7d43e05e, 0xe5ae8ed8, - 0x7d3eb30f, 0xe595f6d7, - 0x7d3980ec, 0xe57d5fda, 0x7d3449f5, 0xe564c9e3, 0x7d2f0e2b, 0xe54c34f3, - 0x7d29cd8c, 0xe533a10a, - 0x7d24881b, 0xe51b0e2a, 0x7d1f3dd6, 0xe5027c53, 0x7d19eebf, 0xe4e9eb87, - 0x7d149ad5, 0xe4d15bc6, - 0x7d0f4218, 0xe4b8cd11, 0x7d09e489, 0xe4a03f69, 0x7d048228, 0xe487b2d0, - 0x7cff1af5, 0xe46f2745, - 0x7cf9aef0, 0xe4569ccb, 0x7cf43e1a, 0xe43e1362, 0x7ceec873, 0xe4258b0a, - 0x7ce94dfb, 0xe40d03c6, - 0x7ce3ceb2, 0xe3f47d96, 0x7cde4a98, 0xe3dbf87a, 0x7cd8c1ae, 0xe3c37474, - 0x7cd333f3, 0xe3aaf184, - 0x7ccda169, 0xe3926fad, 0x7cc80a0f, 0xe379eeed, 0x7cc26de5, 0xe3616f48, - 0x7cbcccec, 0xe348f0bd, - 0x7cb72724, 0xe330734d, 0x7cb17c8d, 0xe317f6fa, 0x7cabcd28, 0xe2ff7bc3, - 0x7ca618f3, 0xe2e701ac, - 0x7ca05ff1, 0xe2ce88b3, 0x7c9aa221, 0xe2b610da, 0x7c94df83, 0xe29d9a23, - 0x7c8f1817, 0xe285248d, - 0x7c894bde, 0xe26cb01b, 0x7c837ad8, 0xe2543ccc, 0x7c7da505, 0xe23bcaa2, - 0x7c77ca65, 0xe223599e, - 0x7c71eaf9, 0xe20ae9c1, 0x7c6c06c0, 0xe1f27b0b, 0x7c661dbc, 0xe1da0d7e, - 0x7c602fec, 0xe1c1a11b, - 0x7c5a3d50, 0xe1a935e2, 0x7c5445e9, 0xe190cbd4, 0x7c4e49b7, 0xe17862f3, - 0x7c4848ba, 0xe15ffb3f, - 0x7c4242f2, 0xe14794ba, 0x7c3c3860, 0xe12f2f63, 0x7c362904, 0xe116cb3d, - 0x7c3014de, 0xe0fe6848, - 0x7c29fbee, 0xe0e60685, 0x7c23de35, 0xe0cda5f5, 0x7c1dbbb3, 0xe0b54698, - 0x7c179467, 0xe09ce871, - 0x7c116853, 0xe0848b7f, 0x7c0b3777, 0xe06c2fc4, 0x7c0501d2, 0xe053d541, - 0x7bfec765, 0xe03b7bf6, - 0x7bf88830, 0xe02323e5, 0x7bf24434, 0xe00acd0e, 0x7bebfb70, 0xdff27773, - 0x7be5ade6, 0xdfda2314, - 0x7bdf5b94, 0xdfc1cff3, 0x7bd9047c, 0xdfa97e0f, 0x7bd2a89e, 0xdf912d6b, - 0x7bcc47fa, 0xdf78de07, - 0x7bc5e290, 0xdf608fe4, 0x7bbf7860, 0xdf484302, 0x7bb9096b, 0xdf2ff764, - 0x7bb295b0, 0xdf17ad0a, - 0x7bac1d31, 0xdeff63f4, 0x7ba59fee, 0xdee71c24, 0x7b9f1de6, 0xdeced59b, - 0x7b989719, 0xdeb69059, - 0x7b920b89, 0xde9e4c60, 0x7b8b7b36, 0xde8609b1, 0x7b84e61f, 0xde6dc84b, - 0x7b7e4c45, 0xde558831, - 0x7b77ada8, 0xde3d4964, 0x7b710a49, 0xde250be3, 0x7b6a6227, 0xde0ccfb1, - 0x7b63b543, 0xddf494ce, - 0x7b5d039e, 0xdddc5b3b, 0x7b564d36, 0xddc422f8, 0x7b4f920e, 0xddabec08, - 0x7b48d225, 0xdd93b66a, - 0x7b420d7a, 0xdd7b8220, 0x7b3b4410, 0xdd634f2b, 0x7b3475e5, 0xdd4b1d8c, - 0x7b2da2fa, 0xdd32ed43, - 0x7b26cb4f, 0xdd1abe51, 0x7b1feee5, 0xdd0290b8, 0x7b190dbc, 0xdcea6478, - 0x7b1227d3, 0xdcd23993, - 0x7b0b3d2c, 0xdcba1008, 0x7b044dc7, 0xdca1e7da, 0x7afd59a4, 0xdc89c109, - 0x7af660c2, 0xdc719b96, - 0x7aef6323, 0xdc597781, 0x7ae860c7, 0xdc4154cd, 0x7ae159ae, 0xdc293379, - 0x7ada4dd8, 0xdc111388, - 0x7ad33d45, 0xdbf8f4f8, 0x7acc27f7, 0xdbe0d7cd, 0x7ac50dec, 0xdbc8bc06, - 0x7abdef25, 0xdbb0a1a4, - 0x7ab6cba4, 0xdb9888a8, 0x7aafa367, 0xdb807114, 0x7aa8766f, 0xdb685ae9, - 0x7aa144bc, 0xdb504626, - 0x7a9a0e50, 0xdb3832cd, 0x7a92d329, 0xdb2020e0, 0x7a8b9348, 0xdb08105e, - 0x7a844eae, 0xdaf00149, - 0x7a7d055b, 0xdad7f3a2, 0x7a75b74f, 0xdabfe76a, 0x7a6e648a, 0xdaa7dca1, - 0x7a670d0d, 0xda8fd349, - 0x7a5fb0d8, 0xda77cb63, 0x7a584feb, 0xda5fc4ef, 0x7a50ea47, 0xda47bfee, - 0x7a497feb, 0xda2fbc61, - 0x7a4210d8, 0xda17ba4a, 0x7a3a9d0f, 0xd9ffb9a9, 0x7a332490, 0xd9e7ba7f, - 0x7a2ba75a, 0xd9cfbccd, - 0x7a24256f, 0xd9b7c094, 0x7a1c9ece, 0xd99fc5d4, 0x7a151378, 0xd987cc90, - 0x7a0d836d, 0xd96fd4c7, - 0x7a05eead, 0xd957de7a, 0x79fe5539, 0xd93fe9ab, 0x79f6b711, 0xd927f65b, - 0x79ef1436, 0xd910048a, - 0x79e76ca7, 0xd8f81439, 0x79dfc064, 0xd8e0256a, 0x79d80f6f, 0xd8c8381d, - 0x79d059c8, 0xd8b04c52, - 0x79c89f6e, 0xd898620c, 0x79c0e062, 0xd880794b, 0x79b91ca4, 0xd868920f, - 0x79b15435, 0xd850ac5a, - 0x79a98715, 0xd838c82d, 0x79a1b545, 0xd820e589, 0x7999dec4, 0xd809046e, - 0x79920392, 0xd7f124dd, - 0x798a23b1, 0xd7d946d8, 0x79823f20, 0xd7c16a5f, 0x797a55e0, 0xd7a98f73, - 0x797267f2, 0xd791b616, - 0x796a7554, 0xd779de47, 0x79627e08, 0xd7620808, 0x795a820e, 0xd74a335b, - 0x79528167, 0xd732603f, - 0x794a7c12, 0xd71a8eb5, 0x79427210, 0xd702bec0, 0x793a6361, 0xd6eaf05f, - 0x79325006, 0xd6d32393, - 0x792a37fe, 0xd6bb585e, 0x79221b4b, 0xd6a38ec0, 0x7919f9ec, 0xd68bc6ba, - 0x7911d3e2, 0xd674004e, - 0x7909a92d, 0xd65c3b7b, 0x790179cd, 0xd6447844, 0x78f945c3, 0xd62cb6a8, - 0x78f10d0f, 0xd614f6a9, - 0x78e8cfb2, 0xd5fd3848, 0x78e08dab, 0xd5e57b85, 0x78d846fb, 0xd5cdc062, - 0x78cffba3, 0xd5b606e0, - 0x78c7aba2, 0xd59e4eff, 0x78bf56f9, 0xd58698c0, 0x78b6fda8, 0xd56ee424, - 0x78ae9fb0, 0xd557312d, - 0x78a63d11, 0xd53f7fda, 0x789dd5cb, 0xd527d02e, 0x789569df, 0xd5102228, - 0x788cf94c, 0xd4f875ca, - 0x78848414, 0xd4e0cb15, 0x787c0a36, 0xd4c92209, 0x78738bb3, 0xd4b17aa8, - 0x786b088c, 0xd499d4f2, - 0x786280bf, 0xd48230e9, 0x7859f44f, 0xd46a8e8d, 0x7851633b, 0xd452eddf, - 0x7848cd83, 0xd43b4ee0, - 0x78403329, 0xd423b191, 0x7837942b, 0xd40c15f3, 0x782ef08b, 0xd3f47c06, - 0x78264849, 0xd3dce3cd, - 0x781d9b65, 0xd3c54d47, 0x7814e9df, 0xd3adb876, 0x780c33b8, 0xd396255a, - 0x780378f1, 0xd37e93f4, - 0x77fab989, 0xd3670446, 0x77f1f581, 0xd34f764f, 0x77e92cd9, 0xd337ea12, - 0x77e05f91, 0xd3205f8f, - 0x77d78daa, 0xd308d6c7, 0x77ceb725, 0xd2f14fba, 0x77c5dc01, 0xd2d9ca6a, - 0x77bcfc3f, 0xd2c246d8, - 0x77b417df, 0xd2aac504, 0x77ab2ee2, 0xd29344f0, 0x77a24148, 0xd27bc69c, - 0x77994f11, 0xd2644a0a, - 0x7790583e, 0xd24ccf39, 0x77875cce, 0xd235562b, 0x777e5cc3, 0xd21ddee2, - 0x7775581d, 0xd206695d, - 0x776c4edb, 0xd1eef59e, 0x776340ff, 0xd1d783a6, 0x775a2e89, 0xd1c01375, - 0x77511778, 0xd1a8a50d, - 0x7747fbce, 0xd191386e, 0x773edb8b, 0xd179cd99, 0x7735b6af, 0xd1626490, - 0x772c8d3a, 0xd14afd52, - 0x77235f2d, 0xd13397e2, 0x771a2c88, 0xd11c343f, 0x7710f54c, 0xd104d26b, - 0x7707b979, 0xd0ed7267, - 0x76fe790e, 0xd0d61434, 0x76f5340e, 0xd0beb7d2, 0x76ebea77, 0xd0a75d42, - 0x76e29c4b, 0xd0900486, - 0x76d94989, 0xd078ad9e, 0x76cff232, 0xd061588b, 0x76c69647, 0xd04a054e, - 0x76bd35c7, 0xd032b3e7, - 0x76b3d0b4, 0xd01b6459, 0x76aa670d, 0xd00416a3, 0x76a0f8d2, 0xcfeccac7, - 0x76978605, 0xcfd580c6, - 0x768e0ea6, 0xcfbe389f, 0x768492b4, 0xcfa6f255, 0x767b1231, 0xcf8fade9, - 0x76718d1c, 0xcf786b5a, - 0x76680376, 0xcf612aaa, 0x765e7540, 0xcf49ebda, 0x7654e279, 0xcf32aeeb, - 0x764b4b23, 0xcf1b73de, - 0x7641af3d, 0xcf043ab3, 0x76380ec8, 0xceed036b, 0x762e69c4, 0xced5ce08, - 0x7624c031, 0xcebe9a8a, - 0x761b1211, 0xcea768f2, 0x76115f63, 0xce903942, 0x7607a828, 0xce790b79, - 0x75fdec60, 0xce61df99, - 0x75f42c0b, 0xce4ab5a2, 0x75ea672a, 0xce338d97, 0x75e09dbd, 0xce1c6777, - 0x75d6cfc5, 0xce054343, - 0x75ccfd42, 0xcdee20fc, 0x75c32634, 0xcdd700a4, 0x75b94a9c, 0xcdbfe23a, - 0x75af6a7b, 0xcda8c5c1, - 0x75a585cf, 0xcd91ab39, 0x759b9c9b, 0xcd7a92a2, 0x7591aedd, 0xcd637bfe, - 0x7587bc98, 0xcd4c674d, - 0x757dc5ca, 0xcd355491, 0x7573ca75, 0xcd1e43ca, 0x7569ca99, 0xcd0734f9, - 0x755fc635, 0xccf0281f, - 0x7555bd4c, 0xccd91d3d, 0x754bafdc, 0xccc21455, 0x75419de7, 0xccab0d65, - 0x7537876c, 0xcc940871, - 0x752d6c6c, 0xcc7d0578, 0x75234ce8, 0xcc66047b, 0x751928e0, 0xcc4f057c, - 0x750f0054, 0xcc38087b, - 0x7504d345, 0xcc210d79, 0x74faa1b3, 0xcc0a1477, 0x74f06b9e, 0xcbf31d75, - 0x74e63108, 0xcbdc2876, - 0x74dbf1ef, 0xcbc53579, 0x74d1ae55, 0xcbae447f, 0x74c7663a, 0xcb97558a, - 0x74bd199f, 0xcb80689a, - 0x74b2c884, 0xcb697db0, 0x74a872e8, 0xcb5294ce, 0x749e18cd, 0xcb3badf3, - 0x7493ba34, 0xcb24c921, - 0x7489571c, 0xcb0de658, 0x747eef85, 0xcaf7059a, 0x74748371, 0xcae026e8, - 0x746a12df, 0xcac94a42, - 0x745f9dd1, 0xcab26fa9, 0x74552446, 0xca9b971e, 0x744aa63f, 0xca84c0a3, - 0x744023bc, 0xca6dec37, - 0x74359cbd, 0xca5719db, 0x742b1144, 0xca404992, 0x74208150, 0xca297b5a, - 0x7415ece2, 0xca12af37, - 0x740b53fb, 0xc9fbe527, 0x7400b69a, 0xc9e51d2d, 0x73f614c0, 0xc9ce5748, - 0x73eb6e6e, 0xc9b7937a, - 0x73e0c3a3, 0xc9a0d1c5, 0x73d61461, 0xc98a1227, 0x73cb60a8, 0xc97354a4, - 0x73c0a878, 0xc95c993a, - 0x73b5ebd1, 0xc945dfec, 0x73ab2ab4, 0xc92f28ba, 0x73a06522, 0xc91873a5, - 0x73959b1b, 0xc901c0ae, - 0x738acc9e, 0xc8eb0fd6, 0x737ff9ae, 0xc8d4611d, 0x73752249, 0xc8bdb485, - 0x736a4671, 0xc8a70a0e, - 0x735f6626, 0xc89061ba, 0x73548168, 0xc879bb89, 0x73499838, 0xc863177b, - 0x733eaa96, 0xc84c7593, - 0x7333b883, 0xc835d5d0, 0x7328c1ff, 0xc81f3834, 0x731dc70a, 0xc8089cbf, - 0x7312c7a5, 0xc7f20373, - 0x7307c3d0, 0xc7db6c50, 0x72fcbb8c, 0xc7c4d757, 0x72f1aed9, 0xc7ae4489, - 0x72e69db7, 0xc797b3e7, - 0x72db8828, 0xc7812572, 0x72d06e2b, 0xc76a992a, 0x72c54fc1, 0xc7540f11, - 0x72ba2cea, 0xc73d8727, - 0x72af05a7, 0xc727016d, 0x72a3d9f7, 0xc7107de4, 0x7298a9dd, 0xc6f9fc8d, - 0x728d7557, 0xc6e37d69, - 0x72823c67, 0xc6cd0079, 0x7276ff0d, 0xc6b685bd, 0x726bbd48, 0xc6a00d37, - 0x7260771b, 0xc68996e7, - 0x72552c85, 0xc67322ce, 0x7249dd86, 0xc65cb0ed, 0x723e8a20, 0xc6464144, - 0x72333251, 0xc62fd3d6, - 0x7227d61c, 0xc61968a2, 0x721c7580, 0xc602ffaa, 0x7211107e, 0xc5ec98ee, - 0x7205a716, 0xc5d6346f, - 0x71fa3949, 0xc5bfd22e, 0x71eec716, 0xc5a9722c, 0x71e35080, 0xc593146a, - 0x71d7d585, 0xc57cb8e9, - 0x71cc5626, 0xc5665fa9, 0x71c0d265, 0xc55008ab, 0x71b54a41, 0xc539b3f1, - 0x71a9bdba, 0xc523617a, - 0x719e2cd2, 0xc50d1149, 0x71929789, 0xc4f6c35d, 0x7186fdde, 0xc4e077b8, - 0x717b5fd3, 0xc4ca2e5b, - 0x716fbd68, 0xc4b3e746, 0x7164169d, 0xc49da27a, 0x71586b74, 0xc4875ff9, - 0x714cbbeb, 0xc4711fc2, - 0x71410805, 0xc45ae1d7, 0x71354fc0, 0xc444a639, 0x7129931f, 0xc42e6ce8, - 0x711dd220, 0xc41835e6, - 0x71120cc5, 0xc4020133, 0x7106430e, 0xc3ebced0, 0x70fa74fc, 0xc3d59ebe, - 0x70eea28e, 0xc3bf70fd, - 0x70e2cbc6, 0xc3a94590, 0x70d6f0a4, 0xc3931c76, 0x70cb1128, 0xc37cf5b0, - 0x70bf2d53, 0xc366d140, - 0x70b34525, 0xc350af26, 0x70a7589f, 0xc33a8f62, 0x709b67c0, 0xc32471f7, - 0x708f728b, 0xc30e56e4, - 0x708378ff, 0xc2f83e2a, 0x70777b1c, 0xc2e227cb, 0x706b78e3, 0xc2cc13c7, - 0x705f7255, 0xc2b6021f, - 0x70536771, 0xc29ff2d4, 0x70475839, 0xc289e5e7, 0x703b44ad, 0xc273db58, - 0x702f2ccd, 0xc25dd329, - 0x7023109a, 0xc247cd5a, 0x7016f014, 0xc231c9ec, 0x700acb3c, 0xc21bc8e1, - 0x6ffea212, 0xc205ca38, - 0x6ff27497, 0xc1efcdf3, 0x6fe642ca, 0xc1d9d412, 0x6fda0cae, 0xc1c3dc97, - 0x6fcdd241, 0xc1ade781, - 0x6fc19385, 0xc197f4d4, 0x6fb5507a, 0xc182048d, 0x6fa90921, 0xc16c16b0, - 0x6f9cbd79, 0xc1562b3d, - 0x6f906d84, 0xc1404233, 0x6f841942, 0xc12a5b95, 0x6f77c0b3, 0xc1147764, - 0x6f6b63d8, 0xc0fe959f, - 0x6f5f02b2, 0xc0e8b648, 0x6f529d40, 0xc0d2d960, 0x6f463383, 0xc0bcfee7, - 0x6f39c57d, 0xc0a726df, - 0x6f2d532c, 0xc0915148, 0x6f20dc92, 0xc07b7e23, 0x6f1461b0, 0xc065ad70, - 0x6f07e285, 0xc04fdf32, - 0x6efb5f12, 0xc03a1368, 0x6eeed758, 0xc0244a14, 0x6ee24b57, 0xc00e8336, - 0x6ed5bb10, 0xbff8bece, - 0x6ec92683, 0xbfe2fcdf, 0x6ebc8db0, 0xbfcd3d69, 0x6eaff099, 0xbfb7806c, - 0x6ea34f3d, 0xbfa1c5ea, - 0x6e96a99d, 0xbf8c0de3, 0x6e89ffb9, 0xbf765858, 0x6e7d5193, 0xbf60a54a, - 0x6e709f2a, 0xbf4af4ba, - 0x6e63e87f, 0xbf3546a8, 0x6e572d93, 0xbf1f9b16, 0x6e4a6e66, 0xbf09f205, - 0x6e3daaf8, 0xbef44b74, - 0x6e30e34a, 0xbedea765, 0x6e24175c, 0xbec905d9, 0x6e174730, 0xbeb366d1, - 0x6e0a72c5, 0xbe9dca4e, - 0x6dfd9a1c, 0xbe88304f, 0x6df0bd35, 0xbe7298d7, 0x6de3dc11, 0xbe5d03e6, - 0x6dd6f6b1, 0xbe47717c, - 0x6dca0d14, 0xbe31e19b, 0x6dbd1f3c, 0xbe1c5444, 0x6db02d29, 0xbe06c977, - 0x6da336dc, 0xbdf14135, - 0x6d963c54, 0xbddbbb7f, 0x6d893d93, 0xbdc63856, 0x6d7c3a98, 0xbdb0b7bb, - 0x6d6f3365, 0xbd9b39ad, - 0x6d6227fa, 0xbd85be30, 0x6d551858, 0xbd704542, 0x6d48047e, 0xbd5acee5, - 0x6d3aec6e, 0xbd455b1a, - 0x6d2dd027, 0xbd2fe9e2, 0x6d20afac, 0xbd1a7b3d, 0x6d138afb, 0xbd050f2c, - 0x6d066215, 0xbcefa5b0, - 0x6cf934fc, 0xbcda3ecb, 0x6cec03af, 0xbcc4da7b, 0x6cdece2f, 0xbcaf78c4, - 0x6cd1947c, 0xbc9a19a5, - 0x6cc45698, 0xbc84bd1f, 0x6cb71482, 0xbc6f6333, 0x6ca9ce3b, 0xbc5a0be2, - 0x6c9c83c3, 0xbc44b72c, - 0x6c8f351c, 0xbc2f6513, 0x6c81e245, 0xbc1a1598, 0x6c748b3f, 0xbc04c8ba, - 0x6c67300b, 0xbbef7e7c, - 0x6c59d0a9, 0xbbda36dd, 0x6c4c6d1a, 0xbbc4f1df, 0x6c3f055d, 0xbbafaf82, - 0x6c319975, 0xbb9a6fc7, - 0x6c242960, 0xbb8532b0, 0x6c16b521, 0xbb6ff83c, 0x6c093cb6, 0xbb5ac06d, - 0x6bfbc021, 0xbb458b43, - 0x6bee3f62, 0xbb3058c0, 0x6be0ba7b, 0xbb1b28e4, 0x6bd3316a, 0xbb05fbb0, - 0x6bc5a431, 0xbaf0d125, - 0x6bb812d1, 0xbadba943, 0x6baa7d49, 0xbac6840c, 0x6b9ce39b, 0xbab16180, - 0x6b8f45c7, 0xba9c41a0, - 0x6b81a3cd, 0xba87246d, 0x6b73fdae, 0xba7209e7, 0x6b66536b, 0xba5cf210, - 0x6b58a503, 0xba47dce8, - 0x6b4af279, 0xba32ca71, 0x6b3d3bcb, 0xba1dbaaa, 0x6b2f80fb, 0xba08ad95, - 0x6b21c208, 0xb9f3a332, - 0x6b13fef5, 0xb9de9b83, 0x6b0637c1, 0xb9c99688, 0x6af86c6c, 0xb9b49442, - 0x6aea9cf8, 0xb99f94b2, - 0x6adcc964, 0xb98a97d8, 0x6acef1b2, 0xb9759db6, 0x6ac115e2, 0xb960a64c, - 0x6ab335f4, 0xb94bb19b, - 0x6aa551e9, 0xb936bfa4, 0x6a9769c1, 0xb921d067, 0x6a897d7d, 0xb90ce3e6, - 0x6a7b8d1e, 0xb8f7fa21, - 0x6a6d98a4, 0xb8e31319, 0x6a5fa010, 0xb8ce2ecf, 0x6a51a361, 0xb8b94d44, - 0x6a43a29a, 0xb8a46e78, - 0x6a359db9, 0xb88f926d, 0x6a2794c1, 0xb87ab922, 0x6a1987b0, 0xb865e299, - 0x6a0b7689, 0xb8510ed4, - 0x69fd614a, 0xb83c3dd1, 0x69ef47f6, 0xb8276f93, 0x69e12a8c, 0xb812a41a, - 0x69d3090e, 0xb7fddb67, - 0x69c4e37a, 0xb7e9157a, 0x69b6b9d3, 0xb7d45255, 0x69a88c19, 0xb7bf91f8, - 0x699a5a4c, 0xb7aad465, - 0x698c246c, 0xb796199b, 0x697dea7b, 0xb781619c, 0x696fac78, 0xb76cac69, - 0x69616a65, 0xb757fa01, - 0x69532442, 0xb7434a67, 0x6944da10, 0xb72e9d9b, 0x69368bce, 0xb719f39e, - 0x6928397e, 0xb7054c6f, - 0x6919e320, 0xb6f0a812, 0x690b88b5, 0xb6dc0685, 0x68fd2a3d, 0xb6c767ca, - 0x68eec7b9, 0xb6b2cbe2, - 0x68e06129, 0xb69e32cd, 0x68d1f68f, 0xb6899c8d, 0x68c387e9, 0xb6750921, - 0x68b5153a, 0xb660788c, - 0x68a69e81, 0xb64beacd, 0x689823bf, 0xb6375fe5, 0x6889a4f6, 0xb622d7d6, - 0x687b2224, 0xb60e529f, - 0x686c9b4b, 0xb5f9d043, 0x685e106c, 0xb5e550c1, 0x684f8186, 0xb5d0d41a, - 0x6840ee9b, 0xb5bc5a50, - 0x683257ab, 0xb5a7e362, 0x6823bcb7, 0xb5936f53, 0x68151dbe, 0xb57efe22, - 0x68067ac3, 0xb56a8fd0, - 0x67f7d3c5, 0xb556245e, 0x67e928c5, 0xb541bbcd, 0x67da79c3, 0xb52d561e, - 0x67cbc6c0, 0xb518f351, - 0x67bd0fbd, 0xb5049368, 0x67ae54ba, 0xb4f03663, 0x679f95b7, 0xb4dbdc42, - 0x6790d2b6, 0xb4c78507, - 0x67820bb7, 0xb4b330b3, 0x677340ba, 0xb49edf45, 0x676471c0, 0xb48a90c0, - 0x67559eca, 0xb4764523, - 0x6746c7d8, 0xb461fc70, 0x6737ecea, 0xb44db6a8, 0x67290e02, 0xb43973ca, - 0x671a2b20, 0xb42533d8, - 0x670b4444, 0xb410f6d3, 0x66fc596f, 0xb3fcbcbb, 0x66ed6aa1, 0xb3e88592, - 0x66de77dc, 0xb3d45157, - 0x66cf8120, 0xb3c0200c, 0x66c0866d, 0xb3abf1b2, 0x66b187c3, 0xb397c649, - 0x66a28524, 0xb3839dd3, - 0x66937e91, 0xb36f784f, 0x66847408, 0xb35b55bf, 0x6675658c, 0xb3473623, - 0x6666531d, 0xb333197c, - 0x66573cbb, 0xb31effcc, 0x66482267, 0xb30ae912, 0x66390422, 0xb2f6d550, - 0x6629e1ec, 0xb2e2c486, - 0x661abbc5, 0xb2ceb6b5, 0x660b91af, 0xb2baabde, 0x65fc63a9, 0xb2a6a402, - 0x65ed31b5, 0xb2929f21, - 0x65ddfbd3, 0xb27e9d3c, 0x65cec204, 0xb26a9e54, 0x65bf8447, 0xb256a26a, - 0x65b0429f, 0xb242a97e, - 0x65a0fd0b, 0xb22eb392, 0x6591b38c, 0xb21ac0a6, 0x65826622, 0xb206d0ba, - 0x657314cf, 0xb1f2e3d0, - 0x6563bf92, 0xb1def9e9, 0x6554666d, 0xb1cb1304, 0x6545095f, 0xb1b72f23, - 0x6535a86b, 0xb1a34e47, - 0x6526438f, 0xb18f7071, 0x6516dacd, 0xb17b95a0, 0x65076e25, 0xb167bdd7, - 0x64f7fd98, 0xb153e915, - 0x64e88926, 0xb140175b, 0x64d910d1, 0xb12c48ab, 0x64c99498, 0xb1187d05, - 0x64ba147d, 0xb104b46a, - 0x64aa907f, 0xb0f0eeda, 0x649b08a0, 0xb0dd2c56, 0x648b7ce0, 0xb0c96ce0, - 0x647bed3f, 0xb0b5b077, - 0x646c59bf, 0xb0a1f71d, 0x645cc260, 0xb08e40d2, 0x644d2722, 0xb07a8d97, - 0x643d8806, 0xb066dd6d, - 0x642de50d, 0xb0533055, 0x641e3e38, 0xb03f864f, 0x640e9386, 0xb02bdf5c, - 0x63fee4f8, 0xb0183b7d, - 0x63ef3290, 0xb0049ab3, 0x63df7c4d, 0xaff0fcfe, 0x63cfc231, 0xafdd625f, - 0x63c0043b, 0xafc9cad7, - 0x63b0426d, 0xafb63667, 0x63a07cc7, 0xafa2a50f, 0x6390b34a, 0xaf8f16d1, - 0x6380e5f6, 0xaf7b8bac, - 0x637114cc, 0xaf6803a2, 0x63613fcd, 0xaf547eb3, 0x635166f9, 0xaf40fce1, - 0x63418a50, 0xaf2d7e2b, - 0x6331a9d4, 0xaf1a0293, 0x6321c585, 0xaf068a1a, 0x6311dd64, 0xaef314c0, - 0x6301f171, 0xaedfa285, - 0x62f201ac, 0xaecc336c, 0x62e20e17, 0xaeb8c774, 0x62d216b3, 0xaea55e9e, - 0x62c21b7e, 0xae91f8eb, - 0x62b21c7b, 0xae7e965b, 0x62a219aa, 0xae6b36f0, 0x6292130c, 0xae57daab, - 0x628208a1, 0xae44818b, - 0x6271fa69, 0xae312b92, 0x6261e866, 0xae1dd8c0, 0x6251d298, 0xae0a8916, - 0x6241b8ff, 0xadf73c96, - 0x62319b9d, 0xade3f33e, 0x62217a72, 0xadd0ad12, 0x6211557e, 0xadbd6a10, - 0x62012cc2, 0xadaa2a3b, - 0x61f1003f, 0xad96ed92, 0x61e0cff5, 0xad83b416, 0x61d09be5, 0xad707dc8, - 0x61c06410, 0xad5d4aaa, - 0x61b02876, 0xad4a1aba, 0x619fe918, 0xad36edfc, 0x618fa5f7, 0xad23c46e, - 0x617f5f12, 0xad109e12, - 0x616f146c, 0xacfd7ae8, 0x615ec603, 0xacea5af2, 0x614e73da, 0xacd73e30, - 0x613e1df0, 0xacc424a3, - 0x612dc447, 0xacb10e4b, 0x611d66de, 0xac9dfb29, 0x610d05b7, 0xac8aeb3e, - 0x60fca0d2, 0xac77de8b, - 0x60ec3830, 0xac64d510, 0x60dbcbd1, 0xac51cecf, 0x60cb5bb7, 0xac3ecbc7, - 0x60bae7e1, 0xac2bcbfa, - 0x60aa7050, 0xac18cf69, 0x6099f505, 0xac05d613, 0x60897601, 0xabf2dffb, - 0x6078f344, 0xabdfed1f, - 0x60686ccf, 0xabccfd83, 0x6057e2a2, 0xabba1125, 0x604754bf, 0xaba72807, - 0x6036c325, 0xab944229, - 0x60262dd6, 0xab815f8d, 0x601594d1, 0xab6e8032, 0x6004f819, 0xab5ba41a, - 0x5ff457ad, 0xab48cb46, - 0x5fe3b38d, 0xab35f5b5, 0x5fd30bbc, 0xab23236a, 0x5fc26038, 0xab105464, - 0x5fb1b104, 0xaafd88a4, - 0x5fa0fe1f, 0xaaeac02c, 0x5f90478a, 0xaad7fafb, 0x5f7f8d46, 0xaac53912, - 0x5f6ecf53, 0xaab27a73, - 0x5f5e0db3, 0xaa9fbf1e, 0x5f4d4865, 0xaa8d0713, 0x5f3c7f6b, 0xaa7a5253, - 0x5f2bb2c5, 0xaa67a0e0, - 0x5f1ae274, 0xaa54f2ba, 0x5f0a0e77, 0xaa4247e1, 0x5ef936d1, 0xaa2fa056, - 0x5ee85b82, 0xaa1cfc1a, - 0x5ed77c8a, 0xaa0a5b2e, 0x5ec699e9, 0xa9f7bd92, 0x5eb5b3a2, 0xa9e52347, - 0x5ea4c9b3, 0xa9d28c4e, - 0x5e93dc1f, 0xa9bff8a8, 0x5e82eae5, 0xa9ad6855, 0x5e71f606, 0xa99adb56, - 0x5e60fd84, 0xa98851ac, - 0x5e50015d, 0xa975cb57, 0x5e3f0194, 0xa9634858, 0x5e2dfe29, 0xa950c8b0, - 0x5e1cf71c, 0xa93e4c5f, - 0x5e0bec6e, 0xa92bd367, 0x5dfade20, 0xa9195dc7, 0x5de9cc33, 0xa906eb82, - 0x5dd8b6a7, 0xa8f47c97, - 0x5dc79d7c, 0xa8e21106, 0x5db680b4, 0xa8cfa8d2, 0x5da5604f, 0xa8bd43fa, - 0x5d943c4e, 0xa8aae280, - 0x5d8314b1, 0xa8988463, 0x5d71e979, 0xa88629a5, 0x5d60baa7, 0xa873d246, - 0x5d4f883b, 0xa8617e48, - 0x5d3e5237, 0xa84f2daa, 0x5d2d189a, 0xa83ce06e, 0x5d1bdb65, 0xa82a9693, - 0x5d0a9a9a, 0xa818501c, - 0x5cf95638, 0xa8060d08, 0x5ce80e41, 0xa7f3cd59, 0x5cd6c2b5, 0xa7e1910f, - 0x5cc57394, 0xa7cf582a, - 0x5cb420e0, 0xa7bd22ac, 0x5ca2ca99, 0xa7aaf094, 0x5c9170bf, 0xa798c1e5, - 0x5c801354, 0xa786969e, - 0x5c6eb258, 0xa7746ec0, 0x5c5d4dcc, 0xa7624a4d, 0x5c4be5b0, 0xa7502943, - 0x5c3a7a05, 0xa73e0ba5, - 0x5c290acc, 0xa72bf174, 0x5c179806, 0xa719daae, 0x5c0621b2, 0xa707c757, - 0x5bf4a7d2, 0xa6f5b76d, - 0x5be32a67, 0xa6e3aaf2, 0x5bd1a971, 0xa6d1a1e7, 0x5bc024f0, 0xa6bf9c4b, - 0x5bae9ce7, 0xa6ad9a21, - 0x5b9d1154, 0xa69b9b68, 0x5b8b8239, 0xa689a022, 0x5b79ef96, 0xa677a84e, - 0x5b68596d, 0xa665b3ee, - 0x5b56bfbd, 0xa653c303, 0x5b452288, 0xa641d58c, 0x5b3381ce, 0xa62feb8b, - 0x5b21dd90, 0xa61e0501, - 0x5b1035cf, 0xa60c21ee, 0x5afe8a8b, 0xa5fa4252, 0x5aecdbc5, 0xa5e8662f, - 0x5adb297d, 0xa5d68d85, - 0x5ac973b5, 0xa5c4b855, 0x5ab7ba6c, 0xa5b2e6a0, 0x5aa5fda5, 0xa5a11866, - 0x5a943d5e, 0xa58f4da8, - 0x5a82799a, 0xa57d8666, 0x5a70b258, 0xa56bc2a2, 0x5a5ee79a, 0xa55a025b, - 0x5a4d1960, 0xa5484594, - 0x5a3b47ab, 0xa5368c4b, 0x5a29727b, 0xa524d683, 0x5a1799d1, 0xa513243b, - 0x5a05bdae, 0xa5017575, - 0x59f3de12, 0xa4efca31, 0x59e1faff, 0xa4de2270, 0x59d01475, 0xa4cc7e32, - 0x59be2a74, 0xa4badd78, - 0x59ac3cfd, 0xa4a94043, 0x599a4c12, 0xa497a693, 0x598857b2, 0xa486106a, - 0x59765fde, 0xa4747dc7, - 0x59646498, 0xa462eeac, 0x595265df, 0xa4516319, 0x594063b5, 0xa43fdb10, - 0x592e5e19, 0xa42e568f, - 0x591c550e, 0xa41cd599, 0x590a4893, 0xa40b582e, 0x58f838a9, 0xa3f9de4e, - 0x58e62552, 0xa3e867fa, - 0x58d40e8c, 0xa3d6f534, 0x58c1f45b, 0xa3c585fb, 0x58afd6bd, 0xa3b41a50, - 0x589db5b3, 0xa3a2b234, - 0x588b9140, 0xa3914da8, 0x58796962, 0xa37fecac, 0x58673e1b, 0xa36e8f41, - 0x58550f6c, 0xa35d3567, - 0x5842dd54, 0xa34bdf20, 0x5830a7d6, 0xa33a8c6c, 0x581e6ef1, 0xa3293d4b, - 0x580c32a7, 0xa317f1bf, - 0x57f9f2f8, 0xa306a9c8, 0x57e7afe4, 0xa2f56566, 0x57d5696d, 0xa2e4249b, - 0x57c31f92, 0xa2d2e766, - 0x57b0d256, 0xa2c1adc9, 0x579e81b8, 0xa2b077c5, 0x578c2dba, 0xa29f4559, - 0x5779d65b, 0xa28e1687, - 0x57677b9d, 0xa27ceb4f, 0x57551d80, 0xa26bc3b2, 0x5742bc06, 0xa25a9fb1, - 0x5730572e, 0xa2497f4c, - 0x571deefa, 0xa2386284, 0x570b8369, 0xa2274959, 0x56f9147e, 0xa21633cd, - 0x56e6a239, 0xa20521e0, - 0x56d42c99, 0xa1f41392, 0x56c1b3a1, 0xa1e308e4, 0x56af3750, 0xa1d201d7, - 0x569cb7a8, 0xa1c0fe6c, - 0x568a34a9, 0xa1affea3, 0x5677ae54, 0xa19f027c, 0x566524aa, 0xa18e09fa, - 0x565297ab, 0xa17d151b, - 0x56400758, 0xa16c23e1, 0x562d73b2, 0xa15b364d, 0x561adcb9, 0xa14a4c5e, - 0x5608426e, 0xa1396617, - 0x55f5a4d2, 0xa1288376, 0x55e303e6, 0xa117a47e, 0x55d05faa, 0xa106c92f, - 0x55bdb81f, 0xa0f5f189, - 0x55ab0d46, 0xa0e51d8c, 0x55985f20, 0xa0d44d3b, 0x5585adad, 0xa0c38095, - 0x5572f8ed, 0xa0b2b79b, - 0x556040e2, 0xa0a1f24d, 0x554d858d, 0xa09130ad, 0x553ac6ee, 0xa08072ba, - 0x55280505, 0xa06fb876, - 0x55153fd4, 0xa05f01e1, 0x5502775c, 0xa04e4efc, 0x54efab9c, 0xa03d9fc8, - 0x54dcdc96, 0xa02cf444, - 0x54ca0a4b, 0xa01c4c73, 0x54b734ba, 0xa00ba853, 0x54a45be6, 0x9ffb07e7, - 0x54917fce, 0x9fea6b2f, - 0x547ea073, 0x9fd9d22a, 0x546bbdd7, 0x9fc93cdb, 0x5458d7f9, 0x9fb8ab41, - 0x5445eedb, 0x9fa81d5e, - 0x5433027d, 0x9f979331, 0x542012e1, 0x9f870cbc, 0x540d2005, 0x9f7689ff, - 0x53fa29ed, 0x9f660afb, - 0x53e73097, 0x9f558fb0, 0x53d43406, 0x9f45181f, 0x53c13439, 0x9f34a449, - 0x53ae3131, 0x9f24342f, - 0x539b2af0, 0x9f13c7d0, 0x53882175, 0x9f035f2e, 0x537514c2, 0x9ef2fa49, - 0x536204d7, 0x9ee29922, - 0x534ef1b5, 0x9ed23bb9, 0x533bdb5d, 0x9ec1e210, 0x5328c1d0, 0x9eb18c26, - 0x5315a50e, 0x9ea139fd, - 0x53028518, 0x9e90eb94, 0x52ef61ee, 0x9e80a0ee, 0x52dc3b92, 0x9e705a09, - 0x52c91204, 0x9e6016e8, - 0x52b5e546, 0x9e4fd78a, 0x52a2b556, 0x9e3f9bf0, 0x528f8238, 0x9e2f641b, - 0x527c4bea, 0x9e1f300b, - 0x5269126e, 0x9e0effc1, 0x5255d5c5, 0x9dfed33e, 0x524295f0, 0x9deeaa82, - 0x522f52ee, 0x9dde858e, - 0x521c0cc2, 0x9dce6463, 0x5208c36a, 0x9dbe4701, 0x51f576ea, 0x9dae2d68, - 0x51e22740, 0x9d9e179a, - 0x51ced46e, 0x9d8e0597, 0x51bb7e75, 0x9d7df75f, 0x51a82555, 0x9d6decf4, - 0x5194c910, 0x9d5de656, - 0x518169a5, 0x9d4de385, 0x516e0715, 0x9d3de482, 0x515aa162, 0x9d2de94d, - 0x5147388c, 0x9d1df1e9, - 0x5133cc94, 0x9d0dfe54, 0x51205d7b, 0x9cfe0e8f, 0x510ceb40, 0x9cee229c, - 0x50f975e6, 0x9cde3a7b, - 0x50e5fd6d, 0x9cce562c, 0x50d281d5, 0x9cbe75b0, 0x50bf031f, 0x9cae9907, - 0x50ab814d, 0x9c9ec033, - 0x5097fc5e, 0x9c8eeb34, 0x50847454, 0x9c7f1a0a, 0x5070e92f, 0x9c6f4cb6, - 0x505d5af1, 0x9c5f8339, - 0x5049c999, 0x9c4fbd93, 0x50363529, 0x9c3ffbc5, 0x50229da1, 0x9c303dcf, - 0x500f0302, 0x9c2083b3, - 0x4ffb654d, 0x9c10cd70, 0x4fe7c483, 0x9c011b08, 0x4fd420a4, 0x9bf16c7a, - 0x4fc079b1, 0x9be1c1c8, - 0x4faccfab, 0x9bd21af3, 0x4f992293, 0x9bc277fa, 0x4f857269, 0x9bb2d8de, - 0x4f71bf2e, 0x9ba33da0, - 0x4f5e08e3, 0x9b93a641, 0x4f4a4f89, 0x9b8412c1, 0x4f369320, 0x9b748320, - 0x4f22d3aa, 0x9b64f760, - 0x4f0f1126, 0x9b556f81, 0x4efb4b96, 0x9b45eb83, 0x4ee782fb, 0x9b366b68, - 0x4ed3b755, 0x9b26ef2f, - 0x4ebfe8a5, 0x9b1776da, 0x4eac16eb, 0x9b080268, 0x4e984229, 0x9af891db, - 0x4e846a60, 0x9ae92533, - 0x4e708f8f, 0x9ad9bc71, 0x4e5cb1b9, 0x9aca5795, 0x4e48d0dd, 0x9abaf6a1, - 0x4e34ecfc, 0x9aab9993, - 0x4e210617, 0x9a9c406e, 0x4e0d1c30, 0x9a8ceb31, 0x4df92f46, 0x9a7d99de, - 0x4de53f5a, 0x9a6e4c74, - 0x4dd14c6e, 0x9a5f02f5, 0x4dbd5682, 0x9a4fbd61, 0x4da95d96, 0x9a407bb9, - 0x4d9561ac, 0x9a313dfc, - 0x4d8162c4, 0x9a22042d, 0x4d6d60df, 0x9a12ce4b, 0x4d595bfe, 0x9a039c57, - 0x4d455422, 0x99f46e51, - 0x4d31494b, 0x99e5443b, 0x4d1d3b7a, 0x99d61e14, 0x4d092ab0, 0x99c6fbde, - 0x4cf516ee, 0x99b7dd99, - 0x4ce10034, 0x99a8c345, 0x4ccce684, 0x9999ace3, 0x4cb8c9dd, 0x998a9a74, - 0x4ca4aa41, 0x997b8bf8, - 0x4c9087b1, 0x996c816f, 0x4c7c622d, 0x995d7adc, 0x4c6839b7, 0x994e783d, - 0x4c540e4e, 0x993f7993, - 0x4c3fdff4, 0x99307ee0, 0x4c2baea9, 0x99218824, 0x4c177a6e, 0x9912955f, - 0x4c034345, 0x9903a691, - 0x4bef092d, 0x98f4bbbc, 0x4bdacc28, 0x98e5d4e0, 0x4bc68c36, 0x98d6f1fe, - 0x4bb24958, 0x98c81316, - 0x4b9e0390, 0x98b93828, 0x4b89badd, 0x98aa6136, 0x4b756f40, 0x989b8e40, - 0x4b6120bb, 0x988cbf46, - 0x4b4ccf4d, 0x987df449, 0x4b387af9, 0x986f2d4a, 0x4b2423be, 0x98606a49, - 0x4b0fc99d, 0x9851ab46, - 0x4afb6c98, 0x9842f043, 0x4ae70caf, 0x98343940, 0x4ad2a9e2, 0x9825863d, - 0x4abe4433, 0x9816d73b, - 0x4aa9dba2, 0x98082c3b, 0x4a957030, 0x97f9853d, 0x4a8101de, 0x97eae242, - 0x4a6c90ad, 0x97dc4349, - 0x4a581c9e, 0x97cda855, 0x4a43a5b0, 0x97bf1165, 0x4a2f2be6, 0x97b07e7a, - 0x4a1aaf3f, 0x97a1ef94, - 0x4a062fbd, 0x979364b5, 0x49f1ad61, 0x9784dddc, 0x49dd282a, 0x97765b0a, - 0x49c8a01b, 0x9767dc41, - 0x49b41533, 0x9759617f, 0x499f8774, 0x974aeac6, 0x498af6df, 0x973c7817, - 0x49766373, 0x972e0971, - 0x4961cd33, 0x971f9ed7, 0x494d341e, 0x97113847, 0x49389836, 0x9702d5c3, - 0x4923f97b, 0x96f4774b, - 0x490f57ee, 0x96e61ce0, 0x48fab391, 0x96d7c682, 0x48e60c62, 0x96c97432, - 0x48d16265, 0x96bb25f0, - 0x48bcb599, 0x96acdbbe, 0x48a805ff, 0x969e959b, 0x48935397, 0x96905388, - 0x487e9e64, 0x96821585, - 0x4869e665, 0x9673db94, 0x48552b9b, 0x9665a5b4, 0x48406e08, 0x965773e7, - 0x482badab, 0x9649462d, - 0x4816ea86, 0x963b1c86, 0x48022499, 0x962cf6f2, 0x47ed5be6, 0x961ed574, - 0x47d8906d, 0x9610b80a, - 0x47c3c22f, 0x96029eb6, 0x47aef12c, 0x95f48977, 0x479a1d67, 0x95e67850, - 0x478546de, 0x95d86b3f, - 0x47706d93, 0x95ca6247, 0x475b9188, 0x95bc5d66, 0x4746b2bc, 0x95ae5c9f, - 0x4731d131, 0x95a05ff0, - 0x471cece7, 0x9592675c, 0x470805df, 0x958472e2, 0x46f31c1a, 0x95768283, - 0x46de2f99, 0x9568963f, - 0x46c9405c, 0x955aae17, 0x46b44e65, 0x954cca0c, 0x469f59b4, 0x953eea1e, - 0x468a624a, 0x95310e4e, - 0x46756828, 0x9523369c, 0x46606b4e, 0x95156308, 0x464b6bbe, 0x95079394, - 0x46366978, 0x94f9c83f, - 0x4621647d, 0x94ec010b, 0x460c5cce, 0x94de3df8, 0x45f7526b, 0x94d07f05, - 0x45e24556, 0x94c2c435, - 0x45cd358f, 0x94b50d87, 0x45b82318, 0x94a75afd, 0x45a30df0, 0x9499ac95, - 0x458df619, 0x948c0252, - 0x4578db93, 0x947e5c33, 0x4563be60, 0x9470ba39, 0x454e9e80, 0x94631c65, - 0x45397bf4, 0x945582b7, - 0x452456bd, 0x9447ed2f, 0x450f2edb, 0x943a5bcf, 0x44fa0450, 0x942cce96, - 0x44e4d71c, 0x941f4585, - 0x44cfa740, 0x9411c09e, 0x44ba74bd, 0x94043fdf, 0x44a53f93, 0x93f6c34a, - 0x449007c4, 0x93e94adf, - 0x447acd50, 0x93dbd6a0, 0x44659039, 0x93ce668b, 0x4450507e, 0x93c0faa3, - 0x443b0e21, 0x93b392e6, - 0x4425c923, 0x93a62f57, 0x44108184, 0x9398cff5, 0x43fb3746, 0x938b74c1, - 0x43e5ea68, 0x937e1dbb, - 0x43d09aed, 0x9370cae4, 0x43bb48d4, 0x93637c3d, 0x43a5f41e, 0x935631c5, - 0x43909ccd, 0x9348eb7e, - 0x437b42e1, 0x933ba968, 0x4365e65b, 0x932e6b84, 0x4350873c, 0x932131d1, - 0x433b2585, 0x9313fc51, - 0x4325c135, 0x9306cb04, 0x43105a50, 0x92f99deb, 0x42faf0d4, 0x92ec7505, - 0x42e584c3, 0x92df5054, - 0x42d0161e, 0x92d22fd9, 0x42baa4e6, 0x92c51392, 0x42a5311b, 0x92b7fb82, - 0x428fbabe, 0x92aae7a8, - 0x427a41d0, 0x929dd806, 0x4264c653, 0x9290cc9b, 0x424f4845, 0x9283c568, - 0x4239c7aa, 0x9276c26d, - 0x42244481, 0x9269c3ac, 0x420ebecb, 0x925cc924, 0x41f93689, 0x924fd2d7, - 0x41e3abbc, 0x9242e0c4, - 0x41ce1e65, 0x9235f2ec, 0x41b88e84, 0x9229094f, 0x41a2fc1a, 0x921c23ef, - 0x418d6729, 0x920f42cb, - 0x4177cfb1, 0x920265e4, 0x416235b2, 0x91f58d3b, 0x414c992f, 0x91e8b8d0, - 0x4136fa27, 0x91dbe8a4, - 0x4121589b, 0x91cf1cb6, 0x410bb48c, 0x91c25508, 0x40f60dfb, 0x91b5919a, - 0x40e064ea, 0x91a8d26d, - 0x40cab958, 0x919c1781, 0x40b50b46, 0x918f60d6, 0x409f5ab6, 0x9182ae6d, - 0x4089a7a8, 0x91760047, - 0x4073f21d, 0x91695663, 0x405e3a16, 0x915cb0c3, 0x40487f94, 0x91500f67, - 0x4032c297, 0x91437250, - 0x401d0321, 0x9136d97d, 0x40074132, 0x912a44f0, 0x3ff17cca, 0x911db4a9, - 0x3fdbb5ec, 0x911128a8, - 0x3fc5ec98, 0x9104a0ee, 0x3fb020ce, 0x90f81d7b, 0x3f9a5290, 0x90eb9e50, - 0x3f8481dd, 0x90df236e, - 0x3f6eaeb8, 0x90d2acd4, 0x3f58d921, 0x90c63a83, 0x3f430119, 0x90b9cc7d, - 0x3f2d26a0, 0x90ad62c0, - 0x3f1749b8, 0x90a0fd4e, 0x3f016a61, 0x90949c28, 0x3eeb889c, 0x90883f4d, - 0x3ed5a46b, 0x907be6be, - 0x3ebfbdcd, 0x906f927c, 0x3ea9d4c3, 0x90634287, 0x3e93e950, 0x9056f6df, - 0x3e7dfb73, 0x904aaf86, - 0x3e680b2c, 0x903e6c7b, 0x3e52187f, 0x90322dbf, 0x3e3c2369, 0x9025f352, - 0x3e262bee, 0x9019bd36, - 0x3e10320d, 0x900d8b69, 0x3dfa35c8, 0x90015dee, 0x3de4371f, 0x8ff534c4, - 0x3dce3614, 0x8fe90fec, - 0x3db832a6, 0x8fdcef66, 0x3da22cd7, 0x8fd0d333, 0x3d8c24a8, 0x8fc4bb53, - 0x3d761a19, 0x8fb8a7c7, - 0x3d600d2c, 0x8fac988f, 0x3d49fde1, 0x8fa08dab, 0x3d33ec39, 0x8f94871d, - 0x3d1dd835, 0x8f8884e4, - 0x3d07c1d6, 0x8f7c8701, 0x3cf1a91c, 0x8f708d75, 0x3cdb8e09, 0x8f649840, - 0x3cc5709e, 0x8f58a761, - 0x3caf50da, 0x8f4cbadb, 0x3c992ec0, 0x8f40d2ad, 0x3c830a50, 0x8f34eed8, - 0x3c6ce38a, 0x8f290f5c, - 0x3c56ba70, 0x8f1d343a, 0x3c408f03, 0x8f115d72, 0x3c2a6142, 0x8f058b04, - 0x3c143130, 0x8ef9bcf2, - 0x3bfdfecd, 0x8eedf33b, 0x3be7ca1a, 0x8ee22de0, 0x3bd19318, 0x8ed66ce1, - 0x3bbb59c7, 0x8ecab040, - 0x3ba51e29, 0x8ebef7fb, 0x3b8ee03e, 0x8eb34415, 0x3b78a007, 0x8ea7948c, - 0x3b625d86, 0x8e9be963, - 0x3b4c18ba, 0x8e904298, 0x3b35d1a5, 0x8e84a02d, 0x3b1f8848, 0x8e790222, - 0x3b093ca3, 0x8e6d6877, - 0x3af2eeb7, 0x8e61d32e, 0x3adc9e86, 0x8e564246, 0x3ac64c0f, 0x8e4ab5bf, - 0x3aaff755, 0x8e3f2d9b, - 0x3a99a057, 0x8e33a9da, 0x3a834717, 0x8e282a7b, 0x3a6ceb96, 0x8e1caf80, - 0x3a568dd4, 0x8e1138ea, - 0x3a402dd2, 0x8e05c6b7, 0x3a29cb91, 0x8dfa58ea, 0x3a136712, 0x8deeef82, - 0x39fd0056, 0x8de38a80, - 0x39e6975e, 0x8dd829e4, 0x39d02c2a, 0x8dcccdaf, 0x39b9bebc, 0x8dc175e0, - 0x39a34f13, 0x8db6227a, - 0x398cdd32, 0x8daad37b, 0x39766919, 0x8d9f88e5, 0x395ff2c9, 0x8d9442b8, - 0x39497a43, 0x8d8900f3, - 0x3932ff87, 0x8d7dc399, 0x391c8297, 0x8d728aa9, 0x39060373, 0x8d675623, - 0x38ef821c, 0x8d5c2609, - 0x38d8fe93, 0x8d50fa59, 0x38c278d9, 0x8d45d316, 0x38abf0ef, 0x8d3ab03f, - 0x389566d6, 0x8d2f91d5, - 0x387eda8e, 0x8d2477d8, 0x38684c19, 0x8d196249, 0x3851bb77, 0x8d0e5127, - 0x383b28a9, 0x8d034474, - 0x382493b0, 0x8cf83c30, 0x380dfc8d, 0x8ced385b, 0x37f76341, 0x8ce238f6, - 0x37e0c7cc, 0x8cd73e01, - 0x37ca2a30, 0x8ccc477d, 0x37b38a6d, 0x8cc1556a, 0x379ce885, 0x8cb667c8, - 0x37864477, 0x8cab7e98, - 0x376f9e46, 0x8ca099da, 0x3758f5f2, 0x8c95b98f, 0x37424b7b, 0x8c8addb7, - 0x372b9ee3, 0x8c800652, - 0x3714f02a, 0x8c753362, 0x36fe3f52, 0x8c6a64e5, 0x36e78c5b, 0x8c5f9ade, - 0x36d0d746, 0x8c54d54c, - 0x36ba2014, 0x8c4a142f, 0x36a366c6, 0x8c3f5788, 0x368cab5c, 0x8c349f58, - 0x3675edd9, 0x8c29eb9f, - 0x365f2e3b, 0x8c1f3c5d, 0x36486c86, 0x8c149192, 0x3631a8b8, 0x8c09eb40, - 0x361ae2d3, 0x8bff4966, - 0x36041ad9, 0x8bf4ac05, 0x35ed50c9, 0x8bea131e, 0x35d684a6, 0x8bdf7eb0, - 0x35bfb66e, 0x8bd4eebc, - 0x35a8e625, 0x8bca6343, 0x359213c9, 0x8bbfdc44, 0x357b3f5d, 0x8bb559c1, - 0x356468e2, 0x8baadbba, - 0x354d9057, 0x8ba0622f, 0x3536b5be, 0x8b95ed21, 0x351fd918, 0x8b8b7c8f, - 0x3508fa66, 0x8b81107b, - 0x34f219a8, 0x8b76a8e4, 0x34db36df, 0x8b6c45cc, 0x34c4520d, 0x8b61e733, - 0x34ad6b32, 0x8b578d18, - 0x34968250, 0x8b4d377c, 0x347f9766, 0x8b42e661, 0x3468aa76, 0x8b3899c6, - 0x3451bb81, 0x8b2e51ab, - 0x343aca87, 0x8b240e11, 0x3423d78a, 0x8b19cef8, 0x340ce28b, 0x8b0f9462, - 0x33f5eb89, 0x8b055e4d, - 0x33def287, 0x8afb2cbb, 0x33c7f785, 0x8af0ffac, 0x33b0fa84, 0x8ae6d720, - 0x3399fb85, 0x8adcb318, - 0x3382fa88, 0x8ad29394, 0x336bf78f, 0x8ac87894, 0x3354f29b, 0x8abe6219, - 0x333debab, 0x8ab45024, - 0x3326e2c3, 0x8aaa42b4, 0x330fd7e1, 0x8aa039cb, 0x32f8cb07, 0x8a963567, - 0x32e1bc36, 0x8a8c358b, - 0x32caab6f, 0x8a823a36, 0x32b398b3, 0x8a784368, 0x329c8402, 0x8a6e5123, - 0x32856d5e, 0x8a646365, - 0x326e54c7, 0x8a5a7a31, 0x32573a3f, 0x8a509585, 0x32401dc6, 0x8a46b564, - 0x3228ff5c, 0x8a3cd9cc, - 0x3211df04, 0x8a3302be, 0x31fabcbd, 0x8a29303b, 0x31e39889, 0x8a1f6243, - 0x31cc7269, 0x8a1598d6, - 0x31b54a5e, 0x8a0bd3f5, 0x319e2067, 0x8a0213a0, 0x3186f487, 0x89f857d8, - 0x316fc6be, 0x89eea09d, - 0x3158970e, 0x89e4edef, 0x31416576, 0x89db3fcf, 0x312a31f8, 0x89d1963c, - 0x3112fc95, 0x89c7f138, - 0x30fbc54d, 0x89be50c3, 0x30e48c22, 0x89b4b4dd, 0x30cd5115, 0x89ab1d87, - 0x30b61426, 0x89a18ac0, - 0x309ed556, 0x8997fc8a, 0x308794a6, 0x898e72e4, 0x30705217, 0x8984edcf, - 0x30590dab, 0x897b6d4c, - 0x3041c761, 0x8971f15a, 0x302a7f3a, 0x896879fb, 0x30133539, 0x895f072e, - 0x2ffbe95d, 0x895598f3, - 0x2fe49ba7, 0x894c2f4c, 0x2fcd4c19, 0x8942ca39, 0x2fb5fab2, 0x893969b9, - 0x2f9ea775, 0x89300dce, - 0x2f875262, 0x8926b677, 0x2f6ffb7a, 0x891d63b5, 0x2f58a2be, 0x89141589, - 0x2f41482e, 0x890acbf2, - 0x2f29ebcc, 0x890186f2, 0x2f128d99, 0x88f84687, 0x2efb2d95, 0x88ef0ab4, - 0x2ee3cbc1, 0x88e5d378, - 0x2ecc681e, 0x88dca0d3, 0x2eb502ae, 0x88d372c6, 0x2e9d9b70, 0x88ca4951, - 0x2e863267, 0x88c12475, - 0x2e6ec792, 0x88b80432, 0x2e575af3, 0x88aee888, 0x2e3fec8b, 0x88a5d177, - 0x2e287c5a, 0x889cbf01, - 0x2e110a62, 0x8893b125, 0x2df996a3, 0x888aa7e3, 0x2de2211e, 0x8881a33d, - 0x2dcaa9d5, 0x8878a332, - 0x2db330c7, 0x886fa7c2, 0x2d9bb5f6, 0x8866b0ef, 0x2d843964, 0x885dbeb8, - 0x2d6cbb10, 0x8854d11e, - 0x2d553afc, 0x884be821, 0x2d3db928, 0x884303c1, 0x2d263596, 0x883a23ff, - 0x2d0eb046, 0x883148db, - 0x2cf72939, 0x88287256, 0x2cdfa071, 0x881fa06f, 0x2cc815ee, 0x8816d327, - 0x2cb089b1, 0x880e0a7f, - 0x2c98fbba, 0x88054677, 0x2c816c0c, 0x87fc870f, 0x2c69daa6, 0x87f3cc48, - 0x2c52478a, 0x87eb1621, - 0x2c3ab2b9, 0x87e2649b, 0x2c231c33, 0x87d9b7b7, 0x2c0b83fa, 0x87d10f75, - 0x2bf3ea0d, 0x87c86bd5, - 0x2bdc4e6f, 0x87bfccd7, 0x2bc4b120, 0x87b7327d, 0x2bad1221, 0x87ae9cc5, - 0x2b957173, 0x87a60bb1, - 0x2b7dcf17, 0x879d7f41, 0x2b662b0e, 0x8794f774, 0x2b4e8558, 0x878c744d, - 0x2b36ddf7, 0x8783f5ca, - 0x2b1f34eb, 0x877b7bec, 0x2b078a36, 0x877306b4, 0x2aefddd8, 0x876a9621, - 0x2ad82fd2, 0x87622a35, - 0x2ac08026, 0x8759c2ef, 0x2aa8ced3, 0x87516050, 0x2a911bdc, 0x87490258, - 0x2a796740, 0x8740a907, - 0x2a61b101, 0x8738545e, 0x2a49f920, 0x8730045d, 0x2a323f9e, 0x8727b905, - 0x2a1a847b, 0x871f7255, - 0x2a02c7b8, 0x8717304e, 0x29eb0957, 0x870ef2f1, 0x29d34958, 0x8706ba3d, - 0x29bb87bc, 0x86fe8633, - 0x29a3c485, 0x86f656d3, 0x298bffb2, 0x86ee2c1e, 0x29743946, 0x86e60614, - 0x295c7140, 0x86dde4b5, - 0x2944a7a2, 0x86d5c802, 0x292cdc6d, 0x86cdaffa, 0x29150fa1, 0x86c59c9f, - 0x28fd4140, 0x86bd8df0, - 0x28e5714b, 0x86b583ee, 0x28cd9fc1, 0x86ad7e99, 0x28b5cca5, 0x86a57df2, - 0x289df7f8, 0x869d81f8, - 0x288621b9, 0x86958aac, 0x286e49ea, 0x868d980e, 0x2856708d, 0x8685aa20, - 0x283e95a1, 0x867dc0e0, - 0x2826b928, 0x8675dc4f, 0x280edb23, 0x866dfc6e, 0x27f6fb92, 0x8666213c, - 0x27df1a77, 0x865e4abb, - 0x27c737d3, 0x865678eb, 0x27af53a6, 0x864eabcb, 0x27976df1, 0x8646e35c, - 0x277f86b5, 0x863f1f9e, - 0x27679df4, 0x86376092, 0x274fb3ae, 0x862fa638, 0x2737c7e3, 0x8627f091, - 0x271fda96, 0x86203f9c, - 0x2707ebc7, 0x86189359, 0x26effb76, 0x8610ebca, 0x26d809a5, 0x860948ef, - 0x26c01655, 0x8601aac7, - 0x26a82186, 0x85fa1153, 0x26902b39, 0x85f27c93, 0x26783370, 0x85eaec88, - 0x26603a2c, 0x85e36132, - 0x26483f6c, 0x85dbda91, 0x26304333, 0x85d458a6, 0x26184581, 0x85ccdb70, - 0x26004657, 0x85c562f1, - 0x25e845b6, 0x85bdef28, 0x25d0439f, 0x85b68015, 0x25b84012, 0x85af15b9, - 0x25a03b11, 0x85a7b015, - 0x2588349d, 0x85a04f28, 0x25702cb7, 0x8598f2f3, 0x2558235f, 0x85919b76, - 0x25401896, 0x858a48b1, - 0x25280c5e, 0x8582faa5, 0x250ffeb7, 0x857bb152, 0x24f7efa2, 0x85746cb8, - 0x24dfdf20, 0x856d2cd7, - 0x24c7cd33, 0x8565f1b0, 0x24afb9da, 0x855ebb44, 0x2497a517, 0x85578991, - 0x247f8eec, 0x85505c99, - 0x24677758, 0x8549345c, 0x244f5e5c, 0x854210db, 0x243743fa, 0x853af214, - 0x241f2833, 0x8533d809, - 0x24070b08, 0x852cc2bb, 0x23eeec78, 0x8525b228, 0x23d6cc87, 0x851ea652, - 0x23beab33, 0x85179f39, - 0x23a6887f, 0x85109cdd, 0x238e646a, 0x85099f3e, 0x23763ef7, 0x8502a65c, - 0x235e1826, 0x84fbb239, - 0x2345eff8, 0x84f4c2d4, 0x232dc66d, 0x84edd82d, 0x23159b88, 0x84e6f244, - 0x22fd6f48, 0x84e0111b, - 0x22e541af, 0x84d934b1, 0x22cd12bd, 0x84d25d06, 0x22b4e274, 0x84cb8a1b, - 0x229cb0d5, 0x84c4bbf0, - 0x22847de0, 0x84bdf286, 0x226c4996, 0x84b72ddb, 0x225413f8, 0x84b06df2, - 0x223bdd08, 0x84a9b2ca, - 0x2223a4c5, 0x84a2fc62, 0x220b6b32, 0x849c4abd, 0x21f3304f, 0x84959dd9, - 0x21daf41d, 0x848ef5b7, - 0x21c2b69c, 0x84885258, 0x21aa77cf, 0x8481b3bb, 0x219237b5, 0x847b19e1, - 0x2179f64f, 0x847484ca, - 0x2161b3a0, 0x846df477, 0x21496fa7, 0x846768e7, 0x21312a65, 0x8460e21a, - 0x2118e3dc, 0x845a6012, - 0x21009c0c, 0x8453e2cf, 0x20e852f6, 0x844d6a50, 0x20d0089c, 0x8446f695, - 0x20b7bcfe, 0x844087a0, - 0x209f701c, 0x843a1d70, 0x208721f9, 0x8433b806, 0x206ed295, 0x842d5762, - 0x205681f1, 0x8426fb84, - 0x203e300d, 0x8420a46c, 0x2025dcec, 0x841a521a, 0x200d888d, 0x84140490, - 0x1ff532f2, 0x840dbbcc, - 0x1fdcdc1b, 0x840777d0, 0x1fc4840a, 0x8401389b, 0x1fac2abf, 0x83fafe2e, - 0x1f93d03c, 0x83f4c889, - 0x1f7b7481, 0x83ee97ad, 0x1f63178f, 0x83e86b99, 0x1f4ab968, 0x83e2444d, - 0x1f325a0b, 0x83dc21cb, - 0x1f19f97b, 0x83d60412, 0x1f0197b8, 0x83cfeb22, 0x1ee934c3, 0x83c9d6fc, - 0x1ed0d09d, 0x83c3c7a0, - 0x1eb86b46, 0x83bdbd0e, 0x1ea004c1, 0x83b7b746, 0x1e879d0d, 0x83b1b649, - 0x1e6f342c, 0x83abba17, - 0x1e56ca1e, 0x83a5c2b0, 0x1e3e5ee5, 0x839fd014, 0x1e25f282, 0x8399e244, - 0x1e0d84f5, 0x8393f940, - 0x1df5163f, 0x838e1507, 0x1ddca662, 0x8388359b, 0x1dc4355e, 0x83825afb, - 0x1dabc334, 0x837c8528, - 0x1d934fe5, 0x8376b422, 0x1d7adb73, 0x8370e7e9, 0x1d6265dd, 0x836b207d, - 0x1d49ef26, 0x83655ddf, - 0x1d31774d, 0x835fa00f, 0x1d18fe54, 0x8359e70d, 0x1d00843d, 0x835432d8, - 0x1ce80906, 0x834e8373, - 0x1ccf8cb3, 0x8348d8dc, 0x1cb70f43, 0x83433314, 0x1c9e90b8, 0x833d921b, - 0x1c861113, 0x8337f5f1, - 0x1c6d9053, 0x83325e97, 0x1c550e7c, 0x832ccc0d, 0x1c3c8b8c, 0x83273e52, - 0x1c240786, 0x8321b568, - 0x1c0b826a, 0x831c314e, 0x1bf2fc3a, 0x8316b205, 0x1bda74f6, 0x8311378d, - 0x1bc1ec9e, 0x830bc1e6, - 0x1ba96335, 0x83065110, 0x1b90d8bb, 0x8300e50b, 0x1b784d30, 0x82fb7dd8, - 0x1b5fc097, 0x82f61b77, - 0x1b4732ef, 0x82f0bde8, 0x1b2ea43a, 0x82eb652b, 0x1b161479, 0x82e61141, - 0x1afd83ad, 0x82e0c22a, - 0x1ae4f1d6, 0x82db77e5, 0x1acc5ef6, 0x82d63274, 0x1ab3cb0d, 0x82d0f1d5, - 0x1a9b361d, 0x82cbb60b, - 0x1a82a026, 0x82c67f14, 0x1a6a0929, 0x82c14cf1, 0x1a517128, 0x82bc1fa2, - 0x1a38d823, 0x82b6f727, - 0x1a203e1b, 0x82b1d381, 0x1a07a311, 0x82acb4b0, 0x19ef0707, 0x82a79ab3, - 0x19d669fc, 0x82a2858c, - 0x19bdcbf3, 0x829d753a, 0x19a52ceb, 0x829869be, 0x198c8ce7, 0x82936317, - 0x1973ebe6, 0x828e6146, - 0x195b49ea, 0x8289644b, 0x1942a6f3, 0x82846c26, 0x192a0304, 0x827f78d8, - 0x19115e1c, 0x827a8a61, - 0x18f8b83c, 0x8275a0c0, 0x18e01167, 0x8270bbf7, 0x18c7699b, 0x826bdc04, - 0x18aec0db, 0x826700e9, - 0x18961728, 0x82622aa6, 0x187d6c82, 0x825d593a, 0x1864c0ea, 0x82588ca7, - 0x184c1461, 0x8253c4eb, - 0x183366e9, 0x824f0208, 0x181ab881, 0x824a43fe, 0x1802092c, 0x82458acc, - 0x17e958ea, 0x8240d673, - 0x17d0a7bc, 0x823c26f3, 0x17b7f5a3, 0x82377c4c, 0x179f429f, 0x8232d67f, - 0x17868eb3, 0x822e358b, - 0x176dd9de, 0x82299971, 0x17552422, 0x82250232, 0x173c6d80, 0x82206fcc, - 0x1723b5f9, 0x821be240, - 0x170afd8d, 0x82175990, 0x16f2443e, 0x8212d5b9, 0x16d98a0c, 0x820e56be, - 0x16c0cef9, 0x8209dc9e, - 0x16a81305, 0x82056758, 0x168f5632, 0x8200f6ef, 0x1676987f, 0x81fc8b60, - 0x165dd9f0, 0x81f824ae, - 0x16451a83, 0x81f3c2d7, 0x162c5a3b, 0x81ef65dc, 0x16139918, 0x81eb0dbe, - 0x15fad71b, 0x81e6ba7c, - 0x15e21445, 0x81e26c16, 0x15c95097, 0x81de228d, 0x15b08c12, 0x81d9dde1, - 0x1597c6b7, 0x81d59e13, - 0x157f0086, 0x81d16321, 0x15663982, 0x81cd2d0c, 0x154d71aa, 0x81c8fbd6, - 0x1534a901, 0x81c4cf7d, - 0x151bdf86, 0x81c0a801, 0x1503153a, 0x81bc8564, 0x14ea4a1f, 0x81b867a5, - 0x14d17e36, 0x81b44ec4, - 0x14b8b17f, 0x81b03ac2, 0x149fe3fc, 0x81ac2b9e, 0x148715ae, 0x81a82159, - 0x146e4694, 0x81a41bf4, - 0x145576b1, 0x81a01b6d, 0x143ca605, 0x819c1fc5, 0x1423d492, 0x819828fd, - 0x140b0258, 0x81943715, - 0x13f22f58, 0x81904a0c, 0x13d95b93, 0x818c61e3, 0x13c0870a, 0x81887e9a, - 0x13a7b1bf, 0x8184a032, - 0x138edbb1, 0x8180c6a9, 0x137604e2, 0x817cf201, 0x135d2d53, 0x8179223a, - 0x13445505, 0x81755754, - 0x132b7bf9, 0x8171914e, 0x1312a230, 0x816dd02a, 0x12f9c7aa, 0x816a13e6, - 0x12e0ec6a, 0x81665c84, - 0x12c8106f, 0x8162aa04, 0x12af33ba, 0x815efc65, 0x1296564d, 0x815b53a8, - 0x127d7829, 0x8157afcd, - 0x1264994e, 0x815410d4, 0x124bb9be, 0x815076bd, 0x1232d979, 0x814ce188, - 0x1219f880, 0x81495136, - 0x120116d5, 0x8145c5c7, 0x11e83478, 0x81423f3a, 0x11cf516a, 0x813ebd90, - 0x11b66dad, 0x813b40ca, - 0x119d8941, 0x8137c8e6, 0x1184a427, 0x813455e6, 0x116bbe60, 0x8130e7c9, - 0x1152d7ed, 0x812d7e8f, - 0x1139f0cf, 0x812a1a3a, 0x11210907, 0x8126bac8, 0x11082096, 0x8123603a, - 0x10ef377d, 0x81200a90, - 0x10d64dbd, 0x811cb9ca, 0x10bd6356, 0x81196de9, 0x10a4784b, 0x811626ec, - 0x108b8c9b, 0x8112e4d4, - 0x1072a048, 0x810fa7a0, 0x1059b352, 0x810c6f52, 0x1040c5bb, 0x81093be8, - 0x1027d784, 0x81060d63, - 0x100ee8ad, 0x8102e3c4, 0xff5f938, 0x80ffbf0a, 0xfdd0926, 0x80fc9f35, - 0xfc41876, 0x80f98446, - 0xfab272b, 0x80f66e3c, 0xf923546, 0x80f35d19, 0xf7942c7, 0x80f050db, - 0xf604faf, 0x80ed4984, - 0xf475bff, 0x80ea4712, 0xf2e67b8, 0x80e74987, 0xf1572dc, 0x80e450e2, - 0xefc7d6b, 0x80e15d24, - 0xee38766, 0x80de6e4c, 0xeca90ce, 0x80db845b, 0xeb199a4, 0x80d89f51, - 0xe98a1e9, 0x80d5bf2e, - 0xe7fa99e, 0x80d2e3f2, 0xe66b0c3, 0x80d00d9d, 0xe4db75b, 0x80cd3c2f, - 0xe34bd66, 0x80ca6fa9, - 0xe1bc2e4, 0x80c7a80a, 0xe02c7d7, 0x80c4e553, 0xde9cc40, 0x80c22784, - 0xdd0d01f, 0x80bf6e9c, - 0xdb7d376, 0x80bcba9d, 0xd9ed646, 0x80ba0b85, 0xd85d88f, 0x80b76156, - 0xd6cda53, 0x80b4bc0e, - 0xd53db92, 0x80b21baf, 0xd3adc4e, 0x80af8039, 0xd21dc87, 0x80ace9ab, - 0xd08dc3f, 0x80aa5806, - 0xcefdb76, 0x80a7cb49, 0xcd6da2d, 0x80a54376, 0xcbdd865, 0x80a2c08b, - 0xca4d620, 0x80a04289, - 0xc8bd35e, 0x809dc971, 0xc72d020, 0x809b5541, 0xc59cc68, 0x8098e5fb, - 0xc40c835, 0x80967b9f, - 0xc27c389, 0x8094162c, 0xc0ebe66, 0x8091b5a2, 0xbf5b8cb, 0x808f5a02, - 0xbdcb2bb, 0x808d034c, - 0xbc3ac35, 0x808ab180, 0xbaaa53b, 0x8088649e, 0xb919dcf, 0x80861ca6, - 0xb7895f0, 0x8083d998, - 0xb5f8d9f, 0x80819b74, 0xb4684df, 0x807f623b, 0xb2d7baf, 0x807d2dec, - 0xb147211, 0x807afe87, - 0xafb6805, 0x8078d40d, 0xae25d8d, 0x8076ae7e, 0xac952aa, 0x80748dd9, - 0xab0475c, 0x8072721f, - 0xa973ba5, 0x80705b50, 0xa7e2f85, 0x806e496c, 0xa6522fe, 0x806c3c74, - 0xa4c1610, 0x806a3466, - 0xa3308bd, 0x80683143, 0xa19fb04, 0x8066330c, 0xa00ece8, 0x806439c0, - 0x9e7de6a, 0x80624560, - 0x9cecf89, 0x806055eb, 0x9b5c048, 0x805e6b62, 0x99cb0a7, 0x805c85c4, - 0x983a0a7, 0x805aa512, - 0x96a9049, 0x8058c94c, 0x9517f8f, 0x8056f272, 0x9386e78, 0x80552084, - 0x91f5d06, 0x80535381, - 0x9064b3a, 0x80518b6b, 0x8ed3916, 0x804fc841, 0x8d42699, 0x804e0a04, - 0x8bb13c5, 0x804c50b2, - 0x8a2009a, 0x804a9c4d, 0x888ed1b, 0x8048ecd5, 0x86fd947, 0x80474248, - 0x856c520, 0x80459ca9, - 0x83db0a7, 0x8043fbf6, 0x8249bdd, 0x80426030, 0x80b86c2, 0x8040c956, - 0x7f27157, 0x803f376a, - 0x7d95b9e, 0x803daa6a, 0x7c04598, 0x803c2257, 0x7a72f45, 0x803a9f31, - 0x78e18a7, 0x803920f8, - 0x77501be, 0x8037a7ac, 0x75bea8c, 0x8036334e, 0x742d311, 0x8034c3dd, - 0x729bb4e, 0x80335959, - 0x710a345, 0x8031f3c2, 0x6f78af6, 0x80309318, 0x6de7262, 0x802f375d, - 0x6c5598a, 0x802de08e, - 0x6ac406f, 0x802c8ead, 0x6932713, 0x802b41ba, 0x67a0d76, 0x8029f9b4, - 0x660f398, 0x8028b69c, - 0x647d97c, 0x80277872, 0x62ebf22, 0x80263f36, 0x615a48b, 0x80250ae7, - 0x5fc89b8, 0x8023db86, - 0x5e36ea9, 0x8022b114, 0x5ca5361, 0x80218b8f, 0x5b137df, 0x80206af8, - 0x5981c26, 0x801f4f4f, - 0x57f0035, 0x801e3895, 0x565e40d, 0x801d26c8, 0x54cc7b1, 0x801c19ea, - 0x533ab20, 0x801b11fa, - 0x51a8e5c, 0x801a0ef8, 0x5017165, 0x801910e4, 0x4e8543e, 0x801817bf, - 0x4cf36e5, 0x80172388, - 0x4b6195d, 0x80163440, 0x49cfba7, 0x801549e6, 0x483ddc3, 0x8014647b, - 0x46abfb3, 0x801383fe, - 0x451a177, 0x8012a86f, 0x4388310, 0x8011d1d0, 0x41f6480, 0x8011001f, - 0x40645c7, 0x8010335c, - 0x3ed26e6, 0x800f6b88, 0x3d407df, 0x800ea8a3, 0x3bae8b2, 0x800deaad, - 0x3a1c960, 0x800d31a5, - 0x388a9ea, 0x800c7d8c, 0x36f8a51, 0x800bce63, 0x3566a96, 0x800b2427, - 0x33d4abb, 0x800a7edb, - 0x3242abf, 0x8009de7e, 0x30b0aa4, 0x80094310, 0x2f1ea6c, 0x8008ac90, - 0x2d8ca16, 0x80081b00, - 0x2bfa9a4, 0x80078e5e, 0x2a68917, 0x800706ac, 0x28d6870, 0x800683e8, - 0x27447b0, 0x80060614, - 0x25b26d7, 0x80058d2f, 0x24205e8, 0x80051939, 0x228e4e2, 0x8004aa32, - 0x20fc3c6, 0x8004401a, - 0x1f6a297, 0x8003daf1, 0x1dd8154, 0x80037ab7, 0x1c45ffe, 0x80031f6d, - 0x1ab3e97, 0x8002c912, - 0x1921d20, 0x800277a6, 0x178fb99, 0x80022b29, 0x15fda03, 0x8001e39b, - 0x146b860, 0x8001a0fd, - 0x12d96b1, 0x8001634e, 0x11474f6, 0x80012a8e, 0xfb5330, 0x8000f6bd, - 0xe23160, 0x8000c7dc, - 0xc90f88, 0x80009dea, 0xafeda8, 0x800078e7, 0x96cbc1, 0x800058d4, 0x7da9d4, - 0x80003daf, - 0x6487e3, 0x8000277a, 0x4b65ee, 0x80001635, 0x3243f5, 0x800009df, 0x1921fb, - 0x80000278, -}; - -static const q31_t WeightsQ31_8192[16384] = { - 0x7fffffff, 0x0, 0x7fffffd9, 0xfff9b781, 0x7fffff62, 0xfff36f02, 0x7ffffe9d, - 0xffed2684, - 0x7ffffd88, 0xffe6de05, 0x7ffffc25, 0xffe09586, 0x7ffffa73, 0xffda4d08, - 0x7ffff872, 0xffd40489, - 0x7ffff621, 0xffcdbc0b, 0x7ffff382, 0xffc7738c, 0x7ffff094, 0xffc12b0e, - 0x7fffed57, 0xffbae290, - 0x7fffe9cb, 0xffb49a12, 0x7fffe5f0, 0xffae5195, 0x7fffe1c6, 0xffa80917, - 0x7fffdd4d, 0xffa1c09a, - 0x7fffd886, 0xff9b781d, 0x7fffd36f, 0xff952fa0, 0x7fffce09, 0xff8ee724, - 0x7fffc854, 0xff889ea7, - 0x7fffc251, 0xff82562c, 0x7fffbbfe, 0xff7c0db0, 0x7fffb55c, 0xff75c535, - 0x7fffae6c, 0xff6f7cba, - 0x7fffa72c, 0xff69343f, 0x7fff9f9e, 0xff62ebc5, 0x7fff97c1, 0xff5ca34b, - 0x7fff8f94, 0xff565ad1, - 0x7fff8719, 0xff501258, 0x7fff7e4f, 0xff49c9df, 0x7fff7536, 0xff438167, - 0x7fff6bcd, 0xff3d38ef, - 0x7fff6216, 0xff36f078, 0x7fff5810, 0xff30a801, 0x7fff4dbb, 0xff2a5f8b, - 0x7fff4317, 0xff241715, - 0x7fff3824, 0xff1dcea0, 0x7fff2ce2, 0xff17862b, 0x7fff2151, 0xff113db7, - 0x7fff1572, 0xff0af543, - 0x7fff0943, 0xff04acd0, 0x7ffefcc5, 0xfefe645e, 0x7ffeeff8, 0xfef81bec, - 0x7ffee2dd, 0xfef1d37b, - 0x7ffed572, 0xfeeb8b0a, 0x7ffec7b9, 0xfee5429a, 0x7ffeb9b0, 0xfedefa2b, - 0x7ffeab59, 0xfed8b1bd, - 0x7ffe9cb2, 0xfed2694f, 0x7ffe8dbd, 0xfecc20e2, 0x7ffe7e79, 0xfec5d876, - 0x7ffe6ee5, 0xfebf900a, - 0x7ffe5f03, 0xfeb947a0, 0x7ffe4ed2, 0xfeb2ff36, 0x7ffe3e52, 0xfeacb6cc, - 0x7ffe2d83, 0xfea66e64, - 0x7ffe1c65, 0xfea025fd, 0x7ffe0af8, 0xfe99dd96, 0x7ffdf93c, 0xfe939530, - 0x7ffde731, 0xfe8d4ccb, - 0x7ffdd4d7, 0xfe870467, 0x7ffdc22e, 0xfe80bc04, 0x7ffdaf37, 0xfe7a73a2, - 0x7ffd9bf0, 0xfe742b41, - 0x7ffd885a, 0xfe6de2e0, 0x7ffd7476, 0xfe679a81, 0x7ffd6042, 0xfe615223, - 0x7ffd4bc0, 0xfe5b09c5, - 0x7ffd36ee, 0xfe54c169, 0x7ffd21ce, 0xfe4e790d, 0x7ffd0c5f, 0xfe4830b3, - 0x7ffcf6a0, 0xfe41e85a, - 0x7ffce093, 0xfe3ba002, 0x7ffcca37, 0xfe3557ab, 0x7ffcb38c, 0xfe2f0f55, - 0x7ffc9c92, 0xfe28c700, - 0x7ffc8549, 0xfe227eac, 0x7ffc6db1, 0xfe1c365a, 0x7ffc55ca, 0xfe15ee09, - 0x7ffc3d94, 0xfe0fa5b8, - 0x7ffc250f, 0xfe095d69, 0x7ffc0c3b, 0xfe03151c, 0x7ffbf319, 0xfdfccccf, - 0x7ffbd9a7, 0xfdf68484, - 0x7ffbbfe6, 0xfdf03c3a, 0x7ffba5d7, 0xfde9f3f1, 0x7ffb8b78, 0xfde3aba9, - 0x7ffb70cb, 0xfddd6363, - 0x7ffb55ce, 0xfdd71b1e, 0x7ffb3a83, 0xfdd0d2db, 0x7ffb1ee9, 0xfdca8a99, - 0x7ffb0300, 0xfdc44258, - 0x7ffae6c7, 0xfdbdfa18, 0x7ffaca40, 0xfdb7b1da, 0x7ffaad6a, 0xfdb1699e, - 0x7ffa9045, 0xfdab2162, - 0x7ffa72d1, 0xfda4d929, 0x7ffa550e, 0xfd9e90f0, 0x7ffa36fc, 0xfd9848b9, - 0x7ffa189c, 0xfd920084, - 0x7ff9f9ec, 0xfd8bb850, 0x7ff9daed, 0xfd85701e, 0x7ff9bba0, 0xfd7f27ed, - 0x7ff99c03, 0xfd78dfbd, - 0x7ff97c18, 0xfd729790, 0x7ff95bdd, 0xfd6c4f64, 0x7ff93b54, 0xfd660739, - 0x7ff91a7b, 0xfd5fbf10, - 0x7ff8f954, 0xfd5976e9, 0x7ff8d7de, 0xfd532ec3, 0x7ff8b619, 0xfd4ce69f, - 0x7ff89405, 0xfd469e7c, - 0x7ff871a2, 0xfd40565c, 0x7ff84ef0, 0xfd3a0e3d, 0x7ff82bef, 0xfd33c61f, - 0x7ff8089f, 0xfd2d7e04, - 0x7ff7e500, 0xfd2735ea, 0x7ff7c113, 0xfd20edd2, 0x7ff79cd6, 0xfd1aa5bc, - 0x7ff7784a, 0xfd145da7, - 0x7ff75370, 0xfd0e1594, 0x7ff72e46, 0xfd07cd83, 0x7ff708ce, 0xfd018574, - 0x7ff6e307, 0xfcfb3d67, - 0x7ff6bcf0, 0xfcf4f55c, 0x7ff6968b, 0xfceead52, 0x7ff66fd7, 0xfce8654b, - 0x7ff648d4, 0xfce21d45, - 0x7ff62182, 0xfcdbd541, 0x7ff5f9e1, 0xfcd58d3f, 0x7ff5d1f1, 0xfccf453f, - 0x7ff5a9b2, 0xfcc8fd41, - 0x7ff58125, 0xfcc2b545, 0x7ff55848, 0xfcbc6d4c, 0x7ff52f1d, 0xfcb62554, - 0x7ff505a2, 0xfcafdd5e, - 0x7ff4dbd9, 0xfca9956a, 0x7ff4b1c0, 0xfca34d78, 0x7ff48759, 0xfc9d0588, - 0x7ff45ca3, 0xfc96bd9b, - 0x7ff4319d, 0xfc9075af, 0x7ff40649, 0xfc8a2dc6, 0x7ff3daa6, 0xfc83e5de, - 0x7ff3aeb4, 0xfc7d9df9, - 0x7ff38274, 0xfc775616, 0x7ff355e4, 0xfc710e36, 0x7ff32905, 0xfc6ac657, - 0x7ff2fbd7, 0xfc647e7b, - 0x7ff2ce5b, 0xfc5e36a0, 0x7ff2a08f, 0xfc57eec9, 0x7ff27275, 0xfc51a6f3, - 0x7ff2440b, 0xfc4b5f20, - 0x7ff21553, 0xfc45174e, 0x7ff1e64c, 0xfc3ecf80, 0x7ff1b6f6, 0xfc3887b3, - 0x7ff18751, 0xfc323fe9, - 0x7ff1575d, 0xfc2bf821, 0x7ff1271a, 0xfc25b05c, 0x7ff0f688, 0xfc1f6899, - 0x7ff0c5a7, 0xfc1920d8, - 0x7ff09478, 0xfc12d91a, 0x7ff062f9, 0xfc0c915e, 0x7ff0312c, 0xfc0649a5, - 0x7fefff0f, 0xfc0001ee, - 0x7fefcca4, 0xfbf9ba39, 0x7fef99ea, 0xfbf37287, 0x7fef66e1, 0xfbed2ad8, - 0x7fef3388, 0xfbe6e32b, - 0x7feeffe1, 0xfbe09b80, 0x7feecbec, 0xfbda53d8, 0x7fee97a7, 0xfbd40c33, - 0x7fee6313, 0xfbcdc490, - 0x7fee2e30, 0xfbc77cf0, 0x7fedf8ff, 0xfbc13552, 0x7fedc37e, 0xfbbaedb7, - 0x7fed8daf, 0xfbb4a61f, - 0x7fed5791, 0xfbae5e89, 0x7fed2123, 0xfba816f6, 0x7fecea67, 0xfba1cf66, - 0x7fecb35c, 0xfb9b87d8, - 0x7fec7c02, 0xfb95404d, 0x7fec4459, 0xfb8ef8c5, 0x7fec0c62, 0xfb88b13f, - 0x7febd41b, 0xfb8269bd, - 0x7feb9b85, 0xfb7c223d, 0x7feb62a1, 0xfb75dac0, 0x7feb296d, 0xfb6f9345, - 0x7feaefeb, 0xfb694bce, - 0x7feab61a, 0xfb630459, 0x7fea7bfa, 0xfb5cbce7, 0x7fea418b, 0xfb567578, - 0x7fea06cd, 0xfb502e0c, - 0x7fe9cbc0, 0xfb49e6a3, 0x7fe99064, 0xfb439f3c, 0x7fe954ba, 0xfb3d57d9, - 0x7fe918c0, 0xfb371078, - 0x7fe8dc78, 0xfb30c91b, 0x7fe89fe0, 0xfb2a81c0, 0x7fe862fa, 0xfb243a69, - 0x7fe825c5, 0xfb1df314, - 0x7fe7e841, 0xfb17abc2, 0x7fe7aa6e, 0xfb116474, 0x7fe76c4c, 0xfb0b1d28, - 0x7fe72ddb, 0xfb04d5e0, - 0x7fe6ef1c, 0xfafe8e9b, 0x7fe6b00d, 0xfaf84758, 0x7fe670b0, 0xfaf20019, - 0x7fe63103, 0xfaebb8dd, - 0x7fe5f108, 0xfae571a4, 0x7fe5b0be, 0xfadf2a6e, 0x7fe57025, 0xfad8e33c, - 0x7fe52f3d, 0xfad29c0c, - 0x7fe4ee06, 0xfacc54e0, 0x7fe4ac81, 0xfac60db7, 0x7fe46aac, 0xfabfc691, - 0x7fe42889, 0xfab97f6e, - 0x7fe3e616, 0xfab3384f, 0x7fe3a355, 0xfaacf133, 0x7fe36045, 0xfaa6aa1a, - 0x7fe31ce6, 0xfaa06305, - 0x7fe2d938, 0xfa9a1bf3, 0x7fe2953b, 0xfa93d4e4, 0x7fe250ef, 0xfa8d8dd8, - 0x7fe20c55, 0xfa8746d0, - 0x7fe1c76b, 0xfa80ffcb, 0x7fe18233, 0xfa7ab8ca, 0x7fe13cac, 0xfa7471cc, - 0x7fe0f6d6, 0xfa6e2ad1, - 0x7fe0b0b1, 0xfa67e3da, 0x7fe06a3d, 0xfa619ce7, 0x7fe0237a, 0xfa5b55f7, - 0x7fdfdc69, 0xfa550f0a, - 0x7fdf9508, 0xfa4ec821, 0x7fdf4d59, 0xfa48813b, 0x7fdf055a, 0xfa423a59, - 0x7fdebd0d, 0xfa3bf37a, - 0x7fde7471, 0xfa35ac9f, 0x7fde2b86, 0xfa2f65c8, 0x7fdde24d, 0xfa291ef4, - 0x7fdd98c4, 0xfa22d823, - 0x7fdd4eec, 0xfa1c9157, 0x7fdd04c6, 0xfa164a8e, 0x7fdcba51, 0xfa1003c8, - 0x7fdc6f8d, 0xfa09bd06, - 0x7fdc247a, 0xfa037648, 0x7fdbd918, 0xf9fd2f8e, 0x7fdb8d67, 0xf9f6e8d7, - 0x7fdb4167, 0xf9f0a224, - 0x7fdaf519, 0xf9ea5b75, 0x7fdaa87c, 0xf9e414ca, 0x7fda5b8f, 0xf9ddce22, - 0x7fda0e54, 0xf9d7877e, - 0x7fd9c0ca, 0xf9d140de, 0x7fd972f2, 0xf9cafa42, 0x7fd924ca, 0xf9c4b3a9, - 0x7fd8d653, 0xf9be6d15, - 0x7fd8878e, 0xf9b82684, 0x7fd8387a, 0xf9b1dff7, 0x7fd7e917, 0xf9ab996e, - 0x7fd79965, 0xf9a552e9, - 0x7fd74964, 0xf99f0c68, 0x7fd6f914, 0xf998c5ea, 0x7fd6a875, 0xf9927f71, - 0x7fd65788, 0xf98c38fc, - 0x7fd6064c, 0xf985f28a, 0x7fd5b4c1, 0xf97fac1d, 0x7fd562e7, 0xf97965b4, - 0x7fd510be, 0xf9731f4e, - 0x7fd4be46, 0xf96cd8ed, 0x7fd46b80, 0xf9669290, 0x7fd4186a, 0xf9604c37, - 0x7fd3c506, 0xf95a05e2, - 0x7fd37153, 0xf953bf91, 0x7fd31d51, 0xf94d7944, 0x7fd2c900, 0xf94732fb, - 0x7fd27460, 0xf940ecb7, - 0x7fd21f72, 0xf93aa676, 0x7fd1ca35, 0xf934603a, 0x7fd174a8, 0xf92e1a02, - 0x7fd11ecd, 0xf927d3ce, - 0x7fd0c8a3, 0xf9218d9e, 0x7fd0722b, 0xf91b4773, 0x7fd01b63, 0xf915014c, - 0x7fcfc44d, 0xf90ebb29, - 0x7fcf6ce8, 0xf908750a, 0x7fcf1533, 0xf9022ef0, 0x7fcebd31, 0xf8fbe8da, - 0x7fce64df, 0xf8f5a2c9, - 0x7fce0c3e, 0xf8ef5cbb, 0x7fcdb34f, 0xf8e916b2, 0x7fcd5a11, 0xf8e2d0ae, - 0x7fcd0083, 0xf8dc8aae, - 0x7fcca6a7, 0xf8d644b2, 0x7fcc4c7d, 0xf8cffebb, 0x7fcbf203, 0xf8c9b8c8, - 0x7fcb973b, 0xf8c372d9, - 0x7fcb3c23, 0xf8bd2cef, 0x7fcae0bd, 0xf8b6e70a, 0x7fca8508, 0xf8b0a129, - 0x7fca2905, 0xf8aa5b4c, - 0x7fc9ccb2, 0xf8a41574, 0x7fc97011, 0xf89dcfa1, 0x7fc91320, 0xf89789d2, - 0x7fc8b5e1, 0xf8914407, - 0x7fc85854, 0xf88afe42, 0x7fc7fa77, 0xf884b880, 0x7fc79c4b, 0xf87e72c4, - 0x7fc73dd1, 0xf8782d0c, - 0x7fc6df08, 0xf871e759, 0x7fc67ff0, 0xf86ba1aa, 0x7fc62089, 0xf8655c00, - 0x7fc5c0d3, 0xf85f165b, - 0x7fc560cf, 0xf858d0bb, 0x7fc5007c, 0xf8528b1f, 0x7fc49fda, 0xf84c4588, - 0x7fc43ee9, 0xf845fff5, - 0x7fc3dda9, 0xf83fba68, 0x7fc37c1b, 0xf83974df, 0x7fc31a3d, 0xf8332f5b, - 0x7fc2b811, 0xf82ce9dc, - 0x7fc25596, 0xf826a462, 0x7fc1f2cc, 0xf8205eec, 0x7fc18fb4, 0xf81a197b, - 0x7fc12c4d, 0xf813d410, - 0x7fc0c896, 0xf80d8ea9, 0x7fc06491, 0xf8074947, 0x7fc0003e, 0xf80103ea, - 0x7fbf9b9b, 0xf7fabe92, - 0x7fbf36aa, 0xf7f4793e, 0x7fbed16a, 0xf7ee33f0, 0x7fbe6bdb, 0xf7e7eea7, - 0x7fbe05fd, 0xf7e1a963, - 0x7fbd9fd0, 0xf7db6423, 0x7fbd3955, 0xf7d51ee9, 0x7fbcd28b, 0xf7ced9b4, - 0x7fbc6b72, 0xf7c89484, - 0x7fbc040a, 0xf7c24f59, 0x7fbb9c53, 0xf7bc0a33, 0x7fbb344e, 0xf7b5c512, - 0x7fbacbfa, 0xf7af7ff6, - 0x7fba6357, 0xf7a93ae0, 0x7fb9fa65, 0xf7a2f5ce, 0x7fb99125, 0xf79cb0c2, - 0x7fb92796, 0xf7966bbb, - 0x7fb8bdb8, 0xf79026b9, 0x7fb8538b, 0xf789e1bc, 0x7fb7e90f, 0xf7839cc4, - 0x7fb77e45, 0xf77d57d2, - 0x7fb7132b, 0xf77712e5, 0x7fb6a7c3, 0xf770cdfd, 0x7fb63c0d, 0xf76a891b, - 0x7fb5d007, 0xf764443d, - 0x7fb563b3, 0xf75dff66, 0x7fb4f710, 0xf757ba93, 0x7fb48a1e, 0xf75175c6, - 0x7fb41cdd, 0xf74b30fe, - 0x7fb3af4e, 0xf744ec3b, 0x7fb34170, 0xf73ea77e, 0x7fb2d343, 0xf73862c6, - 0x7fb264c7, 0xf7321e14, - 0x7fb1f5fc, 0xf72bd967, 0x7fb186e3, 0xf72594c0, 0x7fb1177b, 0xf71f501e, - 0x7fb0a7c4, 0xf7190b81, - 0x7fb037bf, 0xf712c6ea, 0x7fafc76a, 0xf70c8259, 0x7faf56c7, 0xf7063dcd, - 0x7faee5d5, 0xf6fff946, - 0x7fae7495, 0xf6f9b4c6, 0x7fae0305, 0xf6f3704a, 0x7fad9127, 0xf6ed2bd4, - 0x7fad1efa, 0xf6e6e764, - 0x7facac7f, 0xf6e0a2fa, 0x7fac39b4, 0xf6da5e95, 0x7fabc69b, 0xf6d41a36, - 0x7fab5333, 0xf6cdd5dc, - 0x7faadf7c, 0xf6c79188, 0x7faa6b77, 0xf6c14d3a, 0x7fa9f723, 0xf6bb08f1, - 0x7fa98280, 0xf6b4c4ae, - 0x7fa90d8e, 0xf6ae8071, 0x7fa8984e, 0xf6a83c3a, 0x7fa822bf, 0xf6a1f808, - 0x7fa7ace1, 0xf69bb3dd, - 0x7fa736b4, 0xf6956fb7, 0x7fa6c039, 0xf68f2b96, 0x7fa6496e, 0xf688e77c, - 0x7fa5d256, 0xf682a367, - 0x7fa55aee, 0xf67c5f59, 0x7fa4e338, 0xf6761b50, 0x7fa46b32, 0xf66fd74d, - 0x7fa3f2df, 0xf6699350, - 0x7fa37a3c, 0xf6634f59, 0x7fa3014b, 0xf65d0b68, 0x7fa2880b, 0xf656c77c, - 0x7fa20e7c, 0xf6508397, - 0x7fa1949e, 0xf64a3fb8, 0x7fa11a72, 0xf643fbdf, 0x7fa09ff7, 0xf63db80b, - 0x7fa0252e, 0xf637743e, - 0x7f9faa15, 0xf6313077, 0x7f9f2eae, 0xf62aecb5, 0x7f9eb2f8, 0xf624a8fa, - 0x7f9e36f4, 0xf61e6545, - 0x7f9dbaa0, 0xf6182196, 0x7f9d3dfe, 0xf611dded, 0x7f9cc10d, 0xf60b9a4b, - 0x7f9c43ce, 0xf60556ae, - 0x7f9bc640, 0xf5ff1318, 0x7f9b4863, 0xf5f8cf87, 0x7f9aca37, 0xf5f28bfd, - 0x7f9a4bbd, 0xf5ec4879, - 0x7f99ccf4, 0xf5e604fc, 0x7f994ddc, 0xf5dfc184, 0x7f98ce76, 0xf5d97e13, - 0x7f984ec1, 0xf5d33aa8, - 0x7f97cebd, 0xf5ccf743, 0x7f974e6a, 0xf5c6b3e5, 0x7f96cdc9, 0xf5c0708d, - 0x7f964cd9, 0xf5ba2d3b, - 0x7f95cb9a, 0xf5b3e9f0, 0x7f954a0d, 0xf5ada6ab, 0x7f94c831, 0xf5a7636c, - 0x7f944606, 0xf5a12034, - 0x7f93c38c, 0xf59add02, 0x7f9340c4, 0xf59499d6, 0x7f92bdad, 0xf58e56b1, - 0x7f923a48, 0xf5881393, - 0x7f91b694, 0xf581d07b, 0x7f913291, 0xf57b8d69, 0x7f90ae3f, 0xf5754a5e, - 0x7f90299f, 0xf56f0759, - 0x7f8fa4b0, 0xf568c45b, 0x7f8f1f72, 0xf5628163, 0x7f8e99e6, 0xf55c3e72, - 0x7f8e140a, 0xf555fb88, - 0x7f8d8de1, 0xf54fb8a4, 0x7f8d0768, 0xf54975c6, 0x7f8c80a1, 0xf54332ef, - 0x7f8bf98b, 0xf53cf01f, - 0x7f8b7227, 0xf536ad56, 0x7f8aea74, 0xf5306a93, 0x7f8a6272, 0xf52a27d7, - 0x7f89da21, 0xf523e521, - 0x7f895182, 0xf51da273, 0x7f88c894, 0xf5175fca, 0x7f883f58, 0xf5111d29, - 0x7f87b5cd, 0xf50ada8f, - 0x7f872bf3, 0xf50497fb, 0x7f86a1ca, 0xf4fe556e, 0x7f861753, 0xf4f812e7, - 0x7f858c8d, 0xf4f1d068, - 0x7f850179, 0xf4eb8def, 0x7f847616, 0xf4e54b7d, 0x7f83ea64, 0xf4df0912, - 0x7f835e64, 0xf4d8c6ae, - 0x7f82d214, 0xf4d28451, 0x7f824577, 0xf4cc41fb, 0x7f81b88a, 0xf4c5ffab, - 0x7f812b4f, 0xf4bfbd63, - 0x7f809dc5, 0xf4b97b21, 0x7f800fed, 0xf4b338e7, 0x7f7f81c6, 0xf4acf6b3, - 0x7f7ef350, 0xf4a6b486, - 0x7f7e648c, 0xf4a07261, 0x7f7dd579, 0xf49a3042, 0x7f7d4617, 0xf493ee2b, - 0x7f7cb667, 0xf48dac1a, - 0x7f7c2668, 0xf4876a10, 0x7f7b961b, 0xf481280e, 0x7f7b057e, 0xf47ae613, - 0x7f7a7494, 0xf474a41f, - 0x7f79e35a, 0xf46e6231, 0x7f7951d2, 0xf468204b, 0x7f78bffb, 0xf461de6d, - 0x7f782dd6, 0xf45b9c95, - 0x7f779b62, 0xf4555ac5, 0x7f77089f, 0xf44f18fb, 0x7f76758e, 0xf448d739, - 0x7f75e22e, 0xf442957e, - 0x7f754e80, 0xf43c53cb, 0x7f74ba83, 0xf436121e, 0x7f742637, 0xf42fd079, - 0x7f73919d, 0xf4298edc, - 0x7f72fcb4, 0xf4234d45, 0x7f72677c, 0xf41d0bb6, 0x7f71d1f6, 0xf416ca2e, - 0x7f713c21, 0xf41088ae, - 0x7f70a5fe, 0xf40a4735, 0x7f700f8c, 0xf40405c3, 0x7f6f78cb, 0xf3fdc459, - 0x7f6ee1bc, 0xf3f782f6, - 0x7f6e4a5e, 0xf3f1419a, 0x7f6db2b1, 0xf3eb0046, 0x7f6d1ab6, 0xf3e4bef9, - 0x7f6c826d, 0xf3de7db4, - 0x7f6be9d4, 0xf3d83c77, 0x7f6b50ed, 0xf3d1fb40, 0x7f6ab7b8, 0xf3cbba12, - 0x7f6a1e34, 0xf3c578eb, - 0x7f698461, 0xf3bf37cb, 0x7f68ea40, 0xf3b8f6b3, 0x7f684fd0, 0xf3b2b5a3, - 0x7f67b512, 0xf3ac749a, - 0x7f671a05, 0xf3a63398, 0x7f667ea9, 0xf39ff29f, 0x7f65e2ff, 0xf399b1ad, - 0x7f654706, 0xf39370c2, - 0x7f64aabf, 0xf38d2fe0, 0x7f640e29, 0xf386ef05, 0x7f637144, 0xf380ae31, - 0x7f62d411, 0xf37a6d66, - 0x7f62368f, 0xf3742ca2, 0x7f6198bf, 0xf36debe6, 0x7f60faa0, 0xf367ab31, - 0x7f605c33, 0xf3616a85, - 0x7f5fbd77, 0xf35b29e0, 0x7f5f1e6c, 0xf354e943, 0x7f5e7f13, 0xf34ea8ae, - 0x7f5ddf6b, 0xf3486820, - 0x7f5d3f75, 0xf342279b, 0x7f5c9f30, 0xf33be71d, 0x7f5bfe9d, 0xf335a6a7, - 0x7f5b5dbb, 0xf32f6639, - 0x7f5abc8a, 0xf32925d3, 0x7f5a1b0b, 0xf322e575, 0x7f59793e, 0xf31ca51f, - 0x7f58d721, 0xf31664d1, - 0x7f5834b7, 0xf310248a, 0x7f5791fd, 0xf309e44c, 0x7f56eef5, 0xf303a416, - 0x7f564b9f, 0xf2fd63e8, - 0x7f55a7fa, 0xf2f723c1, 0x7f550407, 0xf2f0e3a3, 0x7f545fc5, 0xf2eaa38d, - 0x7f53bb34, 0xf2e4637f, - 0x7f531655, 0xf2de2379, 0x7f527127, 0xf2d7e37b, 0x7f51cbab, 0xf2d1a385, - 0x7f5125e0, 0xf2cb6398, - 0x7f507fc7, 0xf2c523b2, 0x7f4fd95f, 0xf2bee3d5, 0x7f4f32a9, 0xf2b8a400, - 0x7f4e8ba4, 0xf2b26433, - 0x7f4de451, 0xf2ac246e, 0x7f4d3caf, 0xf2a5e4b1, 0x7f4c94be, 0xf29fa4fd, - 0x7f4bec7f, 0xf2996551, - 0x7f4b43f2, 0xf29325ad, 0x7f4a9b16, 0xf28ce612, 0x7f49f1eb, 0xf286a67e, - 0x7f494872, 0xf28066f4, - 0x7f489eaa, 0xf27a2771, 0x7f47f494, 0xf273e7f7, 0x7f474a30, 0xf26da885, - 0x7f469f7d, 0xf267691b, - 0x7f45f47b, 0xf26129ba, 0x7f45492b, 0xf25aea61, 0x7f449d8c, 0xf254ab11, - 0x7f43f19f, 0xf24e6bc9, - 0x7f434563, 0xf2482c8a, 0x7f4298d9, 0xf241ed53, 0x7f41ec01, 0xf23bae24, - 0x7f413ed9, 0xf2356efe, - 0x7f409164, 0xf22f2fe1, 0x7f3fe3a0, 0xf228f0cc, 0x7f3f358d, 0xf222b1c0, - 0x7f3e872c, 0xf21c72bc, - 0x7f3dd87c, 0xf21633c0, 0x7f3d297e, 0xf20ff4ce, 0x7f3c7a31, 0xf209b5e4, - 0x7f3bca96, 0xf2037702, - 0x7f3b1aad, 0xf1fd3829, 0x7f3a6a75, 0xf1f6f959, 0x7f39b9ee, 0xf1f0ba91, - 0x7f390919, 0xf1ea7bd2, - 0x7f3857f6, 0xf1e43d1c, 0x7f37a684, 0xf1ddfe6f, 0x7f36f4c3, 0xf1d7bfca, - 0x7f3642b4, 0xf1d1812e, - 0x7f359057, 0xf1cb429a, 0x7f34ddab, 0xf1c50410, 0x7f342ab1, 0xf1bec58e, - 0x7f337768, 0xf1b88715, - 0x7f32c3d1, 0xf1b248a5, 0x7f320feb, 0xf1ac0a3e, 0x7f315bb7, 0xf1a5cbdf, - 0x7f30a734, 0xf19f8d89, - 0x7f2ff263, 0xf1994f3d, 0x7f2f3d44, 0xf19310f9, 0x7f2e87d6, 0xf18cd2be, - 0x7f2dd219, 0xf186948c, - 0x7f2d1c0e, 0xf1805662, 0x7f2c65b5, 0xf17a1842, 0x7f2baf0d, 0xf173da2b, - 0x7f2af817, 0xf16d9c1d, - 0x7f2a40d2, 0xf1675e17, 0x7f29893f, 0xf161201b, 0x7f28d15d, 0xf15ae228, - 0x7f28192d, 0xf154a43d, - 0x7f2760af, 0xf14e665c, 0x7f26a7e2, 0xf1482884, 0x7f25eec7, 0xf141eab5, - 0x7f25355d, 0xf13bacef, - 0x7f247ba5, 0xf1356f32, 0x7f23c19e, 0xf12f317e, 0x7f230749, 0xf128f3d4, - 0x7f224ca6, 0xf122b632, - 0x7f2191b4, 0xf11c789a, 0x7f20d674, 0xf1163b0b, 0x7f201ae5, 0xf10ffd85, - 0x7f1f5f08, 0xf109c009, - 0x7f1ea2dc, 0xf1038295, 0x7f1de662, 0xf0fd452b, 0x7f1d299a, 0xf0f707ca, - 0x7f1c6c83, 0xf0f0ca72, - 0x7f1baf1e, 0xf0ea8d24, 0x7f1af16a, 0xf0e44fdf, 0x7f1a3368, 0xf0de12a3, - 0x7f197518, 0xf0d7d571, - 0x7f18b679, 0xf0d19848, 0x7f17f78c, 0xf0cb5b28, 0x7f173850, 0xf0c51e12, - 0x7f1678c6, 0xf0bee105, - 0x7f15b8ee, 0xf0b8a401, 0x7f14f8c7, 0xf0b26707, 0x7f143852, 0xf0ac2a16, - 0x7f13778e, 0xf0a5ed2f, - 0x7f12b67c, 0xf09fb051, 0x7f11f51c, 0xf099737d, 0x7f11336d, 0xf09336b2, - 0x7f107170, 0xf08cf9f1, - 0x7f0faf25, 0xf086bd39, 0x7f0eec8b, 0xf080808b, 0x7f0e29a3, 0xf07a43e7, - 0x7f0d666c, 0xf074074c, - 0x7f0ca2e7, 0xf06dcaba, 0x7f0bdf14, 0xf0678e32, 0x7f0b1af2, 0xf06151b4, - 0x7f0a5682, 0xf05b1540, - 0x7f0991c4, 0xf054d8d5, 0x7f08ccb7, 0xf04e9c73, 0x7f08075c, 0xf048601c, - 0x7f0741b2, 0xf04223ce, - 0x7f067bba, 0xf03be78a, 0x7f05b574, 0xf035ab4f, 0x7f04eedf, 0xf02f6f1f, - 0x7f0427fc, 0xf02932f8, - 0x7f0360cb, 0xf022f6da, 0x7f02994b, 0xf01cbac7, 0x7f01d17d, 0xf0167ebd, - 0x7f010961, 0xf01042be, - 0x7f0040f6, 0xf00a06c8, 0x7eff783d, 0xf003cadc, 0x7efeaf36, 0xeffd8ef9, - 0x7efde5e0, 0xeff75321, - 0x7efd1c3c, 0xeff11753, 0x7efc524a, 0xefeadb8e, 0x7efb8809, 0xefe49fd3, - 0x7efabd7a, 0xefde6423, - 0x7ef9f29d, 0xefd8287c, 0x7ef92771, 0xefd1ecdf, 0x7ef85bf7, 0xefcbb14c, - 0x7ef7902f, 0xefc575c3, - 0x7ef6c418, 0xefbf3a45, 0x7ef5f7b3, 0xefb8fed0, 0x7ef52b00, 0xefb2c365, - 0x7ef45dfe, 0xefac8804, - 0x7ef390ae, 0xefa64cae, 0x7ef2c310, 0xefa01161, 0x7ef1f524, 0xef99d61f, - 0x7ef126e9, 0xef939ae6, - 0x7ef05860, 0xef8d5fb8, 0x7eef8988, 0xef872494, 0x7eeeba62, 0xef80e97a, - 0x7eedeaee, 0xef7aae6b, - 0x7eed1b2c, 0xef747365, 0x7eec4b1b, 0xef6e386a, 0x7eeb7abc, 0xef67fd79, - 0x7eeaaa0f, 0xef61c292, - 0x7ee9d914, 0xef5b87b5, 0x7ee907ca, 0xef554ce3, 0x7ee83632, 0xef4f121b, - 0x7ee7644c, 0xef48d75d, - 0x7ee69217, 0xef429caa, 0x7ee5bf94, 0xef3c6201, 0x7ee4ecc3, 0xef362762, - 0x7ee419a3, 0xef2feccd, - 0x7ee34636, 0xef29b243, 0x7ee2727a, 0xef2377c4, 0x7ee19e6f, 0xef1d3d4e, - 0x7ee0ca17, 0xef1702e4, - 0x7edff570, 0xef10c883, 0x7edf207b, 0xef0a8e2d, 0x7ede4b38, 0xef0453e2, - 0x7edd75a6, 0xeefe19a1, - 0x7edc9fc6, 0xeef7df6a, 0x7edbc998, 0xeef1a53e, 0x7edaf31c, 0xeeeb6b1c, - 0x7eda1c51, 0xeee53105, - 0x7ed94538, 0xeedef6f9, 0x7ed86dd1, 0xeed8bcf7, 0x7ed7961c, 0xeed28300, - 0x7ed6be18, 0xeecc4913, - 0x7ed5e5c6, 0xeec60f31, 0x7ed50d26, 0xeebfd55a, 0x7ed43438, 0xeeb99b8d, - 0x7ed35afb, 0xeeb361cb, - 0x7ed28171, 0xeead2813, 0x7ed1a798, 0xeea6ee66, 0x7ed0cd70, 0xeea0b4c4, - 0x7ecff2fb, 0xee9a7b2d, - 0x7ecf1837, 0xee9441a0, 0x7ece3d25, 0xee8e081e, 0x7ecd61c5, 0xee87cea7, - 0x7ecc8617, 0xee81953b, - 0x7ecbaa1a, 0xee7b5bd9, 0x7ecacdd0, 0xee752283, 0x7ec9f137, 0xee6ee937, - 0x7ec9144f, 0xee68aff6, - 0x7ec8371a, 0xee6276bf, 0x7ec75996, 0xee5c3d94, 0x7ec67bc5, 0xee560473, - 0x7ec59da5, 0xee4fcb5e, - 0x7ec4bf36, 0xee499253, 0x7ec3e07a, 0xee435953, 0x7ec3016f, 0xee3d205e, - 0x7ec22217, 0xee36e775, - 0x7ec14270, 0xee30ae96, 0x7ec0627a, 0xee2a75c2, 0x7ebf8237, 0xee243cf9, - 0x7ebea1a6, 0xee1e043b, - 0x7ebdc0c6, 0xee17cb88, 0x7ebcdf98, 0xee1192e0, 0x7ebbfe1c, 0xee0b5a43, - 0x7ebb1c52, 0xee0521b2, - 0x7eba3a39, 0xedfee92b, 0x7eb957d2, 0xedf8b0b0, 0x7eb8751e, 0xedf2783f, - 0x7eb7921b, 0xedec3fda, - 0x7eb6aeca, 0xede60780, 0x7eb5cb2a, 0xeddfcf31, 0x7eb4e73d, 0xedd996ed, - 0x7eb40301, 0xedd35eb5, - 0x7eb31e78, 0xedcd2687, 0x7eb239a0, 0xedc6ee65, 0x7eb1547a, 0xedc0b64e, - 0x7eb06f05, 0xedba7e43, - 0x7eaf8943, 0xedb44642, 0x7eaea333, 0xedae0e4d, 0x7eadbcd4, 0xeda7d664, - 0x7eacd627, 0xeda19e85, - 0x7eabef2c, 0xed9b66b2, 0x7eab07e3, 0xed952eea, 0x7eaa204c, 0xed8ef72e, - 0x7ea93867, 0xed88bf7d, - 0x7ea85033, 0xed8287d7, 0x7ea767b2, 0xed7c503d, 0x7ea67ee2, 0xed7618ae, - 0x7ea595c4, 0xed6fe12b, - 0x7ea4ac58, 0xed69a9b3, 0x7ea3c29e, 0xed637246, 0x7ea2d896, 0xed5d3ae5, - 0x7ea1ee3f, 0xed570390, - 0x7ea1039b, 0xed50cc46, 0x7ea018a8, 0xed4a9507, 0x7e9f2d68, 0xed445dd5, - 0x7e9e41d9, 0xed3e26ad, - 0x7e9d55fc, 0xed37ef91, 0x7e9c69d1, 0xed31b881, 0x7e9b7d58, 0xed2b817d, - 0x7e9a9091, 0xed254a84, - 0x7e99a37c, 0xed1f1396, 0x7e98b618, 0xed18dcb5, 0x7e97c867, 0xed12a5df, - 0x7e96da67, 0xed0c6f14, - 0x7e95ec1a, 0xed063856, 0x7e94fd7e, 0xed0001a3, 0x7e940e94, 0xecf9cafb, - 0x7e931f5c, 0xecf39460, - 0x7e922fd6, 0xeced5dd0, 0x7e914002, 0xece7274c, 0x7e904fe0, 0xece0f0d4, - 0x7e8f5f70, 0xecdaba67, - 0x7e8e6eb2, 0xecd48407, 0x7e8d7da6, 0xecce4db2, 0x7e8c8c4b, 0xecc81769, - 0x7e8b9aa3, 0xecc1e12c, - 0x7e8aa8ac, 0xecbbaafb, 0x7e89b668, 0xecb574d5, 0x7e88c3d5, 0xecaf3ebc, - 0x7e87d0f5, 0xeca908ae, - 0x7e86ddc6, 0xeca2d2ad, 0x7e85ea49, 0xec9c9cb7, 0x7e84f67e, 0xec9666cd, - 0x7e840265, 0xec9030f0, - 0x7e830dff, 0xec89fb1e, 0x7e82194a, 0xec83c558, 0x7e812447, 0xec7d8f9e, - 0x7e802ef6, 0xec7759f1, - 0x7e7f3957, 0xec71244f, 0x7e7e436a, 0xec6aeeba, 0x7e7d4d2f, 0xec64b930, - 0x7e7c56a5, 0xec5e83b3, - 0x7e7b5fce, 0xec584e41, 0x7e7a68a9, 0xec5218dc, 0x7e797136, 0xec4be383, - 0x7e787975, 0xec45ae36, - 0x7e778166, 0xec3f78f6, 0x7e768908, 0xec3943c1, 0x7e75905d, 0xec330e99, - 0x7e749764, 0xec2cd97d, - 0x7e739e1d, 0xec26a46d, 0x7e72a488, 0xec206f69, 0x7e71aaa4, 0xec1a3a72, - 0x7e70b073, 0xec140587, - 0x7e6fb5f4, 0xec0dd0a8, 0x7e6ebb27, 0xec079bd6, 0x7e6dc00c, 0xec01670f, - 0x7e6cc4a2, 0xebfb3256, - 0x7e6bc8eb, 0xebf4fda8, 0x7e6acce6, 0xebeec907, 0x7e69d093, 0xebe89472, - 0x7e68d3f2, 0xebe25fea, - 0x7e67d703, 0xebdc2b6e, 0x7e66d9c6, 0xebd5f6fe, 0x7e65dc3b, 0xebcfc29b, - 0x7e64de62, 0xebc98e45, - 0x7e63e03b, 0xebc359fb, 0x7e62e1c6, 0xebbd25bd, 0x7e61e303, 0xebb6f18c, - 0x7e60e3f2, 0xebb0bd67, - 0x7e5fe493, 0xebaa894f, 0x7e5ee4e6, 0xeba45543, 0x7e5de4ec, 0xeb9e2144, - 0x7e5ce4a3, 0xeb97ed52, - 0x7e5be40c, 0xeb91b96c, 0x7e5ae328, 0xeb8b8593, 0x7e59e1f5, 0xeb8551c6, - 0x7e58e075, 0xeb7f1e06, - 0x7e57dea7, 0xeb78ea52, 0x7e56dc8a, 0xeb72b6ac, 0x7e55da20, 0xeb6c8312, - 0x7e54d768, 0xeb664f84, - 0x7e53d462, 0xeb601c04, 0x7e52d10e, 0xeb59e890, 0x7e51cd6c, 0xeb53b529, - 0x7e50c97c, 0xeb4d81ce, - 0x7e4fc53e, 0xeb474e81, 0x7e4ec0b2, 0xeb411b40, 0x7e4dbbd9, 0xeb3ae80c, - 0x7e4cb6b1, 0xeb34b4e4, - 0x7e4bb13c, 0xeb2e81ca, 0x7e4aab78, 0xeb284ebc, 0x7e49a567, 0xeb221bbb, - 0x7e489f08, 0xeb1be8c8, - 0x7e47985b, 0xeb15b5e1, 0x7e469160, 0xeb0f8307, 0x7e458a17, 0xeb095039, - 0x7e448281, 0xeb031d79, - 0x7e437a9c, 0xeafceac6, 0x7e427269, 0xeaf6b81f, 0x7e4169e9, 0xeaf08586, - 0x7e40611b, 0xeaea52fa, - 0x7e3f57ff, 0xeae4207a, 0x7e3e4e95, 0xeaddee08, 0x7e3d44dd, 0xead7bba3, - 0x7e3c3ad7, 0xead1894b, - 0x7e3b3083, 0xeacb56ff, 0x7e3a25e2, 0xeac524c1, 0x7e391af3, 0xeabef290, - 0x7e380fb5, 0xeab8c06c, - 0x7e37042a, 0xeab28e56, 0x7e35f851, 0xeaac5c4c, 0x7e34ec2b, 0xeaa62a4f, - 0x7e33dfb6, 0xea9ff860, - 0x7e32d2f4, 0xea99c67e, 0x7e31c5e3, 0xea9394a9, 0x7e30b885, 0xea8d62e1, - 0x7e2faad9, 0xea873127, - 0x7e2e9cdf, 0xea80ff7a, 0x7e2d8e97, 0xea7acdda, 0x7e2c8002, 0xea749c47, - 0x7e2b711f, 0xea6e6ac2, - 0x7e2a61ed, 0xea683949, 0x7e29526e, 0xea6207df, 0x7e2842a2, 0xea5bd681, - 0x7e273287, 0xea55a531, - 0x7e26221f, 0xea4f73ee, 0x7e251168, 0xea4942b9, 0x7e240064, 0xea431191, - 0x7e22ef12, 0xea3ce077, - 0x7e21dd73, 0xea36af69, 0x7e20cb85, 0xea307e6a, 0x7e1fb94a, 0xea2a4d78, - 0x7e1ea6c1, 0xea241c93, - 0x7e1d93ea, 0xea1debbb, 0x7e1c80c5, 0xea17baf2, 0x7e1b6d53, 0xea118a35, - 0x7e1a5992, 0xea0b5987, - 0x7e194584, 0xea0528e5, 0x7e183128, 0xe9fef852, 0x7e171c7f, 0xe9f8c7cc, - 0x7e160787, 0xe9f29753, - 0x7e14f242, 0xe9ec66e8, 0x7e13dcaf, 0xe9e6368b, 0x7e12c6ce, 0xe9e0063c, - 0x7e11b0a0, 0xe9d9d5fa, - 0x7e109a24, 0xe9d3a5c5, 0x7e0f835a, 0xe9cd759f, 0x7e0e6c42, 0xe9c74586, - 0x7e0d54dc, 0xe9c1157a, - 0x7e0c3d29, 0xe9bae57d, 0x7e0b2528, 0xe9b4b58d, 0x7e0a0cd9, 0xe9ae85ab, - 0x7e08f43d, 0xe9a855d7, - 0x7e07db52, 0xe9a22610, 0x7e06c21a, 0xe99bf658, 0x7e05a894, 0xe995c6ad, - 0x7e048ec1, 0xe98f9710, - 0x7e0374a0, 0xe9896781, 0x7e025a31, 0xe98337ff, 0x7e013f74, 0xe97d088c, - 0x7e00246a, 0xe976d926, - 0x7dff0911, 0xe970a9ce, 0x7dfded6c, 0xe96a7a85, 0x7dfcd178, 0xe9644b49, - 0x7dfbb537, 0xe95e1c1b, - 0x7dfa98a8, 0xe957ecfb, 0x7df97bcb, 0xe951bde9, 0x7df85ea0, 0xe94b8ee5, - 0x7df74128, 0xe9455fef, - 0x7df62362, 0xe93f3107, 0x7df5054f, 0xe939022d, 0x7df3e6ee, 0xe932d361, - 0x7df2c83f, 0xe92ca4a4, - 0x7df1a942, 0xe92675f4, 0x7df089f8, 0xe9204752, 0x7def6a60, 0xe91a18bf, - 0x7dee4a7a, 0xe913ea39, - 0x7ded2a47, 0xe90dbbc2, 0x7dec09c6, 0xe9078d59, 0x7deae8f7, 0xe9015efe, - 0x7de9c7da, 0xe8fb30b1, - 0x7de8a670, 0xe8f50273, 0x7de784b9, 0xe8eed443, 0x7de662b3, 0xe8e8a621, - 0x7de54060, 0xe8e2780d, - 0x7de41dc0, 0xe8dc4a07, 0x7de2fad1, 0xe8d61c10, 0x7de1d795, 0xe8cfee27, - 0x7de0b40b, 0xe8c9c04c, - 0x7ddf9034, 0xe8c39280, 0x7dde6c0f, 0xe8bd64c2, 0x7ddd479d, 0xe8b73712, - 0x7ddc22dc, 0xe8b10971, - 0x7ddafdce, 0xe8aadbde, 0x7dd9d873, 0xe8a4ae59, 0x7dd8b2ca, 0xe89e80e3, - 0x7dd78cd3, 0xe898537b, - 0x7dd6668f, 0xe8922622, 0x7dd53ffc, 0xe88bf8d7, 0x7dd4191d, 0xe885cb9a, - 0x7dd2f1f0, 0xe87f9e6c, - 0x7dd1ca75, 0xe879714d, 0x7dd0a2ac, 0xe873443c, 0x7dcf7a96, 0xe86d173a, - 0x7dce5232, 0xe866ea46, - 0x7dcd2981, 0xe860bd61, 0x7dcc0082, 0xe85a908a, 0x7dcad736, 0xe85463c2, - 0x7dc9ad9c, 0xe84e3708, - 0x7dc883b4, 0xe8480a5d, 0x7dc7597f, 0xe841ddc1, 0x7dc62efc, 0xe83bb133, - 0x7dc5042b, 0xe83584b4, - 0x7dc3d90d, 0xe82f5844, 0x7dc2ada2, 0xe8292be3, 0x7dc181e8, 0xe822ff90, - 0x7dc055e2, 0xe81cd34b, - 0x7dbf298d, 0xe816a716, 0x7dbdfceb, 0xe8107aef, 0x7dbccffc, 0xe80a4ed7, - 0x7dbba2bf, 0xe80422ce, - 0x7dba7534, 0xe7fdf6d4, 0x7db9475c, 0xe7f7cae8, 0x7db81936, 0xe7f19f0c, - 0x7db6eac3, 0xe7eb733e, - 0x7db5bc02, 0xe7e5477f, 0x7db48cf4, 0xe7df1bcf, 0x7db35d98, 0xe7d8f02d, - 0x7db22def, 0xe7d2c49b, - 0x7db0fdf8, 0xe7cc9917, 0x7dafcdb3, 0xe7c66da3, 0x7dae9d21, 0xe7c0423d, - 0x7dad6c42, 0xe7ba16e7, - 0x7dac3b15, 0xe7b3eb9f, 0x7dab099a, 0xe7adc066, 0x7da9d7d2, 0xe7a7953d, - 0x7da8a5bc, 0xe7a16a22, - 0x7da77359, 0xe79b3f16, 0x7da640a9, 0xe795141a, 0x7da50dab, 0xe78ee92c, - 0x7da3da5f, 0xe788be4e, - 0x7da2a6c6, 0xe782937e, 0x7da172df, 0xe77c68be, 0x7da03eab, 0xe7763e0d, - 0x7d9f0a29, 0xe770136b, - 0x7d9dd55a, 0xe769e8d8, 0x7d9ca03e, 0xe763be55, 0x7d9b6ad3, 0xe75d93e0, - 0x7d9a351c, 0xe757697b, - 0x7d98ff17, 0xe7513f25, 0x7d97c8c4, 0xe74b14de, 0x7d969224, 0xe744eaa6, - 0x7d955b37, 0xe73ec07e, - 0x7d9423fc, 0xe7389665, 0x7d92ec73, 0xe7326c5b, 0x7d91b49e, 0xe72c4260, - 0x7d907c7a, 0xe7261875, - 0x7d8f4409, 0xe71fee99, 0x7d8e0b4b, 0xe719c4cd, 0x7d8cd240, 0xe7139b10, - 0x7d8b98e6, 0xe70d7162, - 0x7d8a5f40, 0xe70747c4, 0x7d89254c, 0xe7011e35, 0x7d87eb0a, 0xe6faf4b5, - 0x7d86b07c, 0xe6f4cb45, - 0x7d85759f, 0xe6eea1e4, 0x7d843a76, 0xe6e87893, 0x7d82fefe, 0xe6e24f51, - 0x7d81c33a, 0xe6dc261f, - 0x7d808728, 0xe6d5fcfc, 0x7d7f4ac8, 0xe6cfd3e9, 0x7d7e0e1c, 0xe6c9aae5, - 0x7d7cd121, 0xe6c381f1, - 0x7d7b93da, 0xe6bd590d, 0x7d7a5645, 0xe6b73038, 0x7d791862, 0xe6b10772, - 0x7d77da32, 0xe6aadebc, - 0x7d769bb5, 0xe6a4b616, 0x7d755cea, 0xe69e8d80, 0x7d741dd2, 0xe69864f9, - 0x7d72de6d, 0xe6923c82, - 0x7d719eba, 0xe68c141a, 0x7d705eba, 0xe685ebc2, 0x7d6f1e6c, 0xe67fc37a, - 0x7d6dddd2, 0xe6799b42, - 0x7d6c9ce9, 0xe6737319, 0x7d6b5bb4, 0xe66d4b01, 0x7d6a1a31, 0xe66722f7, - 0x7d68d860, 0xe660fafe, - 0x7d679642, 0xe65ad315, 0x7d6653d7, 0xe654ab3b, 0x7d65111f, 0xe64e8371, - 0x7d63ce19, 0xe6485bb7, - 0x7d628ac6, 0xe642340d, 0x7d614725, 0xe63c0c73, 0x7d600338, 0xe635e4e9, - 0x7d5ebefc, 0xe62fbd6e, - 0x7d5d7a74, 0xe6299604, 0x7d5c359e, 0xe6236ea9, 0x7d5af07b, 0xe61d475e, - 0x7d59ab0a, 0xe6172024, - 0x7d58654d, 0xe610f8f9, 0x7d571f41, 0xe60ad1de, 0x7d55d8e9, 0xe604aad4, - 0x7d549243, 0xe5fe83d9, - 0x7d534b50, 0xe5f85cef, 0x7d520410, 0xe5f23614, 0x7d50bc82, 0xe5ec0f4a, - 0x7d4f74a7, 0xe5e5e88f, - 0x7d4e2c7f, 0xe5dfc1e5, 0x7d4ce409, 0xe5d99b4b, 0x7d4b9b46, 0xe5d374c1, - 0x7d4a5236, 0xe5cd4e47, - 0x7d4908d9, 0xe5c727dd, 0x7d47bf2e, 0xe5c10184, 0x7d467536, 0xe5badb3a, - 0x7d452af1, 0xe5b4b501, - 0x7d43e05e, 0xe5ae8ed8, 0x7d42957e, 0xe5a868bf, 0x7d414a51, 0xe5a242b7, - 0x7d3ffed7, 0xe59c1cbf, - 0x7d3eb30f, 0xe595f6d7, 0x7d3d66fa, 0xe58fd0ff, 0x7d3c1a98, 0xe589ab38, - 0x7d3acde9, 0xe5838581, - 0x7d3980ec, 0xe57d5fda, 0x7d3833a2, 0xe5773a44, 0x7d36e60b, 0xe57114be, - 0x7d359827, 0xe56aef49, - 0x7d3449f5, 0xe564c9e3, 0x7d32fb76, 0xe55ea48f, 0x7d31acaa, 0xe5587f4a, - 0x7d305d91, 0xe5525a17, - 0x7d2f0e2b, 0xe54c34f3, 0x7d2dbe77, 0xe5460fe0, 0x7d2c6e76, 0xe53feade, - 0x7d2b1e28, 0xe539c5ec, - 0x7d29cd8c, 0xe533a10a, 0x7d287ca4, 0xe52d7c39, 0x7d272b6e, 0xe5275779, - 0x7d25d9eb, 0xe52132c9, - 0x7d24881b, 0xe51b0e2a, 0x7d2335fe, 0xe514e99b, 0x7d21e393, 0xe50ec51d, - 0x7d2090db, 0xe508a0b0, - 0x7d1f3dd6, 0xe5027c53, 0x7d1dea84, 0xe4fc5807, 0x7d1c96e5, 0xe4f633cc, - 0x7d1b42f9, 0xe4f00fa1, - 0x7d19eebf, 0xe4e9eb87, 0x7d189a38, 0xe4e3c77d, 0x7d174564, 0xe4dda385, - 0x7d15f043, 0xe4d77f9d, - 0x7d149ad5, 0xe4d15bc6, 0x7d134519, 0xe4cb37ff, 0x7d11ef11, 0xe4c5144a, - 0x7d1098bb, 0xe4bef0a5, - 0x7d0f4218, 0xe4b8cd11, 0x7d0deb28, 0xe4b2a98e, 0x7d0c93eb, 0xe4ac861b, - 0x7d0b3c60, 0xe4a662ba, - 0x7d09e489, 0xe4a03f69, 0x7d088c64, 0xe49a1c29, 0x7d0733f3, 0xe493f8fb, - 0x7d05db34, 0xe48dd5dd, - 0x7d048228, 0xe487b2d0, 0x7d0328cf, 0xe4818fd4, 0x7d01cf29, 0xe47b6ce9, - 0x7d007535, 0xe4754a0e, - 0x7cff1af5, 0xe46f2745, 0x7cfdc068, 0xe469048d, 0x7cfc658d, 0xe462e1e6, - 0x7cfb0a65, 0xe45cbf50, - 0x7cf9aef0, 0xe4569ccb, 0x7cf8532f, 0xe4507a57, 0x7cf6f720, 0xe44a57f4, - 0x7cf59ac4, 0xe44435a2, - 0x7cf43e1a, 0xe43e1362, 0x7cf2e124, 0xe437f132, 0x7cf183e1, 0xe431cf14, - 0x7cf02651, 0xe42bad07, - 0x7ceec873, 0xe4258b0a, 0x7ced6a49, 0xe41f6920, 0x7cec0bd1, 0xe4194746, - 0x7ceaad0c, 0xe413257d, - 0x7ce94dfb, 0xe40d03c6, 0x7ce7ee9c, 0xe406e220, 0x7ce68ef0, 0xe400c08b, - 0x7ce52ef7, 0xe3fa9f08, - 0x7ce3ceb2, 0xe3f47d96, 0x7ce26e1f, 0xe3ee5c35, 0x7ce10d3f, 0xe3e83ae5, - 0x7cdfac12, 0xe3e219a7, - 0x7cde4a98, 0xe3dbf87a, 0x7cdce8d1, 0xe3d5d75e, 0x7cdb86bd, 0xe3cfb654, - 0x7cda245c, 0xe3c9955b, - 0x7cd8c1ae, 0xe3c37474, 0x7cd75eb3, 0xe3bd539e, 0x7cd5fb6a, 0xe3b732d9, - 0x7cd497d5, 0xe3b11226, - 0x7cd333f3, 0xe3aaf184, 0x7cd1cfc4, 0xe3a4d0f4, 0x7cd06b48, 0xe39eb075, - 0x7ccf067f, 0xe3989008, - 0x7ccda169, 0xe3926fad, 0x7ccc3c06, 0xe38c4f63, 0x7ccad656, 0xe3862f2a, - 0x7cc97059, 0xe3800f03, - 0x7cc80a0f, 0xe379eeed, 0x7cc6a378, 0xe373ceea, 0x7cc53c94, 0xe36daef7, - 0x7cc3d563, 0xe3678f17, - 0x7cc26de5, 0xe3616f48, 0x7cc1061a, 0xe35b4f8b, 0x7cbf9e03, 0xe3552fdf, - 0x7cbe359e, 0xe34f1045, - 0x7cbcccec, 0xe348f0bd, 0x7cbb63ee, 0xe342d146, 0x7cb9faa2, 0xe33cb1e1, - 0x7cb8910a, 0xe336928e, - 0x7cb72724, 0xe330734d, 0x7cb5bcf2, 0xe32a541d, 0x7cb45272, 0xe3243500, - 0x7cb2e7a6, 0xe31e15f4, - 0x7cb17c8d, 0xe317f6fa, 0x7cb01127, 0xe311d811, 0x7caea574, 0xe30bb93b, - 0x7cad3974, 0xe3059a76, - 0x7cabcd28, 0xe2ff7bc3, 0x7caa608e, 0xe2f95d23, 0x7ca8f3a7, 0xe2f33e94, - 0x7ca78674, 0xe2ed2017, - 0x7ca618f3, 0xe2e701ac, 0x7ca4ab26, 0xe2e0e352, 0x7ca33d0c, 0xe2dac50b, - 0x7ca1cea5, 0xe2d4a6d6, - 0x7ca05ff1, 0xe2ce88b3, 0x7c9ef0f0, 0xe2c86aa2, 0x7c9d81a3, 0xe2c24ca2, - 0x7c9c1208, 0xe2bc2eb5, - 0x7c9aa221, 0xe2b610da, 0x7c9931ec, 0xe2aff311, 0x7c97c16b, 0xe2a9d55a, - 0x7c96509d, 0xe2a3b7b5, - 0x7c94df83, 0xe29d9a23, 0x7c936e1b, 0xe2977ca2, 0x7c91fc66, 0xe2915f34, - 0x7c908a65, 0xe28b41d7, - 0x7c8f1817, 0xe285248d, 0x7c8da57c, 0xe27f0755, 0x7c8c3294, 0xe278ea30, - 0x7c8abf5f, 0xe272cd1c, - 0x7c894bde, 0xe26cb01b, 0x7c87d810, 0xe266932c, 0x7c8663f4, 0xe260764f, - 0x7c84ef8c, 0xe25a5984, - 0x7c837ad8, 0xe2543ccc, 0x7c8205d6, 0xe24e2026, 0x7c809088, 0xe2480393, - 0x7c7f1aed, 0xe241e711, - 0x7c7da505, 0xe23bcaa2, 0x7c7c2ed0, 0xe235ae46, 0x7c7ab84e, 0xe22f91fc, - 0x7c794180, 0xe22975c4, - 0x7c77ca65, 0xe223599e, 0x7c7652fd, 0xe21d3d8b, 0x7c74db48, 0xe217218b, - 0x7c736347, 0xe211059d, - 0x7c71eaf9, 0xe20ae9c1, 0x7c70725e, 0xe204cdf8, 0x7c6ef976, 0xe1feb241, - 0x7c6d8041, 0xe1f8969d, - 0x7c6c06c0, 0xe1f27b0b, 0x7c6a8cf2, 0xe1ec5f8c, 0x7c6912d7, 0xe1e64420, - 0x7c679870, 0xe1e028c6, - 0x7c661dbc, 0xe1da0d7e, 0x7c64a2bb, 0xe1d3f24a, 0x7c63276d, 0xe1cdd727, - 0x7c61abd3, 0xe1c7bc18, - 0x7c602fec, 0xe1c1a11b, 0x7c5eb3b8, 0xe1bb8631, 0x7c5d3737, 0xe1b56b59, - 0x7c5bba6a, 0xe1af5094, - 0x7c5a3d50, 0xe1a935e2, 0x7c58bfe9, 0xe1a31b42, 0x7c574236, 0xe19d00b6, - 0x7c55c436, 0xe196e63c, - 0x7c5445e9, 0xe190cbd4, 0x7c52c74f, 0xe18ab180, 0x7c514869, 0xe184973e, - 0x7c4fc936, 0xe17e7d0f, - 0x7c4e49b7, 0xe17862f3, 0x7c4cc9ea, 0xe17248ea, 0x7c4b49d2, 0xe16c2ef4, - 0x7c49c96c, 0xe1661510, - 0x7c4848ba, 0xe15ffb3f, 0x7c46c7bb, 0xe159e182, 0x7c45466f, 0xe153c7d7, - 0x7c43c4d7, 0xe14dae3f, - 0x7c4242f2, 0xe14794ba, 0x7c40c0c1, 0xe1417b48, 0x7c3f3e42, 0xe13b61e9, - 0x7c3dbb78, 0xe135489d, - 0x7c3c3860, 0xe12f2f63, 0x7c3ab4fc, 0xe129163d, 0x7c39314b, 0xe122fd2a, - 0x7c37ad4e, 0xe11ce42a, - 0x7c362904, 0xe116cb3d, 0x7c34a46d, 0xe110b263, 0x7c331f8a, 0xe10a999c, - 0x7c319a5a, 0xe10480e9, - 0x7c3014de, 0xe0fe6848, 0x7c2e8f15, 0xe0f84fbb, 0x7c2d08ff, 0xe0f23740, - 0x7c2b829d, 0xe0ec1ed9, - 0x7c29fbee, 0xe0e60685, 0x7c2874f3, 0xe0dfee44, 0x7c26edab, 0xe0d9d616, - 0x7c256616, 0xe0d3bdfc, - 0x7c23de35, 0xe0cda5f5, 0x7c225607, 0xe0c78e01, 0x7c20cd8d, 0xe0c17620, - 0x7c1f44c6, 0xe0bb5e53, - 0x7c1dbbb3, 0xe0b54698, 0x7c1c3253, 0xe0af2ef2, 0x7c1aa8a6, 0xe0a9175e, - 0x7c191ead, 0xe0a2ffde, - 0x7c179467, 0xe09ce871, 0x7c1609d5, 0xe096d117, 0x7c147ef6, 0xe090b9d1, - 0x7c12f3cb, 0xe08aa29f, - 0x7c116853, 0xe0848b7f, 0x7c0fdc8f, 0xe07e7473, 0x7c0e507e, 0xe0785d7b, - 0x7c0cc421, 0xe0724696, - 0x7c0b3777, 0xe06c2fc4, 0x7c09aa80, 0xe0661906, 0x7c081d3d, 0xe060025c, - 0x7c068fae, 0xe059ebc5, - 0x7c0501d2, 0xe053d541, 0x7c0373a9, 0xe04dbed1, 0x7c01e534, 0xe047a875, - 0x7c005673, 0xe041922c, - 0x7bfec765, 0xe03b7bf6, 0x7bfd380a, 0xe03565d5, 0x7bfba863, 0xe02f4fc6, - 0x7bfa1870, 0xe02939cc, - 0x7bf88830, 0xe02323e5, 0x7bf6f7a4, 0xe01d0e12, 0x7bf566cb, 0xe016f852, - 0x7bf3d5a6, 0xe010e2a7, - 0x7bf24434, 0xe00acd0e, 0x7bf0b276, 0xe004b78a, 0x7bef206b, 0xdffea219, - 0x7bed8e14, 0xdff88cbc, - 0x7bebfb70, 0xdff27773, 0x7bea6880, 0xdfec623e, 0x7be8d544, 0xdfe64d1c, - 0x7be741bb, 0xdfe0380e, - 0x7be5ade6, 0xdfda2314, 0x7be419c4, 0xdfd40e2e, 0x7be28556, 0xdfcdf95c, - 0x7be0f09b, 0xdfc7e49d, - 0x7bdf5b94, 0xdfc1cff3, 0x7bddc641, 0xdfbbbb5c, 0x7bdc30a1, 0xdfb5a6d9, - 0x7bda9ab5, 0xdfaf926a, - 0x7bd9047c, 0xdfa97e0f, 0x7bd76df7, 0xdfa369c8, 0x7bd5d726, 0xdf9d5595, - 0x7bd44008, 0xdf974176, - 0x7bd2a89e, 0xdf912d6b, 0x7bd110e8, 0xdf8b1974, 0x7bcf78e5, 0xdf850591, - 0x7bcde095, 0xdf7ef1c2, - 0x7bcc47fa, 0xdf78de07, 0x7bcaaf12, 0xdf72ca60, 0x7bc915dd, 0xdf6cb6cd, - 0x7bc77c5d, 0xdf66a34e, - 0x7bc5e290, 0xdf608fe4, 0x7bc44876, 0xdf5a7c8d, 0x7bc2ae10, 0xdf54694b, - 0x7bc1135e, 0xdf4e561c, - 0x7bbf7860, 0xdf484302, 0x7bbddd15, 0xdf422ffd, 0x7bbc417e, 0xdf3c1d0b, - 0x7bbaa59a, 0xdf360a2d, - 0x7bb9096b, 0xdf2ff764, 0x7bb76cef, 0xdf29e4af, 0x7bb5d026, 0xdf23d20e, - 0x7bb43311, 0xdf1dbf82, - 0x7bb295b0, 0xdf17ad0a, 0x7bb0f803, 0xdf119aa6, 0x7baf5a09, 0xdf0b8856, - 0x7badbbc3, 0xdf05761b, - 0x7bac1d31, 0xdeff63f4, 0x7baa7e53, 0xdef951e2, 0x7ba8df28, 0xdef33fe3, - 0x7ba73fb1, 0xdeed2dfa, - 0x7ba59fee, 0xdee71c24, 0x7ba3ffde, 0xdee10a63, 0x7ba25f82, 0xdedaf8b7, - 0x7ba0beda, 0xded4e71f, - 0x7b9f1de6, 0xdeced59b, 0x7b9d7ca5, 0xdec8c42c, 0x7b9bdb18, 0xdec2b2d1, - 0x7b9a393f, 0xdebca18b, - 0x7b989719, 0xdeb69059, 0x7b96f4a8, 0xdeb07f3c, 0x7b9551ea, 0xdeaa6e34, - 0x7b93aee0, 0xdea45d40, - 0x7b920b89, 0xde9e4c60, 0x7b9067e7, 0xde983b95, 0x7b8ec3f8, 0xde922adf, - 0x7b8d1fbd, 0xde8c1a3e, - 0x7b8b7b36, 0xde8609b1, 0x7b89d662, 0xde7ff938, 0x7b883143, 0xde79e8d5, - 0x7b868bd7, 0xde73d886, - 0x7b84e61f, 0xde6dc84b, 0x7b83401b, 0xde67b826, 0x7b8199ca, 0xde61a815, - 0x7b7ff32e, 0xde5b9819, - 0x7b7e4c45, 0xde558831, 0x7b7ca510, 0xde4f785f, 0x7b7afd8f, 0xde4968a1, - 0x7b7955c2, 0xde4358f8, - 0x7b77ada8, 0xde3d4964, 0x7b760542, 0xde3739e4, 0x7b745c91, 0xde312a7a, - 0x7b72b393, 0xde2b1b24, - 0x7b710a49, 0xde250be3, 0x7b6f60b2, 0xde1efcb7, 0x7b6db6d0, 0xde18eda0, - 0x7b6c0ca2, 0xde12de9e, - 0x7b6a6227, 0xde0ccfb1, 0x7b68b760, 0xde06c0d9, 0x7b670c4d, 0xde00b216, - 0x7b6560ee, 0xddfaa367, - 0x7b63b543, 0xddf494ce, 0x7b62094c, 0xddee8649, 0x7b605d09, 0xdde877da, - 0x7b5eb079, 0xdde26980, - 0x7b5d039e, 0xdddc5b3b, 0x7b5b5676, 0xddd64d0a, 0x7b59a902, 0xddd03eef, - 0x7b57fb42, 0xddca30e9, - 0x7b564d36, 0xddc422f8, 0x7b549ede, 0xddbe151d, 0x7b52f03a, 0xddb80756, - 0x7b51414a, 0xddb1f9a4, - 0x7b4f920e, 0xddabec08, 0x7b4de286, 0xdda5de81, 0x7b4c32b1, 0xdd9fd10f, - 0x7b4a8291, 0xdd99c3b2, - 0x7b48d225, 0xdd93b66a, 0x7b47216c, 0xdd8da938, 0x7b457068, 0xdd879c1b, - 0x7b43bf17, 0xdd818f13, - 0x7b420d7a, 0xdd7b8220, 0x7b405b92, 0xdd757543, 0x7b3ea95d, 0xdd6f687b, - 0x7b3cf6dc, 0xdd695bc9, - 0x7b3b4410, 0xdd634f2b, 0x7b3990f7, 0xdd5d42a3, 0x7b37dd92, 0xdd573631, - 0x7b3629e1, 0xdd5129d4, - 0x7b3475e5, 0xdd4b1d8c, 0x7b32c19c, 0xdd451159, 0x7b310d07, 0xdd3f053c, - 0x7b2f5826, 0xdd38f935, - 0x7b2da2fa, 0xdd32ed43, 0x7b2bed81, 0xdd2ce166, 0x7b2a37bc, 0xdd26d59f, - 0x7b2881ac, 0xdd20c9ed, - 0x7b26cb4f, 0xdd1abe51, 0x7b2514a6, 0xdd14b2ca, 0x7b235db2, 0xdd0ea759, - 0x7b21a671, 0xdd089bfe, - 0x7b1feee5, 0xdd0290b8, 0x7b1e370d, 0xdcfc8588, 0x7b1c7ee8, 0xdcf67a6d, - 0x7b1ac678, 0xdcf06f68, - 0x7b190dbc, 0xdcea6478, 0x7b1754b3, 0xdce4599e, 0x7b159b5f, 0xdcde4eda, - 0x7b13e1bf, 0xdcd8442b, - 0x7b1227d3, 0xdcd23993, 0x7b106d9b, 0xdccc2f0f, 0x7b0eb318, 0xdcc624a2, - 0x7b0cf848, 0xdcc01a4a, - 0x7b0b3d2c, 0xdcba1008, 0x7b0981c5, 0xdcb405dc, 0x7b07c612, 0xdcadfbc5, - 0x7b060a12, 0xdca7f1c5, - 0x7b044dc7, 0xdca1e7da, 0x7b029130, 0xdc9bde05, 0x7b00d44d, 0xdc95d446, - 0x7aff171e, 0xdc8fca9c, - 0x7afd59a4, 0xdc89c109, 0x7afb9bdd, 0xdc83b78b, 0x7af9ddcb, 0xdc7dae23, - 0x7af81f6c, 0xdc77a4d2, - 0x7af660c2, 0xdc719b96, 0x7af4a1cc, 0xdc6b9270, 0x7af2e28b, 0xdc658960, - 0x7af122fd, 0xdc5f8066, - 0x7aef6323, 0xdc597781, 0x7aeda2fe, 0xdc536eb3, 0x7aebe28d, 0xdc4d65fb, - 0x7aea21d0, 0xdc475d59, - 0x7ae860c7, 0xdc4154cd, 0x7ae69f73, 0xdc3b4c57, 0x7ae4ddd2, 0xdc3543f7, - 0x7ae31be6, 0xdc2f3bad, - 0x7ae159ae, 0xdc293379, 0x7adf972a, 0xdc232b5c, 0x7addd45b, 0xdc1d2354, - 0x7adc113f, 0xdc171b63, - 0x7ada4dd8, 0xdc111388, 0x7ad88a25, 0xdc0b0bc2, 0x7ad6c626, 0xdc050414, - 0x7ad501dc, 0xdbfefc7b, - 0x7ad33d45, 0xdbf8f4f8, 0x7ad17863, 0xdbf2ed8c, 0x7acfb336, 0xdbece636, - 0x7acdedbc, 0xdbe6def6, - 0x7acc27f7, 0xdbe0d7cd, 0x7aca61e6, 0xdbdad0b9, 0x7ac89b89, 0xdbd4c9bc, - 0x7ac6d4e0, 0xdbcec2d6, - 0x7ac50dec, 0xdbc8bc06, 0x7ac346ac, 0xdbc2b54c, 0x7ac17f20, 0xdbbcaea8, - 0x7abfb749, 0xdbb6a81b, - 0x7abdef25, 0xdbb0a1a4, 0x7abc26b7, 0xdbaa9b43, 0x7aba5dfc, 0xdba494f9, - 0x7ab894f6, 0xdb9e8ec6, - 0x7ab6cba4, 0xdb9888a8, 0x7ab50206, 0xdb9282a2, 0x7ab3381d, 0xdb8c7cb1, - 0x7ab16de7, 0xdb8676d8, - 0x7aafa367, 0xdb807114, 0x7aadd89a, 0xdb7a6b68, 0x7aac0d82, 0xdb7465d1, - 0x7aaa421e, 0xdb6e6052, - 0x7aa8766f, 0xdb685ae9, 0x7aa6aa74, 0xdb625596, 0x7aa4de2d, 0xdb5c505a, - 0x7aa3119a, 0xdb564b35, - 0x7aa144bc, 0xdb504626, 0x7a9f7793, 0xdb4a412e, 0x7a9daa1d, 0xdb443c4c, - 0x7a9bdc5c, 0xdb3e3781, - 0x7a9a0e50, 0xdb3832cd, 0x7a983ff7, 0xdb322e30, 0x7a967153, 0xdb2c29a9, - 0x7a94a264, 0xdb262539, - 0x7a92d329, 0xdb2020e0, 0x7a9103a2, 0xdb1a1c9d, 0x7a8f33d0, 0xdb141871, - 0x7a8d63b2, 0xdb0e145c, - 0x7a8b9348, 0xdb08105e, 0x7a89c293, 0xdb020c77, 0x7a87f192, 0xdafc08a6, - 0x7a862046, 0xdaf604ec, - 0x7a844eae, 0xdaf00149, 0x7a827ccb, 0xdae9fdbd, 0x7a80aa9c, 0xdae3fa48, - 0x7a7ed821, 0xdaddf6ea, - 0x7a7d055b, 0xdad7f3a2, 0x7a7b3249, 0xdad1f072, 0x7a795eec, 0xdacbed58, - 0x7a778b43, 0xdac5ea56, - 0x7a75b74f, 0xdabfe76a, 0x7a73e30f, 0xdab9e495, 0x7a720e84, 0xdab3e1d8, - 0x7a7039ad, 0xdaaddf31, - 0x7a6e648a, 0xdaa7dca1, 0x7a6c8f1c, 0xdaa1da29, 0x7a6ab963, 0xda9bd7c7, - 0x7a68e35e, 0xda95d57d, - 0x7a670d0d, 0xda8fd349, 0x7a653671, 0xda89d12d, 0x7a635f8a, 0xda83cf28, - 0x7a618857, 0xda7dcd3a, - 0x7a5fb0d8, 0xda77cb63, 0x7a5dd90e, 0xda71c9a3, 0x7a5c00f9, 0xda6bc7fa, - 0x7a5a2898, 0xda65c669, - 0x7a584feb, 0xda5fc4ef, 0x7a5676f3, 0xda59c38c, 0x7a549db0, 0xda53c240, - 0x7a52c421, 0xda4dc10b, - 0x7a50ea47, 0xda47bfee, 0x7a4f1021, 0xda41bee8, 0x7a4d35b0, 0xda3bbdf9, - 0x7a4b5af3, 0xda35bd22, - 0x7a497feb, 0xda2fbc61, 0x7a47a498, 0xda29bbb9, 0x7a45c8f9, 0xda23bb27, - 0x7a43ed0e, 0xda1dbaad, - 0x7a4210d8, 0xda17ba4a, 0x7a403457, 0xda11b9ff, 0x7a3e578b, 0xda0bb9cb, - 0x7a3c7a73, 0xda05b9ae, - 0x7a3a9d0f, 0xd9ffb9a9, 0x7a38bf60, 0xd9f9b9bb, 0x7a36e166, 0xd9f3b9e5, - 0x7a350321, 0xd9edba26, - 0x7a332490, 0xd9e7ba7f, 0x7a3145b3, 0xd9e1baef, 0x7a2f668c, 0xd9dbbb77, - 0x7a2d8719, 0xd9d5bc16, - 0x7a2ba75a, 0xd9cfbccd, 0x7a29c750, 0xd9c9bd9b, 0x7a27e6fb, 0xd9c3be81, - 0x7a26065b, 0xd9bdbf7e, - 0x7a24256f, 0xd9b7c094, 0x7a224437, 0xd9b1c1c0, 0x7a2062b5, 0xd9abc305, - 0x7a1e80e7, 0xd9a5c461, - 0x7a1c9ece, 0xd99fc5d4, 0x7a1abc69, 0xd999c75f, 0x7a18d9b9, 0xd993c902, - 0x7a16f6be, 0xd98dcabd, - 0x7a151378, 0xd987cc90, 0x7a132fe6, 0xd981ce7a, 0x7a114c09, 0xd97bd07c, - 0x7a0f67e0, 0xd975d295, - 0x7a0d836d, 0xd96fd4c7, 0x7a0b9eae, 0xd969d710, 0x7a09b9a4, 0xd963d971, - 0x7a07d44e, 0xd95ddbea, - 0x7a05eead, 0xd957de7a, 0x7a0408c1, 0xd951e123, 0x7a02228a, 0xd94be3e3, - 0x7a003c07, 0xd945e6bb, - 0x79fe5539, 0xd93fe9ab, 0x79fc6e20, 0xd939ecb3, 0x79fa86bc, 0xd933efd3, - 0x79f89f0c, 0xd92df30b, - 0x79f6b711, 0xd927f65b, 0x79f4cecb, 0xd921f9c3, 0x79f2e63a, 0xd91bfd43, - 0x79f0fd5d, 0xd91600da, - 0x79ef1436, 0xd910048a, 0x79ed2ac3, 0xd90a0852, 0x79eb4105, 0xd9040c32, - 0x79e956fb, 0xd8fe1029, - 0x79e76ca7, 0xd8f81439, 0x79e58207, 0xd8f21861, 0x79e3971c, 0xd8ec1ca1, - 0x79e1abe6, 0xd8e620fa, - 0x79dfc064, 0xd8e0256a, 0x79ddd498, 0xd8da29f2, 0x79dbe880, 0xd8d42e93, - 0x79d9fc1d, 0xd8ce334c, - 0x79d80f6f, 0xd8c8381d, 0x79d62276, 0xd8c23d06, 0x79d43532, 0xd8bc4207, - 0x79d247a2, 0xd8b64720, - 0x79d059c8, 0xd8b04c52, 0x79ce6ba2, 0xd8aa519c, 0x79cc7d31, 0xd8a456ff, - 0x79ca8e75, 0xd89e5c79, - 0x79c89f6e, 0xd898620c, 0x79c6b01b, 0xd89267b7, 0x79c4c07e, 0xd88c6d7b, - 0x79c2d095, 0xd8867356, - 0x79c0e062, 0xd880794b, 0x79beefe3, 0xd87a7f57, 0x79bcff19, 0xd874857c, - 0x79bb0e04, 0xd86e8bb9, - 0x79b91ca4, 0xd868920f, 0x79b72af9, 0xd862987d, 0x79b53903, 0xd85c9f04, - 0x79b346c2, 0xd856a5a3, - 0x79b15435, 0xd850ac5a, 0x79af615e, 0xd84ab32a, 0x79ad6e3c, 0xd844ba13, - 0x79ab7ace, 0xd83ec114, - 0x79a98715, 0xd838c82d, 0x79a79312, 0xd832cf5f, 0x79a59ec3, 0xd82cd6aa, - 0x79a3aa29, 0xd826de0d, - 0x79a1b545, 0xd820e589, 0x799fc015, 0xd81aed1d, 0x799dca9a, 0xd814f4ca, - 0x799bd4d4, 0xd80efc8f, - 0x7999dec4, 0xd809046e, 0x7997e868, 0xd8030c64, 0x7995f1c1, 0xd7fd1474, - 0x7993facf, 0xd7f71c9c, - 0x79920392, 0xd7f124dd, 0x79900c0a, 0xd7eb2d37, 0x798e1438, 0xd7e535a9, - 0x798c1c1a, 0xd7df3e34, - 0x798a23b1, 0xd7d946d8, 0x79882afd, 0xd7d34f94, 0x798631ff, 0xd7cd586a, - 0x798438b5, 0xd7c76158, - 0x79823f20, 0xd7c16a5f, 0x79804541, 0xd7bb737f, 0x797e4b16, 0xd7b57cb7, - 0x797c50a1, 0xd7af8609, - 0x797a55e0, 0xd7a98f73, 0x79785ad5, 0xd7a398f6, 0x79765f7f, 0xd79da293, - 0x797463de, 0xd797ac48, - 0x797267f2, 0xd791b616, 0x79706bbb, 0xd78bbffc, 0x796e6f39, 0xd785c9fc, - 0x796c726c, 0xd77fd415, - 0x796a7554, 0xd779de47, 0x796877f1, 0xd773e892, 0x79667a44, 0xd76df2f6, - 0x79647c4c, 0xd767fd72, - 0x79627e08, 0xd7620808, 0x79607f7a, 0xd75c12b7, 0x795e80a1, 0xd7561d7f, - 0x795c817d, 0xd7502860, - 0x795a820e, 0xd74a335b, 0x79588255, 0xd7443e6e, 0x79568250, 0xd73e499a, - 0x79548201, 0xd73854e0, - 0x79528167, 0xd732603f, 0x79508082, 0xd72c6bb6, 0x794e7f52, 0xd7267748, - 0x794c7dd7, 0xd72082f2, - 0x794a7c12, 0xd71a8eb5, 0x79487a01, 0xd7149a92, 0x794677a6, 0xd70ea688, - 0x79447500, 0xd708b297, - 0x79427210, 0xd702bec0, 0x79406ed4, 0xd6fccb01, 0x793e6b4e, 0xd6f6d75d, - 0x793c677d, 0xd6f0e3d1, - 0x793a6361, 0xd6eaf05f, 0x79385efa, 0xd6e4fd06, 0x79365a49, 0xd6df09c6, - 0x7934554d, 0xd6d916a0, - 0x79325006, 0xd6d32393, 0x79304a74, 0xd6cd30a0, 0x792e4497, 0xd6c73dc6, - 0x792c3e70, 0xd6c14b05, - 0x792a37fe, 0xd6bb585e, 0x79283141, 0xd6b565d0, 0x79262a3a, 0xd6af735c, - 0x792422e8, 0xd6a98101, - 0x79221b4b, 0xd6a38ec0, 0x79201363, 0xd69d9c98, 0x791e0b31, 0xd697aa8a, - 0x791c02b4, 0xd691b895, - 0x7919f9ec, 0xd68bc6ba, 0x7917f0d9, 0xd685d4f9, 0x7915e77c, 0xd67fe351, - 0x7913ddd4, 0xd679f1c2, - 0x7911d3e2, 0xd674004e, 0x790fc9a4, 0xd66e0ef2, 0x790dbf1d, 0xd6681db1, - 0x790bb44a, 0xd6622c89, - 0x7909a92d, 0xd65c3b7b, 0x79079dc5, 0xd6564a87, 0x79059212, 0xd65059ac, - 0x79038615, 0xd64a68eb, - 0x790179cd, 0xd6447844, 0x78ff6d3b, 0xd63e87b6, 0x78fd605d, 0xd6389742, - 0x78fb5336, 0xd632a6e8, - 0x78f945c3, 0xd62cb6a8, 0x78f73806, 0xd626c681, 0x78f529fe, 0xd620d675, - 0x78f31bac, 0xd61ae682, - 0x78f10d0f, 0xd614f6a9, 0x78eefe28, 0xd60f06ea, 0x78eceef6, 0xd6091745, - 0x78eadf79, 0xd60327b9, - 0x78e8cfb2, 0xd5fd3848, 0x78e6bfa0, 0xd5f748f0, 0x78e4af44, 0xd5f159b3, - 0x78e29e9d, 0xd5eb6a8f, - 0x78e08dab, 0xd5e57b85, 0x78de7c6f, 0xd5df8c96, 0x78dc6ae8, 0xd5d99dc0, - 0x78da5917, 0xd5d3af04, - 0x78d846fb, 0xd5cdc062, 0x78d63495, 0xd5c7d1db, 0x78d421e4, 0xd5c1e36d, - 0x78d20ee9, 0xd5bbf519, - 0x78cffba3, 0xd5b606e0, 0x78cde812, 0xd5b018c0, 0x78cbd437, 0xd5aa2abb, - 0x78c9c012, 0xd5a43cd0, - 0x78c7aba2, 0xd59e4eff, 0x78c596e7, 0xd5986148, 0x78c381e2, 0xd59273ab, - 0x78c16c93, 0xd58c8628, - 0x78bf56f9, 0xd58698c0, 0x78bd4114, 0xd580ab72, 0x78bb2ae5, 0xd57abe3d, - 0x78b9146c, 0xd574d124, - 0x78b6fda8, 0xd56ee424, 0x78b4e69a, 0xd568f73f, 0x78b2cf41, 0xd5630a74, - 0x78b0b79e, 0xd55d1dc3, - 0x78ae9fb0, 0xd557312d, 0x78ac8778, 0xd55144b0, 0x78aa6ef5, 0xd54b584f, - 0x78a85628, 0xd5456c07, - 0x78a63d11, 0xd53f7fda, 0x78a423af, 0xd53993c7, 0x78a20a03, 0xd533a7cf, - 0x789ff00c, 0xd52dbbf1, - 0x789dd5cb, 0xd527d02e, 0x789bbb3f, 0xd521e484, 0x7899a06a, 0xd51bf8f6, - 0x78978549, 0xd5160d82, - 0x789569df, 0xd5102228, 0x78934e2a, 0xd50a36e9, 0x7891322a, 0xd5044bc4, - 0x788f15e0, 0xd4fe60ba, - 0x788cf94c, 0xd4f875ca, 0x788adc6e, 0xd4f28af5, 0x7888bf45, 0xd4eca03a, - 0x7886a1d1, 0xd4e6b59a, - 0x78848414, 0xd4e0cb15, 0x7882660c, 0xd4dae0aa, 0x788047ba, 0xd4d4f65a, - 0x787e291d, 0xd4cf0c24, - 0x787c0a36, 0xd4c92209, 0x7879eb05, 0xd4c33809, 0x7877cb89, 0xd4bd4e23, - 0x7875abc3, 0xd4b76458, - 0x78738bb3, 0xd4b17aa8, 0x78716b59, 0xd4ab9112, 0x786f4ab4, 0xd4a5a798, - 0x786d29c5, 0xd49fbe37, - 0x786b088c, 0xd499d4f2, 0x7868e708, 0xd493ebc8, 0x7866c53a, 0xd48e02b8, - 0x7864a322, 0xd48819c3, - 0x786280bf, 0xd48230e9, 0x78605e13, 0xd47c4829, 0x785e3b1c, 0xd4765f85, - 0x785c17db, 0xd47076fb, - 0x7859f44f, 0xd46a8e8d, 0x7857d079, 0xd464a639, 0x7855ac5a, 0xd45ebe00, - 0x785387ef, 0xd458d5e2, - 0x7851633b, 0xd452eddf, 0x784f3e3c, 0xd44d05f6, 0x784d18f4, 0xd4471e29, - 0x784af361, 0xd4413677, - 0x7848cd83, 0xd43b4ee0, 0x7846a75c, 0xd4356763, 0x784480ea, 0xd42f8002, - 0x78425a2f, 0xd42998bc, - 0x78403329, 0xd423b191, 0x783e0bd9, 0xd41dca81, 0x783be43e, 0xd417e38c, - 0x7839bc5a, 0xd411fcb2, - 0x7837942b, 0xd40c15f3, 0x78356bb2, 0xd4062f4f, 0x783342ef, 0xd40048c6, - 0x783119e2, 0xd3fa6259, - 0x782ef08b, 0xd3f47c06, 0x782cc6ea, 0xd3ee95cf, 0x782a9cfe, 0xd3e8afb3, - 0x782872c8, 0xd3e2c9b2, - 0x78264849, 0xd3dce3cd, 0x78241d7f, 0xd3d6fe03, 0x7821f26b, 0xd3d11853, - 0x781fc70d, 0xd3cb32c0, - 0x781d9b65, 0xd3c54d47, 0x781b6f72, 0xd3bf67ea, 0x78194336, 0xd3b982a8, - 0x781716b0, 0xd3b39d81, - 0x7814e9df, 0xd3adb876, 0x7812bcc4, 0xd3a7d385, 0x78108f60, 0xd3a1eeb1, - 0x780e61b1, 0xd39c09f7, - 0x780c33b8, 0xd396255a, 0x780a0575, 0xd39040d7, 0x7807d6e9, 0xd38a5c70, - 0x7805a812, 0xd3847824, - 0x780378f1, 0xd37e93f4, 0x78014986, 0xd378afdf, 0x77ff19d1, 0xd372cbe6, - 0x77fce9d2, 0xd36ce808, - 0x77fab989, 0xd3670446, 0x77f888f6, 0xd361209f, 0x77f65819, 0xd35b3d13, - 0x77f426f2, 0xd35559a4, - 0x77f1f581, 0xd34f764f, 0x77efc3c5, 0xd3499317, 0x77ed91c0, 0xd343affa, - 0x77eb5f71, 0xd33dccf8, - 0x77e92cd9, 0xd337ea12, 0x77e6f9f6, 0xd3320748, 0x77e4c6c9, 0xd32c2499, - 0x77e29352, 0xd3264206, - 0x77e05f91, 0xd3205f8f, 0x77de2b86, 0xd31a7d33, 0x77dbf732, 0xd3149af3, - 0x77d9c293, 0xd30eb8cf, - 0x77d78daa, 0xd308d6c7, 0x77d55878, 0xd302f4da, 0x77d322fc, 0xd2fd1309, - 0x77d0ed35, 0xd2f73154, - 0x77ceb725, 0xd2f14fba, 0x77cc80cb, 0xd2eb6e3c, 0x77ca4a27, 0xd2e58cdb, - 0x77c81339, 0xd2dfab95, - 0x77c5dc01, 0xd2d9ca6a, 0x77c3a47f, 0xd2d3e95c, 0x77c16cb4, 0xd2ce0869, - 0x77bf349f, 0xd2c82793, - 0x77bcfc3f, 0xd2c246d8, 0x77bac396, 0xd2bc6639, 0x77b88aa3, 0xd2b685b6, - 0x77b65166, 0xd2b0a54f, - 0x77b417df, 0xd2aac504, 0x77b1de0f, 0xd2a4e4d5, 0x77afa3f5, 0xd29f04c2, - 0x77ad6990, 0xd29924cb, - 0x77ab2ee2, 0xd29344f0, 0x77a8f3ea, 0xd28d6531, 0x77a6b8a9, 0xd287858e, - 0x77a47d1d, 0xd281a607, - 0x77a24148, 0xd27bc69c, 0x77a00529, 0xd275e74d, 0x779dc8c0, 0xd270081b, - 0x779b8c0e, 0xd26a2904, - 0x77994f11, 0xd2644a0a, 0x779711cb, 0xd25e6b2b, 0x7794d43b, 0xd2588c69, - 0x77929661, 0xd252adc3, - 0x7790583e, 0xd24ccf39, 0x778e19d0, 0xd246f0cb, 0x778bdb19, 0xd241127a, - 0x77899c19, 0xd23b3444, - 0x77875cce, 0xd235562b, 0x77851d3a, 0xd22f782f, 0x7782dd5c, 0xd2299a4e, - 0x77809d35, 0xd223bc8a, - 0x777e5cc3, 0xd21ddee2, 0x777c1c08, 0xd2180156, 0x7779db03, 0xd21223e7, - 0x777799b5, 0xd20c4694, - 0x7775581d, 0xd206695d, 0x7773163b, 0xd2008c43, 0x7770d40f, 0xd1faaf45, - 0x776e919a, 0xd1f4d263, - 0x776c4edb, 0xd1eef59e, 0x776a0bd3, 0xd1e918f5, 0x7767c880, 0xd1e33c69, - 0x776584e5, 0xd1dd5ff9, - 0x776340ff, 0xd1d783a6, 0x7760fcd0, 0xd1d1a76f, 0x775eb857, 0xd1cbcb54, - 0x775c7395, 0xd1c5ef56, - 0x775a2e89, 0xd1c01375, 0x7757e933, 0xd1ba37b0, 0x7755a394, 0xd1b45c08, - 0x77535dab, 0xd1ae807c, - 0x77511778, 0xd1a8a50d, 0x774ed0fc, 0xd1a2c9ba, 0x774c8a36, 0xd19cee84, - 0x774a4327, 0xd197136b, - 0x7747fbce, 0xd191386e, 0x7745b42c, 0xd18b5d8e, 0x77436c40, 0xd18582ca, - 0x7741240a, 0xd17fa823, - 0x773edb8b, 0xd179cd99, 0x773c92c2, 0xd173f32c, 0x773a49b0, 0xd16e18db, - 0x77380054, 0xd1683ea7, - 0x7735b6af, 0xd1626490, 0x77336cc0, 0xd15c8a95, 0x77312287, 0xd156b0b7, - 0x772ed805, 0xd150d6f6, - 0x772c8d3a, 0xd14afd52, 0x772a4225, 0xd14523cb, 0x7727f6c6, 0xd13f4a60, - 0x7725ab1f, 0xd1397113, - 0x77235f2d, 0xd13397e2, 0x772112f2, 0xd12dbece, 0x771ec66e, 0xd127e5d7, - 0x771c79a0, 0xd1220cfc, - 0x771a2c88, 0xd11c343f, 0x7717df27, 0xd1165b9f, 0x7715917d, 0xd110831b, - 0x77134389, 0xd10aaab5, - 0x7710f54c, 0xd104d26b, 0x770ea6c5, 0xd0fefa3f, 0x770c57f5, 0xd0f9222f, - 0x770a08dc, 0xd0f34a3d, - 0x7707b979, 0xd0ed7267, 0x770569cc, 0xd0e79aaf, 0x770319d6, 0xd0e1c313, - 0x7700c997, 0xd0dbeb95, - 0x76fe790e, 0xd0d61434, 0x76fc283c, 0xd0d03cf0, 0x76f9d721, 0xd0ca65c9, - 0x76f785bc, 0xd0c48ebf, - 0x76f5340e, 0xd0beb7d2, 0x76f2e216, 0xd0b8e102, 0x76f08fd5, 0xd0b30a50, - 0x76ee3d4b, 0xd0ad33ba, - 0x76ebea77, 0xd0a75d42, 0x76e9975a, 0xd0a186e7, 0x76e743f4, 0xd09bb0aa, - 0x76e4f044, 0xd095da89, - 0x76e29c4b, 0xd0900486, 0x76e04808, 0xd08a2ea0, 0x76ddf37c, 0xd08458d7, - 0x76db9ea7, 0xd07e832c, - 0x76d94989, 0xd078ad9e, 0x76d6f421, 0xd072d82d, 0x76d49e70, 0xd06d02da, - 0x76d24876, 0xd0672da3, - 0x76cff232, 0xd061588b, 0x76cd9ba5, 0xd05b838f, 0x76cb44cf, 0xd055aeb1, - 0x76c8edb0, 0xd04fd9f1, - 0x76c69647, 0xd04a054e, 0x76c43e95, 0xd04430c8, 0x76c1e699, 0xd03e5c60, - 0x76bf8e55, 0xd0388815, - 0x76bd35c7, 0xd032b3e7, 0x76badcf0, 0xd02cdfd8, 0x76b883d0, 0xd0270be5, - 0x76b62a66, 0xd0213810, - 0x76b3d0b4, 0xd01b6459, 0x76b176b8, 0xd01590bf, 0x76af1c72, 0xd00fbd43, - 0x76acc1e4, 0xd009e9e4, - 0x76aa670d, 0xd00416a3, 0x76a80bec, 0xcffe4380, 0x76a5b082, 0xcff8707a, - 0x76a354cf, 0xcff29d92, - 0x76a0f8d2, 0xcfeccac7, 0x769e9c8d, 0xcfe6f81a, 0x769c3ffe, 0xcfe1258b, - 0x7699e326, 0xcfdb531a, - 0x76978605, 0xcfd580c6, 0x7695289b, 0xcfcfae8f, 0x7692cae8, 0xcfc9dc77, - 0x76906ceb, 0xcfc40a7c, - 0x768e0ea6, 0xcfbe389f, 0x768bb017, 0xcfb866e0, 0x7689513f, 0xcfb2953f, - 0x7686f21e, 0xcfacc3bb, - 0x768492b4, 0xcfa6f255, 0x76823301, 0xcfa1210d, 0x767fd304, 0xcf9b4fe3, - 0x767d72bf, 0xcf957ed7, - 0x767b1231, 0xcf8fade9, 0x7678b159, 0xcf89dd18, 0x76765038, 0xcf840c65, - 0x7673eecf, 0xcf7e3bd1, - 0x76718d1c, 0xcf786b5a, 0x766f2b20, 0xcf729b01, 0x766cc8db, 0xcf6ccac6, - 0x766a664d, 0xcf66faa9, - 0x76680376, 0xcf612aaa, 0x7665a056, 0xcf5b5ac9, 0x76633ced, 0xcf558b06, - 0x7660d93b, 0xcf4fbb61, - 0x765e7540, 0xcf49ebda, 0x765c10fc, 0xcf441c71, 0x7659ac6f, 0xcf3e4d26, - 0x76574798, 0xcf387dfa, - 0x7654e279, 0xcf32aeeb, 0x76527d11, 0xcf2cdffa, 0x76501760, 0xcf271128, - 0x764db166, 0xcf214274, - 0x764b4b23, 0xcf1b73de, 0x7648e497, 0xcf15a566, 0x76467dc2, 0xcf0fd70c, - 0x764416a4, 0xcf0a08d0, - 0x7641af3d, 0xcf043ab3, 0x763f478d, 0xcefe6cb3, 0x763cdf94, 0xcef89ed2, - 0x763a7752, 0xcef2d110, - 0x76380ec8, 0xceed036b, 0x7635a5f4, 0xcee735e5, 0x76333cd8, 0xcee1687d, - 0x7630d372, 0xcedb9b33, - 0x762e69c4, 0xced5ce08, 0x762bffcd, 0xced000fb, 0x7629958c, 0xceca340c, - 0x76272b03, 0xcec4673c, - 0x7624c031, 0xcebe9a8a, 0x76225517, 0xceb8cdf7, 0x761fe9b3, 0xceb30181, - 0x761d7e06, 0xcead352b, - 0x761b1211, 0xcea768f2, 0x7618a5d3, 0xcea19cd8, 0x7616394c, 0xce9bd0dd, - 0x7613cc7c, 0xce960500, - 0x76115f63, 0xce903942, 0x760ef201, 0xce8a6da2, 0x760c8457, 0xce84a220, - 0x760a1664, 0xce7ed6bd, - 0x7607a828, 0xce790b79, 0x760539a3, 0xce734053, 0x7602cad5, 0xce6d754c, - 0x76005bbf, 0xce67aa63, - 0x75fdec60, 0xce61df99, 0x75fb7cb8, 0xce5c14ed, 0x75f90cc7, 0xce564a60, - 0x75f69c8d, 0xce507ff2, - 0x75f42c0b, 0xce4ab5a2, 0x75f1bb40, 0xce44eb71, 0x75ef4a2c, 0xce3f215f, - 0x75ecd8cf, 0xce39576c, - 0x75ea672a, 0xce338d97, 0x75e7f53c, 0xce2dc3e1, 0x75e58305, 0xce27fa49, - 0x75e31086, 0xce2230d0, - 0x75e09dbd, 0xce1c6777, 0x75de2aac, 0xce169e3b, 0x75dbb753, 0xce10d51f, - 0x75d943b0, 0xce0b0c21, - 0x75d6cfc5, 0xce054343, 0x75d45b92, 0xcdff7a83, 0x75d1e715, 0xcdf9b1e2, - 0x75cf7250, 0xcdf3e95f, - 0x75ccfd42, 0xcdee20fc, 0x75ca87ec, 0xcde858b8, 0x75c8124d, 0xcde29092, - 0x75c59c65, 0xcddcc88b, - 0x75c32634, 0xcdd700a4, 0x75c0afbb, 0xcdd138db, 0x75be38fa, 0xcdcb7131, - 0x75bbc1ef, 0xcdc5a9a6, - 0x75b94a9c, 0xcdbfe23a, 0x75b6d301, 0xcdba1aee, 0x75b45b1d, 0xcdb453c0, - 0x75b1e2f0, 0xcdae8cb1, - 0x75af6a7b, 0xcda8c5c1, 0x75acf1bd, 0xcda2fef0, 0x75aa78b6, 0xcd9d383f, - 0x75a7ff67, 0xcd9771ac, - 0x75a585cf, 0xcd91ab39, 0x75a30bef, 0xcd8be4e4, 0x75a091c6, 0xcd861eaf, - 0x759e1755, 0xcd805899, - 0x759b9c9b, 0xcd7a92a2, 0x75992198, 0xcd74ccca, 0x7596a64d, 0xcd6f0711, - 0x75942ab9, 0xcd694178, - 0x7591aedd, 0xcd637bfe, 0x758f32b9, 0xcd5db6a3, 0x758cb64c, 0xcd57f167, - 0x758a3996, 0xcd522c4a, - 0x7587bc98, 0xcd4c674d, 0x75853f51, 0xcd46a26f, 0x7582c1c2, 0xcd40ddb0, - 0x758043ea, 0xcd3b1911, - 0x757dc5ca, 0xcd355491, 0x757b4762, 0xcd2f9030, 0x7578c8b0, 0xcd29cbee, - 0x757649b7, 0xcd2407cc, - 0x7573ca75, 0xcd1e43ca, 0x75714aea, 0xcd187fe6, 0x756ecb18, 0xcd12bc22, - 0x756c4afc, 0xcd0cf87e, - 0x7569ca99, 0xcd0734f9, 0x756749ec, 0xcd017193, 0x7564c8f8, 0xccfbae4d, - 0x756247bb, 0xccf5eb26, - 0x755fc635, 0xccf0281f, 0x755d4467, 0xccea6538, 0x755ac251, 0xcce4a26f, - 0x75583ff3, 0xccdedfc7, - 0x7555bd4c, 0xccd91d3d, 0x75533a5c, 0xccd35ad4, 0x7550b725, 0xcccd988a, - 0x754e33a4, 0xccc7d65f, - 0x754bafdc, 0xccc21455, 0x75492bcb, 0xccbc5269, 0x7546a772, 0xccb6909e, - 0x754422d0, 0xccb0cef2, - 0x75419de7, 0xccab0d65, 0x753f18b4, 0xcca54bf9, 0x753c933a, 0xcc9f8aac, - 0x753a0d77, 0xcc99c97e, - 0x7537876c, 0xcc940871, 0x75350118, 0xcc8e4783, 0x75327a7d, 0xcc8886b5, - 0x752ff399, 0xcc82c607, - 0x752d6c6c, 0xcc7d0578, 0x752ae4f8, 0xcc774509, 0x75285d3b, 0xcc7184ba, - 0x7525d536, 0xcc6bc48b, - 0x75234ce8, 0xcc66047b, 0x7520c453, 0xcc60448c, 0x751e3b75, 0xcc5a84bc, - 0x751bb24f, 0xcc54c50c, - 0x751928e0, 0xcc4f057c, 0x75169f2a, 0xcc49460c, 0x7514152b, 0xcc4386bc, - 0x75118ae4, 0xcc3dc78b, - 0x750f0054, 0xcc38087b, 0x750c757d, 0xcc32498a, 0x7509ea5d, 0xcc2c8aba, - 0x75075ef5, 0xcc26cc09, - 0x7504d345, 0xcc210d79, 0x7502474d, 0xcc1b4f08, 0x74ffbb0d, 0xcc1590b8, - 0x74fd2e84, 0xcc0fd287, - 0x74faa1b3, 0xcc0a1477, 0x74f8149a, 0xcc045686, 0x74f58739, 0xcbfe98b6, - 0x74f2f990, 0xcbf8db05, - 0x74f06b9e, 0xcbf31d75, 0x74eddd65, 0xcbed6005, 0x74eb4ee3, 0xcbe7a2b5, - 0x74e8c01a, 0xcbe1e585, - 0x74e63108, 0xcbdc2876, 0x74e3a1ae, 0xcbd66b86, 0x74e1120c, 0xcbd0aeb7, - 0x74de8221, 0xcbcaf208, - 0x74dbf1ef, 0xcbc53579, 0x74d96175, 0xcbbf790a, 0x74d6d0b2, 0xcbb9bcbb, - 0x74d43fa8, 0xcbb4008d, - 0x74d1ae55, 0xcbae447f, 0x74cf1cbb, 0xcba88891, 0x74cc8ad8, 0xcba2ccc4, - 0x74c9f8ad, 0xcb9d1117, - 0x74c7663a, 0xcb97558a, 0x74c4d380, 0xcb919a1d, 0x74c2407d, 0xcb8bded1, - 0x74bfad32, 0xcb8623a5, - 0x74bd199f, 0xcb80689a, 0x74ba85c4, 0xcb7aadaf, 0x74b7f1a1, 0xcb74f2e4, - 0x74b55d36, 0xcb6f383a, - 0x74b2c884, 0xcb697db0, 0x74b03389, 0xcb63c347, 0x74ad9e46, 0xcb5e08fe, - 0x74ab08bb, 0xcb584ed6, - 0x74a872e8, 0xcb5294ce, 0x74a5dccd, 0xcb4cdae6, 0x74a3466b, 0xcb47211f, - 0x74a0afc0, 0xcb416779, - 0x749e18cd, 0xcb3badf3, 0x749b8193, 0xcb35f48d, 0x7498ea11, 0xcb303b49, - 0x74965246, 0xcb2a8224, - 0x7493ba34, 0xcb24c921, 0x749121da, 0xcb1f103e, 0x748e8938, 0xcb19577b, - 0x748bf04d, 0xcb139ed9, - 0x7489571c, 0xcb0de658, 0x7486bda2, 0xcb082df8, 0x748423e0, 0xcb0275b8, - 0x748189d7, 0xcafcbd99, - 0x747eef85, 0xcaf7059a, 0x747c54ec, 0xcaf14dbd, 0x7479ba0b, 0xcaeb9600, - 0x74771ee2, 0xcae5de64, - 0x74748371, 0xcae026e8, 0x7471e7b8, 0xcada6f8d, 0x746f4bb8, 0xcad4b853, - 0x746caf70, 0xcacf013a, - 0x746a12df, 0xcac94a42, 0x74677608, 0xcac3936b, 0x7464d8e8, 0xcabddcb4, - 0x74623b80, 0xcab8261e, - 0x745f9dd1, 0xcab26fa9, 0x745cffda, 0xcaacb955, 0x745a619b, 0xcaa70322, - 0x7457c314, 0xcaa14d10, - 0x74552446, 0xca9b971e, 0x74528530, 0xca95e14e, 0x744fe5d2, 0xca902b9f, - 0x744d462c, 0xca8a7610, - 0x744aa63f, 0xca84c0a3, 0x7448060a, 0xca7f0b56, 0x7445658d, 0xca79562b, - 0x7442c4c8, 0xca73a120, - 0x744023bc, 0xca6dec37, 0x743d8268, 0xca68376e, 0x743ae0cc, 0xca6282c7, - 0x74383ee9, 0xca5cce40, - 0x74359cbd, 0xca5719db, 0x7432fa4b, 0xca516597, 0x74305790, 0xca4bb174, - 0x742db48e, 0xca45fd72, - 0x742b1144, 0xca404992, 0x74286db3, 0xca3a95d2, 0x7425c9da, 0xca34e234, - 0x742325b9, 0xca2f2eb6, - 0x74208150, 0xca297b5a, 0x741ddca0, 0xca23c820, 0x741b37a9, 0xca1e1506, - 0x74189269, 0xca18620e, - 0x7415ece2, 0xca12af37, 0x74134714, 0xca0cfc81, 0x7410a0fe, 0xca0749ec, - 0x740dfaa0, 0xca019779, - 0x740b53fb, 0xc9fbe527, 0x7408ad0e, 0xc9f632f6, 0x740605d9, 0xc9f080e7, - 0x74035e5d, 0xc9eacef9, - 0x7400b69a, 0xc9e51d2d, 0x73fe0e8f, 0xc9df6b81, 0x73fb663c, 0xc9d9b9f7, - 0x73f8bda2, 0xc9d4088f, - 0x73f614c0, 0xc9ce5748, 0x73f36b97, 0xc9c8a622, 0x73f0c226, 0xc9c2f51e, - 0x73ee186e, 0xc9bd443c, - 0x73eb6e6e, 0xc9b7937a, 0x73e8c426, 0xc9b1e2db, 0x73e61997, 0xc9ac325d, - 0x73e36ec1, 0xc9a68200, - 0x73e0c3a3, 0xc9a0d1c5, 0x73de183e, 0xc99b21ab, 0x73db6c91, 0xc99571b3, - 0x73d8c09d, 0xc98fc1dc, - 0x73d61461, 0xc98a1227, 0x73d367de, 0xc9846294, 0x73d0bb13, 0xc97eb322, - 0x73ce0e01, 0xc97903d2, - 0x73cb60a8, 0xc97354a4, 0x73c8b307, 0xc96da597, 0x73c6051f, 0xc967f6ac, - 0x73c356ef, 0xc96247e2, - 0x73c0a878, 0xc95c993a, 0x73bdf9b9, 0xc956eab4, 0x73bb4ab3, 0xc9513c50, - 0x73b89b66, 0xc94b8e0d, - 0x73b5ebd1, 0xc945dfec, 0x73b33bf5, 0xc94031ed, 0x73b08bd1, 0xc93a8410, - 0x73addb67, 0xc934d654, - 0x73ab2ab4, 0xc92f28ba, 0x73a879bb, 0xc9297b42, 0x73a5c87a, 0xc923cdec, - 0x73a316f2, 0xc91e20b8, - 0x73a06522, 0xc91873a5, 0x739db30b, 0xc912c6b5, 0x739b00ad, 0xc90d19e6, - 0x73984e07, 0xc9076d39, - 0x73959b1b, 0xc901c0ae, 0x7392e7e6, 0xc8fc1445, 0x7390346b, 0xc8f667fe, - 0x738d80a8, 0xc8f0bbd9, - 0x738acc9e, 0xc8eb0fd6, 0x7388184d, 0xc8e563f5, 0x738563b5, 0xc8dfb836, - 0x7382aed5, 0xc8da0c99, - 0x737ff9ae, 0xc8d4611d, 0x737d4440, 0xc8ceb5c4, 0x737a8e8a, 0xc8c90a8d, - 0x7377d88d, 0xc8c35f78, - 0x73752249, 0xc8bdb485, 0x73726bbe, 0xc8b809b4, 0x736fb4ec, 0xc8b25f06, - 0x736cfdd2, 0xc8acb479, - 0x736a4671, 0xc8a70a0e, 0x73678ec9, 0xc8a15fc6, 0x7364d6da, 0xc89bb5a0, - 0x73621ea4, 0xc8960b9c, - 0x735f6626, 0xc89061ba, 0x735cad61, 0xc88ab7fa, 0x7359f456, 0xc8850e5d, - 0x73573b03, 0xc87f64e2, - 0x73548168, 0xc879bb89, 0x7351c787, 0xc8741252, 0x734f0d5f, 0xc86e693d, - 0x734c52ef, 0xc868c04b, - 0x73499838, 0xc863177b, 0x7346dd3a, 0xc85d6ece, 0x734421f6, 0xc857c642, - 0x7341666a, 0xc8521dd9, - 0x733eaa96, 0xc84c7593, 0x733bee7c, 0xc846cd6e, 0x7339321b, 0xc841256d, - 0x73367572, 0xc83b7d8d, - 0x7333b883, 0xc835d5d0, 0x7330fb4d, 0xc8302e35, 0x732e3dcf, 0xc82a86bd, - 0x732b800a, 0xc824df67, - 0x7328c1ff, 0xc81f3834, 0x732603ac, 0xc8199123, 0x73234512, 0xc813ea35, - 0x73208632, 0xc80e4369, - 0x731dc70a, 0xc8089cbf, 0x731b079b, 0xc802f638, 0x731847e5, 0xc7fd4fd4, - 0x731587e8, 0xc7f7a992, - 0x7312c7a5, 0xc7f20373, 0x7310071a, 0xc7ec5d76, 0x730d4648, 0xc7e6b79c, - 0x730a8530, 0xc7e111e5, - 0x7307c3d0, 0xc7db6c50, 0x73050229, 0xc7d5c6de, 0x7302403c, 0xc7d0218e, - 0x72ff7e07, 0xc7ca7c61, - 0x72fcbb8c, 0xc7c4d757, 0x72f9f8c9, 0xc7bf3270, 0x72f735c0, 0xc7b98dab, - 0x72f47270, 0xc7b3e909, - 0x72f1aed9, 0xc7ae4489, 0x72eeeafb, 0xc7a8a02c, 0x72ec26d6, 0xc7a2fbf3, - 0x72e9626a, 0xc79d57db, - 0x72e69db7, 0xc797b3e7, 0x72e3d8be, 0xc7921015, 0x72e1137d, 0xc78c6c67, - 0x72de4df6, 0xc786c8db, - 0x72db8828, 0xc7812572, 0x72d8c213, 0xc77b822b, 0x72d5fbb7, 0xc775df08, - 0x72d33514, 0xc7703c08, - 0x72d06e2b, 0xc76a992a, 0x72cda6fb, 0xc764f66f, 0x72cadf83, 0xc75f53d7, - 0x72c817c6, 0xc759b163, - 0x72c54fc1, 0xc7540f11, 0x72c28775, 0xc74e6ce2, 0x72bfbee3, 0xc748cad6, - 0x72bcf60a, 0xc74328ed, - 0x72ba2cea, 0xc73d8727, 0x72b76383, 0xc737e584, 0x72b499d6, 0xc7324404, - 0x72b1cfe1, 0xc72ca2a7, - 0x72af05a7, 0xc727016d, 0x72ac3b25, 0xc7216056, 0x72a9705c, 0xc71bbf62, - 0x72a6a54d, 0xc7161e92, - 0x72a3d9f7, 0xc7107de4, 0x72a10e5b, 0xc70add5a, 0x729e4277, 0xc7053cf2, - 0x729b764d, 0xc6ff9cae, - 0x7298a9dd, 0xc6f9fc8d, 0x7295dd25, 0xc6f45c8f, 0x72931027, 0xc6eebcb5, - 0x729042e3, 0xc6e91cfd, - 0x728d7557, 0xc6e37d69, 0x728aa785, 0xc6ddddf8, 0x7287d96c, 0xc6d83eab, - 0x72850b0d, 0xc6d29f80, - 0x72823c67, 0xc6cd0079, 0x727f6d7a, 0xc6c76195, 0x727c9e47, 0xc6c1c2d4, - 0x7279cecd, 0xc6bc2437, - 0x7276ff0d, 0xc6b685bd, 0x72742f05, 0xc6b0e767, 0x72715eb8, 0xc6ab4933, - 0x726e8e23, 0xc6a5ab23, - 0x726bbd48, 0xc6a00d37, 0x7268ec27, 0xc69a6f6e, 0x72661abf, 0xc694d1c8, - 0x72634910, 0xc68f3446, - 0x7260771b, 0xc68996e7, 0x725da4df, 0xc683f9ab, 0x725ad25d, 0xc67e5c93, - 0x7257ff94, 0xc678bf9f, - 0x72552c85, 0xc67322ce, 0x7252592f, 0xc66d8620, 0x724f8593, 0xc667e996, - 0x724cb1b0, 0xc6624d30, - 0x7249dd86, 0xc65cb0ed, 0x72470916, 0xc65714cd, 0x72443460, 0xc65178d1, - 0x72415f63, 0xc64bdcf9, - 0x723e8a20, 0xc6464144, 0x723bb496, 0xc640a5b3, 0x7238dec5, 0xc63b0a46, - 0x723608af, 0xc6356efc, - 0x72333251, 0xc62fd3d6, 0x72305bae, 0xc62a38d4, 0x722d84c4, 0xc6249df5, - 0x722aad93, 0xc61f033a, - 0x7227d61c, 0xc61968a2, 0x7224fe5f, 0xc613ce2f, 0x7222265b, 0xc60e33df, - 0x721f4e11, 0xc60899b2, - 0x721c7580, 0xc602ffaa, 0x72199ca9, 0xc5fd65c5, 0x7216c38c, 0xc5f7cc04, - 0x7213ea28, 0xc5f23267, - 0x7211107e, 0xc5ec98ee, 0x720e368d, 0xc5e6ff98, 0x720b5c57, 0xc5e16667, - 0x720881d9, 0xc5dbcd59, - 0x7205a716, 0xc5d6346f, 0x7202cc0c, 0xc5d09ba9, 0x71fff0bc, 0xc5cb0307, - 0x71fd1525, 0xc5c56a89, - 0x71fa3949, 0xc5bfd22e, 0x71f75d25, 0xc5ba39f8, 0x71f480bc, 0xc5b4a1e5, - 0x71f1a40c, 0xc5af09f7, - 0x71eec716, 0xc5a9722c, 0x71ebe9da, 0xc5a3da86, 0x71e90c57, 0xc59e4303, - 0x71e62e8f, 0xc598aba5, - 0x71e35080, 0xc593146a, 0x71e0722a, 0xc58d7d54, 0x71dd938f, 0xc587e661, - 0x71dab4ad, 0xc5824f93, - 0x71d7d585, 0xc57cb8e9, 0x71d4f617, 0xc5772263, 0x71d21662, 0xc5718c00, - 0x71cf3667, 0xc56bf5c2, - 0x71cc5626, 0xc5665fa9, 0x71c9759f, 0xc560c9b3, 0x71c694d2, 0xc55b33e2, - 0x71c3b3bf, 0xc5559e34, - 0x71c0d265, 0xc55008ab, 0x71bdf0c5, 0xc54a7346, 0x71bb0edf, 0xc544de05, - 0x71b82cb3, 0xc53f48e9, - 0x71b54a41, 0xc539b3f1, 0x71b26788, 0xc5341f1d, 0x71af848a, 0xc52e8a6d, - 0x71aca145, 0xc528f5e1, - 0x71a9bdba, 0xc523617a, 0x71a6d9e9, 0xc51dcd37, 0x71a3f5d2, 0xc5183919, - 0x71a11175, 0xc512a51f, - 0x719e2cd2, 0xc50d1149, 0x719b47e9, 0xc5077d97, 0x719862b9, 0xc501ea0a, - 0x71957d44, 0xc4fc56a2, - 0x71929789, 0xc4f6c35d, 0x718fb187, 0xc4f1303d, 0x718ccb3f, 0xc4eb9d42, - 0x7189e4b2, 0xc4e60a6b, - 0x7186fdde, 0xc4e077b8, 0x718416c4, 0xc4dae52a, 0x71812f65, 0xc4d552c1, - 0x717e47bf, 0xc4cfc07c, - 0x717b5fd3, 0xc4ca2e5b, 0x717877a1, 0xc4c49c5f, 0x71758f29, 0xc4bf0a87, - 0x7172a66c, 0xc4b978d4, - 0x716fbd68, 0xc4b3e746, 0x716cd41e, 0xc4ae55dc, 0x7169ea8f, 0xc4a8c497, - 0x716700b9, 0xc4a33376, - 0x7164169d, 0xc49da27a, 0x71612c3c, 0xc49811a3, 0x715e4194, 0xc49280f0, - 0x715b56a7, 0xc48cf062, - 0x71586b74, 0xc4875ff9, 0x71557ffa, 0xc481cfb4, 0x7152943b, 0xc47c3f94, - 0x714fa836, 0xc476af98, - 0x714cbbeb, 0xc4711fc2, 0x7149cf5a, 0xc46b9010, 0x7146e284, 0xc4660083, - 0x7143f567, 0xc460711b, - 0x71410805, 0xc45ae1d7, 0x713e1a5c, 0xc45552b8, 0x713b2c6e, 0xc44fc3be, - 0x71383e3a, 0xc44a34e9, - 0x71354fc0, 0xc444a639, 0x71326101, 0xc43f17ad, 0x712f71fb, 0xc4398947, - 0x712c82b0, 0xc433fb05, - 0x7129931f, 0xc42e6ce8, 0x7126a348, 0xc428def0, 0x7123b32b, 0xc423511d, - 0x7120c2c8, 0xc41dc36f, - 0x711dd220, 0xc41835e6, 0x711ae132, 0xc412a882, 0x7117effe, 0xc40d1b42, - 0x7114fe84, 0xc4078e28, - 0x71120cc5, 0xc4020133, 0x710f1ac0, 0xc3fc7462, 0x710c2875, 0xc3f6e7b7, - 0x710935e4, 0xc3f15b31, - 0x7106430e, 0xc3ebced0, 0x71034ff2, 0xc3e64294, 0x71005c90, 0xc3e0b67d, - 0x70fd68e9, 0xc3db2a8b, - 0x70fa74fc, 0xc3d59ebe, 0x70f780c9, 0xc3d01316, 0x70f48c50, 0xc3ca8793, - 0x70f19792, 0xc3c4fc36, - 0x70eea28e, 0xc3bf70fd, 0x70ebad45, 0xc3b9e5ea, 0x70e8b7b5, 0xc3b45afc, - 0x70e5c1e1, 0xc3aed034, - 0x70e2cbc6, 0xc3a94590, 0x70dfd566, 0xc3a3bb12, 0x70dcdec0, 0xc39e30b8, - 0x70d9e7d5, 0xc398a685, - 0x70d6f0a4, 0xc3931c76, 0x70d3f92d, 0xc38d928d, 0x70d10171, 0xc38808c9, - 0x70ce096f, 0xc3827f2a, - 0x70cb1128, 0xc37cf5b0, 0x70c8189b, 0xc3776c5c, 0x70c51fc8, 0xc371e32d, - 0x70c226b0, 0xc36c5a24, - 0x70bf2d53, 0xc366d140, 0x70bc33b0, 0xc3614881, 0x70b939c7, 0xc35bbfe8, - 0x70b63f99, 0xc3563774, - 0x70b34525, 0xc350af26, 0x70b04a6b, 0xc34b26fc, 0x70ad4f6d, 0xc3459ef9, - 0x70aa5428, 0xc340171b, - 0x70a7589f, 0xc33a8f62, 0x70a45ccf, 0xc33507cf, 0x70a160ba, 0xc32f8061, - 0x709e6460, 0xc329f919, - 0x709b67c0, 0xc32471f7, 0x70986adb, 0xc31eeaf9, 0x70956db1, 0xc3196422, - 0x70927041, 0xc313dd70, - 0x708f728b, 0xc30e56e4, 0x708c7490, 0xc308d07d, 0x70897650, 0xc3034a3c, - 0x708677ca, 0xc2fdc420, - 0x708378ff, 0xc2f83e2a, 0x708079ee, 0xc2f2b85a, 0x707d7a98, 0xc2ed32af, - 0x707a7afd, 0xc2e7ad2a, - 0x70777b1c, 0xc2e227cb, 0x70747af6, 0xc2dca291, 0x70717a8a, 0xc2d71d7e, - 0x706e79d9, 0xc2d1988f, - 0x706b78e3, 0xc2cc13c7, 0x706877a7, 0xc2c68f24, 0x70657626, 0xc2c10aa7, - 0x70627460, 0xc2bb8650, - 0x705f7255, 0xc2b6021f, 0x705c7004, 0xc2b07e14, 0x70596d6d, 0xc2aafa2e, - 0x70566a92, 0xc2a5766e, - 0x70536771, 0xc29ff2d4, 0x7050640b, 0xc29a6f60, 0x704d6060, 0xc294ec12, - 0x704a5c6f, 0xc28f68e9, - 0x70475839, 0xc289e5e7, 0x704453be, 0xc284630a, 0x70414efd, 0xc27ee054, - 0x703e49f8, 0xc2795dc3, - 0x703b44ad, 0xc273db58, 0x70383f1d, 0xc26e5913, 0x70353947, 0xc268d6f5, - 0x7032332d, 0xc26354fc, - 0x702f2ccd, 0xc25dd329, 0x702c2628, 0xc258517c, 0x70291f3e, 0xc252cff5, - 0x7026180e, 0xc24d4e95, - 0x7023109a, 0xc247cd5a, 0x702008e0, 0xc2424c46, 0x701d00e1, 0xc23ccb57, - 0x7019f89d, 0xc2374a8f, - 0x7016f014, 0xc231c9ec, 0x7013e746, 0xc22c4970, 0x7010de32, 0xc226c91a, - 0x700dd4da, 0xc22148ea, - 0x700acb3c, 0xc21bc8e1, 0x7007c159, 0xc21648fd, 0x7004b731, 0xc210c940, - 0x7001acc4, 0xc20b49a9, - 0x6ffea212, 0xc205ca38, 0x6ffb971b, 0xc2004aed, 0x6ff88bde, 0xc1facbc9, - 0x6ff5805d, 0xc1f54cca, - 0x6ff27497, 0xc1efcdf3, 0x6fef688b, 0xc1ea4f41, 0x6fec5c3b, 0xc1e4d0b6, - 0x6fe94fa5, 0xc1df5251, - 0x6fe642ca, 0xc1d9d412, 0x6fe335ab, 0xc1d455f9, 0x6fe02846, 0xc1ced807, - 0x6fdd1a9c, 0xc1c95a3c, - 0x6fda0cae, 0xc1c3dc97, 0x6fd6fe7a, 0xc1be5f18, 0x6fd3f001, 0xc1b8e1bf, - 0x6fd0e144, 0xc1b3648d, - 0x6fcdd241, 0xc1ade781, 0x6fcac2fa, 0xc1a86a9c, 0x6fc7b36d, 0xc1a2edde, - 0x6fc4a39c, 0xc19d7145, - 0x6fc19385, 0xc197f4d4, 0x6fbe832a, 0xc1927888, 0x6fbb728a, 0xc18cfc63, - 0x6fb861a4, 0xc1878065, - 0x6fb5507a, 0xc182048d, 0x6fb23f0b, 0xc17c88dc, 0x6faf2d57, 0xc1770d52, - 0x6fac1b5f, 0xc17191ee, - 0x6fa90921, 0xc16c16b0, 0x6fa5f69e, 0xc1669b99, 0x6fa2e3d7, 0xc16120a9, - 0x6f9fd0cb, 0xc15ba5df, - 0x6f9cbd79, 0xc1562b3d, 0x6f99a9e3, 0xc150b0c0, 0x6f969608, 0xc14b366b, - 0x6f9381e9, 0xc145bc3c, - 0x6f906d84, 0xc1404233, 0x6f8d58db, 0xc13ac852, 0x6f8a43ed, 0xc1354e97, - 0x6f872eba, 0xc12fd503, - 0x6f841942, 0xc12a5b95, 0x6f810386, 0xc124e24f, 0x6f7ded84, 0xc11f692f, - 0x6f7ad73e, 0xc119f036, - 0x6f77c0b3, 0xc1147764, 0x6f74a9e4, 0xc10efeb8, 0x6f7192cf, 0xc1098634, - 0x6f6e7b76, 0xc1040dd6, - 0x6f6b63d8, 0xc0fe959f, 0x6f684bf6, 0xc0f91d8f, 0x6f6533ce, 0xc0f3a5a6, - 0x6f621b62, 0xc0ee2de3, - 0x6f5f02b2, 0xc0e8b648, 0x6f5be9bc, 0xc0e33ed4, 0x6f58d082, 0xc0ddc786, - 0x6f55b703, 0xc0d8505f, - 0x6f529d40, 0xc0d2d960, 0x6f4f8338, 0xc0cd6287, 0x6f4c68eb, 0xc0c7ebd6, - 0x6f494e5a, 0xc0c2754b, - 0x6f463383, 0xc0bcfee7, 0x6f431869, 0xc0b788ab, 0x6f3ffd09, 0xc0b21295, - 0x6f3ce165, 0xc0ac9ca6, - 0x6f39c57d, 0xc0a726df, 0x6f36a94f, 0xc0a1b13e, 0x6f338cde, 0xc09c3bc5, - 0x6f307027, 0xc096c673, - 0x6f2d532c, 0xc0915148, 0x6f2a35ed, 0xc08bdc44, 0x6f271868, 0xc0866767, - 0x6f23faa0, 0xc080f2b1, - 0x6f20dc92, 0xc07b7e23, 0x6f1dbe41, 0xc07609bb, 0x6f1a9faa, 0xc070957b, - 0x6f1780cf, 0xc06b2162, - 0x6f1461b0, 0xc065ad70, 0x6f11424c, 0xc06039a6, 0x6f0e22a3, 0xc05ac603, - 0x6f0b02b6, 0xc0555287, - 0x6f07e285, 0xc04fdf32, 0x6f04c20f, 0xc04a6c05, 0x6f01a155, 0xc044f8fe, - 0x6efe8056, 0xc03f8620, - 0x6efb5f12, 0xc03a1368, 0x6ef83d8a, 0xc034a0d8, 0x6ef51bbe, 0xc02f2e6f, - 0x6ef1f9ad, 0xc029bc2e, - 0x6eeed758, 0xc0244a14, 0x6eebb4bf, 0xc01ed821, 0x6ee891e1, 0xc0196656, - 0x6ee56ebe, 0xc013f4b2, - 0x6ee24b57, 0xc00e8336, 0x6edf27ac, 0xc00911e1, 0x6edc03bc, 0xc003a0b3, - 0x6ed8df88, 0xbffe2fad, - 0x6ed5bb10, 0xbff8bece, 0x6ed29653, 0xbff34e17, 0x6ecf7152, 0xbfeddd88, - 0x6ecc4c0d, 0xbfe86d20, - 0x6ec92683, 0xbfe2fcdf, 0x6ec600b5, 0xbfdd8cc6, 0x6ec2daa2, 0xbfd81cd5, - 0x6ebfb44b, 0xbfd2ad0b, - 0x6ebc8db0, 0xbfcd3d69, 0x6eb966d1, 0xbfc7cdee, 0x6eb63fad, 0xbfc25e9b, - 0x6eb31845, 0xbfbcef70, - 0x6eaff099, 0xbfb7806c, 0x6eacc8a8, 0xbfb21190, 0x6ea9a073, 0xbfaca2dc, - 0x6ea677fa, 0xbfa7344f, - 0x6ea34f3d, 0xbfa1c5ea, 0x6ea0263b, 0xbf9c57ac, 0x6e9cfcf5, 0xbf96e997, - 0x6e99d36b, 0xbf917ba9, - 0x6e96a99d, 0xbf8c0de3, 0x6e937f8a, 0xbf86a044, 0x6e905534, 0xbf8132ce, - 0x6e8d2a99, 0xbf7bc57f, - 0x6e89ffb9, 0xbf765858, 0x6e86d496, 0xbf70eb59, 0x6e83a92f, 0xbf6b7e81, - 0x6e807d83, 0xbf6611d2, - 0x6e7d5193, 0xbf60a54a, 0x6e7a255f, 0xbf5b38ea, 0x6e76f8e7, 0xbf55ccb2, - 0x6e73cc2b, 0xbf5060a2, - 0x6e709f2a, 0xbf4af4ba, 0x6e6d71e6, 0xbf4588fa, 0x6e6a445d, 0xbf401d61, - 0x6e671690, 0xbf3ab1f1, - 0x6e63e87f, 0xbf3546a8, 0x6e60ba2a, 0xbf2fdb88, 0x6e5d8b91, 0xbf2a708f, - 0x6e5a5cb4, 0xbf2505bf, - 0x6e572d93, 0xbf1f9b16, 0x6e53fe2e, 0xbf1a3096, 0x6e50ce84, 0xbf14c63d, - 0x6e4d9e97, 0xbf0f5c0d, - 0x6e4a6e66, 0xbf09f205, 0x6e473df0, 0xbf048824, 0x6e440d37, 0xbeff1e6c, - 0x6e40dc39, 0xbef9b4dc, - 0x6e3daaf8, 0xbef44b74, 0x6e3a7972, 0xbeeee234, 0x6e3747a9, 0xbee9791c, - 0x6e34159b, 0xbee4102d, - 0x6e30e34a, 0xbedea765, 0x6e2db0b4, 0xbed93ec6, 0x6e2a7ddb, 0xbed3d64f, - 0x6e274abe, 0xbece6e00, - 0x6e24175c, 0xbec905d9, 0x6e20e3b7, 0xbec39ddb, 0x6e1dafce, 0xbebe3605, - 0x6e1a7ba1, 0xbeb8ce57, - 0x6e174730, 0xbeb366d1, 0x6e14127b, 0xbeadff74, 0x6e10dd82, 0xbea8983f, - 0x6e0da845, 0xbea33132, - 0x6e0a72c5, 0xbe9dca4e, 0x6e073d00, 0xbe986391, 0x6e0406f8, 0xbe92fcfe, - 0x6e00d0ac, 0xbe8d9692, - 0x6dfd9a1c, 0xbe88304f, 0x6dfa6348, 0xbe82ca35, 0x6df72c30, 0xbe7d6442, - 0x6df3f4d4, 0xbe77fe78, - 0x6df0bd35, 0xbe7298d7, 0x6ded8552, 0xbe6d335e, 0x6dea4d2b, 0xbe67ce0d, - 0x6de714c0, 0xbe6268e5, - 0x6de3dc11, 0xbe5d03e6, 0x6de0a31f, 0xbe579f0f, 0x6ddd69e9, 0xbe523a60, - 0x6dda306f, 0xbe4cd5da, - 0x6dd6f6b1, 0xbe47717c, 0x6dd3bcaf, 0xbe420d47, 0x6dd0826a, 0xbe3ca93b, - 0x6dcd47e1, 0xbe374557, - 0x6dca0d14, 0xbe31e19b, 0x6dc6d204, 0xbe2c7e09, 0x6dc396b0, 0xbe271a9f, - 0x6dc05b18, 0xbe21b75d, - 0x6dbd1f3c, 0xbe1c5444, 0x6db9e31d, 0xbe16f154, 0x6db6a6ba, 0xbe118e8c, - 0x6db36a14, 0xbe0c2bed, - 0x6db02d29, 0xbe06c977, 0x6daceffb, 0xbe01672a, 0x6da9b28a, 0xbdfc0505, - 0x6da674d5, 0xbdf6a309, - 0x6da336dc, 0xbdf14135, 0x6d9ff89f, 0xbdebdf8b, 0x6d9cba1f, 0xbde67e09, - 0x6d997b5b, 0xbde11cb0, - 0x6d963c54, 0xbddbbb7f, 0x6d92fd09, 0xbdd65a78, 0x6d8fbd7a, 0xbdd0f999, - 0x6d8c7da8, 0xbdcb98e3, - 0x6d893d93, 0xbdc63856, 0x6d85fd39, 0xbdc0d7f2, 0x6d82bc9d, 0xbdbb77b7, - 0x6d7f7bbc, 0xbdb617a4, - 0x6d7c3a98, 0xbdb0b7bb, 0x6d78f931, 0xbdab57fa, 0x6d75b786, 0xbda5f862, - 0x6d727597, 0xbda098f3, - 0x6d6f3365, 0xbd9b39ad, 0x6d6bf0f0, 0xbd95da91, 0x6d68ae37, 0xbd907b9d, - 0x6d656b3a, 0xbd8b1cd2, - 0x6d6227fa, 0xbd85be30, 0x6d5ee477, 0xbd805fb7, 0x6d5ba0b0, 0xbd7b0167, - 0x6d585ca6, 0xbd75a340, - 0x6d551858, 0xbd704542, 0x6d51d3c6, 0xbd6ae76d, 0x6d4e8ef2, 0xbd6589c1, - 0x6d4b49da, 0xbd602c3f, - 0x6d48047e, 0xbd5acee5, 0x6d44bedf, 0xbd5571b5, 0x6d4178fd, 0xbd5014ad, - 0x6d3e32d7, 0xbd4ab7cf, - 0x6d3aec6e, 0xbd455b1a, 0x6d37a5c1, 0xbd3ffe8e, 0x6d345ed1, 0xbd3aa22c, - 0x6d31179e, 0xbd3545f2, - 0x6d2dd027, 0xbd2fe9e2, 0x6d2a886e, 0xbd2a8dfb, 0x6d274070, 0xbd25323d, - 0x6d23f830, 0xbd1fd6a8, - 0x6d20afac, 0xbd1a7b3d, 0x6d1d66e4, 0xbd151ffb, 0x6d1a1dda, 0xbd0fc4e2, - 0x6d16d48c, 0xbd0a69f2, - 0x6d138afb, 0xbd050f2c, 0x6d104126, 0xbcffb48f, 0x6d0cf70f, 0xbcfa5a1b, - 0x6d09acb4, 0xbcf4ffd1, - 0x6d066215, 0xbcefa5b0, 0x6d031734, 0xbcea4bb9, 0x6cffcc0f, 0xbce4f1eb, - 0x6cfc80a7, 0xbcdf9846, - 0x6cf934fc, 0xbcda3ecb, 0x6cf5e90d, 0xbcd4e579, 0x6cf29cdc, 0xbccf8c50, - 0x6cef5067, 0xbcca3351, - 0x6cec03af, 0xbcc4da7b, 0x6ce8b6b4, 0xbcbf81cf, 0x6ce56975, 0xbcba294d, - 0x6ce21bf4, 0xbcb4d0f4, - 0x6cdece2f, 0xbcaf78c4, 0x6cdb8027, 0xbcaa20be, 0x6cd831dc, 0xbca4c8e1, - 0x6cd4e34e, 0xbc9f712e, - 0x6cd1947c, 0xbc9a19a5, 0x6cce4568, 0xbc94c245, 0x6ccaf610, 0xbc8f6b0f, - 0x6cc7a676, 0xbc8a1402, - 0x6cc45698, 0xbc84bd1f, 0x6cc10677, 0xbc7f6665, 0x6cbdb613, 0xbc7a0fd6, - 0x6cba656c, 0xbc74b96f, - 0x6cb71482, 0xbc6f6333, 0x6cb3c355, 0xbc6a0d20, 0x6cb071e4, 0xbc64b737, - 0x6cad2031, 0xbc5f6177, - 0x6ca9ce3b, 0xbc5a0be2, 0x6ca67c01, 0xbc54b676, 0x6ca32985, 0xbc4f6134, - 0x6c9fd6c6, 0xbc4a0c1b, - 0x6c9c83c3, 0xbc44b72c, 0x6c99307e, 0xbc3f6267, 0x6c95dcf6, 0xbc3a0dcc, - 0x6c92892a, 0xbc34b95b, - 0x6c8f351c, 0xbc2f6513, 0x6c8be0cb, 0xbc2a10f6, 0x6c888c36, 0xbc24bd02, - 0x6c85375f, 0xbc1f6938, - 0x6c81e245, 0xbc1a1598, 0x6c7e8ce8, 0xbc14c221, 0x6c7b3748, 0xbc0f6ed5, - 0x6c77e165, 0xbc0a1bb3, - 0x6c748b3f, 0xbc04c8ba, 0x6c7134d7, 0xbbff75ec, 0x6c6dde2b, 0xbbfa2347, - 0x6c6a873d, 0xbbf4d0cc, - 0x6c67300b, 0xbbef7e7c, 0x6c63d897, 0xbbea2c55, 0x6c6080e0, 0xbbe4da58, - 0x6c5d28e6, 0xbbdf8885, - 0x6c59d0a9, 0xbbda36dd, 0x6c56782a, 0xbbd4e55e, 0x6c531f67, 0xbbcf940a, - 0x6c4fc662, 0xbbca42df, - 0x6c4c6d1a, 0xbbc4f1df, 0x6c49138f, 0xbbbfa108, 0x6c45b9c1, 0xbbba505c, - 0x6c425fb1, 0xbbb4ffda, - 0x6c3f055d, 0xbbafaf82, 0x6c3baac7, 0xbbaa5f54, 0x6c384fef, 0xbba50f50, - 0x6c34f4d3, 0xbb9fbf77, - 0x6c319975, 0xbb9a6fc7, 0x6c2e3dd4, 0xbb952042, 0x6c2ae1f0, 0xbb8fd0e7, - 0x6c2785ca, 0xbb8a81b6, - 0x6c242960, 0xbb8532b0, 0x6c20ccb4, 0xbb7fe3d3, 0x6c1d6fc6, 0xbb7a9521, - 0x6c1a1295, 0xbb754699, - 0x6c16b521, 0xbb6ff83c, 0x6c13576a, 0xbb6aaa09, 0x6c0ff971, 0xbb655c00, - 0x6c0c9b35, 0xbb600e21, - 0x6c093cb6, 0xbb5ac06d, 0x6c05ddf5, 0xbb5572e3, 0x6c027ef1, 0xbb502583, - 0x6bff1faa, 0xbb4ad84e, - 0x6bfbc021, 0xbb458b43, 0x6bf86055, 0xbb403e63, 0x6bf50047, 0xbb3af1ad, - 0x6bf19ff6, 0xbb35a521, - 0x6bee3f62, 0xbb3058c0, 0x6beade8c, 0xbb2b0c8a, 0x6be77d74, 0xbb25c07d, - 0x6be41c18, 0xbb20749c, - 0x6be0ba7b, 0xbb1b28e4, 0x6bdd589a, 0xbb15dd57, 0x6bd9f677, 0xbb1091f5, - 0x6bd69412, 0xbb0b46bd, - 0x6bd3316a, 0xbb05fbb0, 0x6bcfce80, 0xbb00b0ce, 0x6bcc6b53, 0xbafb6615, - 0x6bc907e3, 0xbaf61b88, - 0x6bc5a431, 0xbaf0d125, 0x6bc2403d, 0xbaeb86ed, 0x6bbedc06, 0xbae63cdf, - 0x6bbb778d, 0xbae0f2fc, - 0x6bb812d1, 0xbadba943, 0x6bb4add3, 0xbad65fb5, 0x6bb14892, 0xbad11652, - 0x6bade30f, 0xbacbcd1a, - 0x6baa7d49, 0xbac6840c, 0x6ba71741, 0xbac13b29, 0x6ba3b0f7, 0xbabbf270, - 0x6ba04a6a, 0xbab6a9e3, - 0x6b9ce39b, 0xbab16180, 0x6b997c8a, 0xbaac1948, 0x6b961536, 0xbaa6d13a, - 0x6b92ada0, 0xbaa18958, - 0x6b8f45c7, 0xba9c41a0, 0x6b8bddac, 0xba96fa13, 0x6b88754f, 0xba91b2b1, - 0x6b850caf, 0xba8c6b79, - 0x6b81a3cd, 0xba87246d, 0x6b7e3aa9, 0xba81dd8b, 0x6b7ad142, 0xba7c96d4, - 0x6b776799, 0xba775048, - 0x6b73fdae, 0xba7209e7, 0x6b709381, 0xba6cc3b1, 0x6b6d2911, 0xba677da6, - 0x6b69be5f, 0xba6237c5, - 0x6b66536b, 0xba5cf210, 0x6b62e834, 0xba57ac86, 0x6b5f7cbc, 0xba526726, - 0x6b5c1101, 0xba4d21f2, - 0x6b58a503, 0xba47dce8, 0x6b5538c4, 0xba42980a, 0x6b51cc42, 0xba3d5356, - 0x6b4e5f7f, 0xba380ece, - 0x6b4af279, 0xba32ca71, 0x6b478530, 0xba2d863e, 0x6b4417a6, 0xba284237, - 0x6b40a9d9, 0xba22fe5b, - 0x6b3d3bcb, 0xba1dbaaa, 0x6b39cd7a, 0xba187724, 0x6b365ee7, 0xba1333c9, - 0x6b32f012, 0xba0df099, - 0x6b2f80fb, 0xba08ad95, 0x6b2c11a1, 0xba036abb, 0x6b28a206, 0xb9fe280d, - 0x6b253228, 0xb9f8e58a, - 0x6b21c208, 0xb9f3a332, 0x6b1e51a7, 0xb9ee6106, 0x6b1ae103, 0xb9e91f04, - 0x6b17701d, 0xb9e3dd2e, - 0x6b13fef5, 0xb9de9b83, 0x6b108d8b, 0xb9d95a03, 0x6b0d1bdf, 0xb9d418af, - 0x6b09a9f1, 0xb9ced786, - 0x6b0637c1, 0xb9c99688, 0x6b02c54f, 0xb9c455b6, 0x6aff529a, 0xb9bf150e, - 0x6afbdfa4, 0xb9b9d493, - 0x6af86c6c, 0xb9b49442, 0x6af4f8f2, 0xb9af541d, 0x6af18536, 0xb9aa1423, - 0x6aee1138, 0xb9a4d455, - 0x6aea9cf8, 0xb99f94b2, 0x6ae72876, 0xb99a553a, 0x6ae3b3b2, 0xb99515ee, - 0x6ae03eac, 0xb98fd6cd, - 0x6adcc964, 0xb98a97d8, 0x6ad953db, 0xb985590e, 0x6ad5de0f, 0xb9801a70, - 0x6ad26802, 0xb97adbfd, - 0x6acef1b2, 0xb9759db6, 0x6acb7b21, 0xb9705f9a, 0x6ac8044e, 0xb96b21aa, - 0x6ac48d39, 0xb965e3e5, - 0x6ac115e2, 0xb960a64c, 0x6abd9e49, 0xb95b68de, 0x6aba266e, 0xb9562b9c, - 0x6ab6ae52, 0xb950ee86, - 0x6ab335f4, 0xb94bb19b, 0x6aafbd54, 0xb94674dc, 0x6aac4472, 0xb9413848, - 0x6aa8cb4e, 0xb93bfbe0, - 0x6aa551e9, 0xb936bfa4, 0x6aa1d841, 0xb9318393, 0x6a9e5e58, 0xb92c47ae, - 0x6a9ae42e, 0xb9270bf5, - 0x6a9769c1, 0xb921d067, 0x6a93ef13, 0xb91c9505, 0x6a907423, 0xb91759cf, - 0x6a8cf8f1, 0xb9121ec5, - 0x6a897d7d, 0xb90ce3e6, 0x6a8601c8, 0xb907a933, 0x6a8285d1, 0xb9026eac, - 0x6a7f0999, 0xb8fd3451, - 0x6a7b8d1e, 0xb8f7fa21, 0x6a781062, 0xb8f2c01d, 0x6a749365, 0xb8ed8646, - 0x6a711625, 0xb8e84c99, - 0x6a6d98a4, 0xb8e31319, 0x6a6a1ae2, 0xb8ddd9c5, 0x6a669cdd, 0xb8d8a09d, - 0x6a631e97, 0xb8d367a0, - 0x6a5fa010, 0xb8ce2ecf, 0x6a5c2147, 0xb8c8f62b, 0x6a58a23c, 0xb8c3bdb2, - 0x6a5522ef, 0xb8be8565, - 0x6a51a361, 0xb8b94d44, 0x6a4e2392, 0xb8b4154f, 0x6a4aa381, 0xb8aedd86, - 0x6a47232e, 0xb8a9a5e9, - 0x6a43a29a, 0xb8a46e78, 0x6a4021c4, 0xb89f3733, 0x6a3ca0ad, 0xb89a001a, - 0x6a391f54, 0xb894c92d, - 0x6a359db9, 0xb88f926d, 0x6a321bdd, 0xb88a5bd8, 0x6a2e99c0, 0xb885256f, - 0x6a2b1761, 0xb87fef33, - 0x6a2794c1, 0xb87ab922, 0x6a2411df, 0xb875833e, 0x6a208ebb, 0xb8704d85, - 0x6a1d0b57, 0xb86b17f9, - 0x6a1987b0, 0xb865e299, 0x6a1603c8, 0xb860ad66, 0x6a127f9f, 0xb85b785e, - 0x6a0efb35, 0xb8564383, - 0x6a0b7689, 0xb8510ed4, 0x6a07f19b, 0xb84bda51, 0x6a046c6c, 0xb846a5fa, - 0x6a00e6fc, 0xb84171cf, - 0x69fd614a, 0xb83c3dd1, 0x69f9db57, 0xb83709ff, 0x69f65523, 0xb831d659, - 0x69f2cead, 0xb82ca2e0, - 0x69ef47f6, 0xb8276f93, 0x69ebc0fe, 0xb8223c72, 0x69e839c4, 0xb81d097e, - 0x69e4b249, 0xb817d6b6, - 0x69e12a8c, 0xb812a41a, 0x69dda28f, 0xb80d71aa, 0x69da1a50, 0xb8083f67, - 0x69d691cf, 0xb8030d51, - 0x69d3090e, 0xb7fddb67, 0x69cf800b, 0xb7f8a9a9, 0x69cbf6c7, 0xb7f37818, - 0x69c86d41, 0xb7ee46b3, - 0x69c4e37a, 0xb7e9157a, 0x69c15973, 0xb7e3e46e, 0x69bdcf29, 0xb7deb38f, - 0x69ba449f, 0xb7d982dc, - 0x69b6b9d3, 0xb7d45255, 0x69b32ec7, 0xb7cf21fb, 0x69afa378, 0xb7c9f1ce, - 0x69ac17e9, 0xb7c4c1cd, - 0x69a88c19, 0xb7bf91f8, 0x69a50007, 0xb7ba6251, 0x69a173b5, 0xb7b532d6, - 0x699de721, 0xb7b00387, - 0x699a5a4c, 0xb7aad465, 0x6996cd35, 0xb7a5a570, 0x69933fde, 0xb7a076a7, - 0x698fb246, 0xb79b480b, - 0x698c246c, 0xb796199b, 0x69889651, 0xb790eb58, 0x698507f6, 0xb78bbd42, - 0x69817959, 0xb7868f59, - 0x697dea7b, 0xb781619c, 0x697a5b5c, 0xb77c340c, 0x6976cbfc, 0xb77706a9, - 0x69733c5b, 0xb771d972, - 0x696fac78, 0xb76cac69, 0x696c1c55, 0xb7677f8c, 0x69688bf1, 0xb76252db, - 0x6964fb4c, 0xb75d2658, - 0x69616a65, 0xb757fa01, 0x695dd93e, 0xb752cdd8, 0x695a47d6, 0xb74da1db, - 0x6956b62d, 0xb748760b, - 0x69532442, 0xb7434a67, 0x694f9217, 0xb73e1ef1, 0x694bffab, 0xb738f3a7, - 0x69486cfe, 0xb733c88b, - 0x6944da10, 0xb72e9d9b, 0x694146e1, 0xb72972d8, 0x693db371, 0xb7244842, - 0x693a1fc0, 0xb71f1dd9, - 0x69368bce, 0xb719f39e, 0x6932f79b, 0xb714c98e, 0x692f6328, 0xb70f9fac, - 0x692bce73, 0xb70a75f7, - 0x6928397e, 0xb7054c6f, 0x6924a448, 0xb7002314, 0x69210ed1, 0xb6faf9e6, - 0x691d7919, 0xb6f5d0e5, - 0x6919e320, 0xb6f0a812, 0x69164ce7, 0xb6eb7f6b, 0x6912b66c, 0xb6e656f1, - 0x690f1fb1, 0xb6e12ea4, - 0x690b88b5, 0xb6dc0685, 0x6907f178, 0xb6d6de92, 0x690459fb, 0xb6d1b6cd, - 0x6900c23c, 0xb6cc8f35, - 0x68fd2a3d, 0xb6c767ca, 0x68f991fd, 0xb6c2408c, 0x68f5f97d, 0xb6bd197c, - 0x68f260bb, 0xb6b7f298, - 0x68eec7b9, 0xb6b2cbe2, 0x68eb2e76, 0xb6ada559, 0x68e794f3, 0xb6a87efd, - 0x68e3fb2e, 0xb6a358ce, - 0x68e06129, 0xb69e32cd, 0x68dcc6e4, 0xb6990cf9, 0x68d92c5d, 0xb693e752, - 0x68d59196, 0xb68ec1d9, - 0x68d1f68f, 0xb6899c8d, 0x68ce5b46, 0xb684776e, 0x68cabfbd, 0xb67f527c, - 0x68c723f3, 0xb67a2db8, - 0x68c387e9, 0xb6750921, 0x68bfeb9e, 0xb66fe4b8, 0x68bc4f13, 0xb66ac07c, - 0x68b8b247, 0xb6659c6d, - 0x68b5153a, 0xb660788c, 0x68b177ed, 0xb65b54d8, 0x68adda5f, 0xb6563151, - 0x68aa3c90, 0xb6510df8, - 0x68a69e81, 0xb64beacd, 0x68a30031, 0xb646c7ce, 0x689f61a1, 0xb641a4fe, - 0x689bc2d1, 0xb63c825b, - 0x689823bf, 0xb6375fe5, 0x6894846e, 0xb6323d9d, 0x6890e4dc, 0xb62d1b82, - 0x688d4509, 0xb627f995, - 0x6889a4f6, 0xb622d7d6, 0x688604a2, 0xb61db644, 0x6882640e, 0xb61894df, - 0x687ec339, 0xb61373a9, - 0x687b2224, 0xb60e529f, 0x687780ce, 0xb60931c4, 0x6873df38, 0xb6041116, - 0x68703d62, 0xb5fef095, - 0x686c9b4b, 0xb5f9d043, 0x6868f8f4, 0xb5f4b01e, 0x6865565c, 0xb5ef9026, - 0x6861b384, 0xb5ea705d, - 0x685e106c, 0xb5e550c1, 0x685a6d13, 0xb5e03153, 0x6856c979, 0xb5db1212, - 0x685325a0, 0xb5d5f2ff, - 0x684f8186, 0xb5d0d41a, 0x684bdd2c, 0xb5cbb563, 0x68483891, 0xb5c696da, - 0x684493b6, 0xb5c1787e, - 0x6840ee9b, 0xb5bc5a50, 0x683d493f, 0xb5b73c50, 0x6839a3a4, 0xb5b21e7e, - 0x6835fdc7, 0xb5ad00d9, - 0x683257ab, 0xb5a7e362, 0x682eb14e, 0xb5a2c61a, 0x682b0ab1, 0xb59da8ff, - 0x682763d4, 0xb5988c12, - 0x6823bcb7, 0xb5936f53, 0x68201559, 0xb58e52c2, 0x681c6dbb, 0xb589365e, - 0x6818c5dd, 0xb5841a29, - 0x68151dbe, 0xb57efe22, 0x68117560, 0xb579e248, 0x680dccc1, 0xb574c69d, - 0x680a23e2, 0xb56fab1f, - 0x68067ac3, 0xb56a8fd0, 0x6802d164, 0xb56574ae, 0x67ff27c4, 0xb56059bb, - 0x67fb7de5, 0xb55b3ef5, - 0x67f7d3c5, 0xb556245e, 0x67f42965, 0xb55109f5, 0x67f07ec5, 0xb54befba, - 0x67ecd3e5, 0xb546d5ac, - 0x67e928c5, 0xb541bbcd, 0x67e57d64, 0xb53ca21c, 0x67e1d1c4, 0xb5378899, - 0x67de25e3, 0xb5326f45, - 0x67da79c3, 0xb52d561e, 0x67d6cd62, 0xb5283d26, 0x67d320c1, 0xb523245b, - 0x67cf73e1, 0xb51e0bbf, - 0x67cbc6c0, 0xb518f351, 0x67c8195f, 0xb513db12, 0x67c46bbe, 0xb50ec300, - 0x67c0bddd, 0xb509ab1d, - 0x67bd0fbd, 0xb5049368, 0x67b9615c, 0xb4ff7be1, 0x67b5b2bb, 0xb4fa6489, - 0x67b203da, 0xb4f54d5f, - 0x67ae54ba, 0xb4f03663, 0x67aaa559, 0xb4eb1f95, 0x67a6f5b8, 0xb4e608f6, - 0x67a345d8, 0xb4e0f285, - 0x679f95b7, 0xb4dbdc42, 0x679be557, 0xb4d6c62e, 0x679834b6, 0xb4d1b048, - 0x679483d6, 0xb4cc9a90, - 0x6790d2b6, 0xb4c78507, 0x678d2156, 0xb4c26fad, 0x67896fb6, 0xb4bd5a80, - 0x6785bdd6, 0xb4b84582, - 0x67820bb7, 0xb4b330b3, 0x677e5957, 0xb4ae1c12, 0x677aa6b8, 0xb4a9079f, - 0x6776f3d9, 0xb4a3f35b, - 0x677340ba, 0xb49edf45, 0x676f8d5b, 0xb499cb5e, 0x676bd9bd, 0xb494b7a6, - 0x676825de, 0xb48fa41c, - 0x676471c0, 0xb48a90c0, 0x6760bd62, 0xb4857d93, 0x675d08c4, 0xb4806a95, - 0x675953e7, 0xb47b57c5, - 0x67559eca, 0xb4764523, 0x6751e96d, 0xb47132b1, 0x674e33d0, 0xb46c206d, - 0x674a7df4, 0xb4670e57, - 0x6746c7d8, 0xb461fc70, 0x6743117c, 0xb45ceab8, 0x673f5ae0, 0xb457d92f, - 0x673ba405, 0xb452c7d4, - 0x6737ecea, 0xb44db6a8, 0x67343590, 0xb448a5aa, 0x67307df5, 0xb44394db, - 0x672cc61c, 0xb43e843b, - 0x67290e02, 0xb43973ca, 0x672555a9, 0xb4346387, 0x67219d10, 0xb42f5373, - 0x671de438, 0xb42a438e, - 0x671a2b20, 0xb42533d8, 0x671671c8, 0xb4202451, 0x6712b831, 0xb41b14f8, - 0x670efe5a, 0xb41605ce, - 0x670b4444, 0xb410f6d3, 0x670789ee, 0xb40be807, 0x6703cf58, 0xb406d969, - 0x67001483, 0xb401cafb, - 0x66fc596f, 0xb3fcbcbb, 0x66f89e1b, 0xb3f7aeaa, 0x66f4e287, 0xb3f2a0c9, - 0x66f126b4, 0xb3ed9316, - 0x66ed6aa1, 0xb3e88592, 0x66e9ae4f, 0xb3e3783d, 0x66e5f1be, 0xb3de6b17, - 0x66e234ed, 0xb3d95e1f, - 0x66de77dc, 0xb3d45157, 0x66daba8c, 0xb3cf44be, 0x66d6fcfd, 0xb3ca3854, - 0x66d33f2e, 0xb3c52c19, - 0x66cf8120, 0xb3c0200c, 0x66cbc2d2, 0xb3bb142f, 0x66c80445, 0xb3b60881, - 0x66c44579, 0xb3b0fd02, - 0x66c0866d, 0xb3abf1b2, 0x66bcc721, 0xb3a6e691, 0x66b90797, 0xb3a1dba0, - 0x66b547cd, 0xb39cd0dd, - 0x66b187c3, 0xb397c649, 0x66adc77b, 0xb392bbe5, 0x66aa06f3, 0xb38db1b0, - 0x66a6462b, 0xb388a7aa, - 0x66a28524, 0xb3839dd3, 0x669ec3de, 0xb37e942b, 0x669b0259, 0xb3798ab2, - 0x66974095, 0xb3748169, - 0x66937e91, 0xb36f784f, 0x668fbc4e, 0xb36a6f64, 0x668bf9cb, 0xb36566a8, - 0x66883709, 0xb3605e1c, - 0x66847408, 0xb35b55bf, 0x6680b0c8, 0xb3564d91, 0x667ced49, 0xb3514592, - 0x6679298a, 0xb34c3dc3, - 0x6675658c, 0xb3473623, 0x6671a14f, 0xb3422eb2, 0x666ddcd3, 0xb33d2771, - 0x666a1818, 0xb338205f, - 0x6666531d, 0xb333197c, 0x66628de4, 0xb32e12c9, 0x665ec86b, 0xb3290c45, - 0x665b02b3, 0xb32405f1, - 0x66573cbb, 0xb31effcc, 0x66537685, 0xb319f9d6, 0x664fb010, 0xb314f410, - 0x664be95b, 0xb30fee79, - 0x66482267, 0xb30ae912, 0x66445b35, 0xb305e3da, 0x664093c3, 0xb300ded2, - 0x663ccc12, 0xb2fbd9f9, - 0x66390422, 0xb2f6d550, 0x66353bf3, 0xb2f1d0d6, 0x66317385, 0xb2eccc8c, - 0x662daad8, 0xb2e7c871, - 0x6629e1ec, 0xb2e2c486, 0x662618c1, 0xb2ddc0ca, 0x66224f56, 0xb2d8bd3e, - 0x661e85ad, 0xb2d3b9e2, - 0x661abbc5, 0xb2ceb6b5, 0x6616f19e, 0xb2c9b3b8, 0x66132738, 0xb2c4b0ea, - 0x660f5c93, 0xb2bfae4c, - 0x660b91af, 0xb2baabde, 0x6607c68c, 0xb2b5a99f, 0x6603fb2a, 0xb2b0a790, - 0x66002f89, 0xb2aba5b1, - 0x65fc63a9, 0xb2a6a402, 0x65f8978b, 0xb2a1a282, 0x65f4cb2d, 0xb29ca132, - 0x65f0fe91, 0xb297a011, - 0x65ed31b5, 0xb2929f21, 0x65e9649b, 0xb28d9e60, 0x65e59742, 0xb2889dcf, - 0x65e1c9aa, 0xb2839d6d, - 0x65ddfbd3, 0xb27e9d3c, 0x65da2dbd, 0xb2799d3a, 0x65d65f69, 0xb2749d68, - 0x65d290d6, 0xb26f9dc6, - 0x65cec204, 0xb26a9e54, 0x65caf2f3, 0xb2659f12, 0x65c723a3, 0xb2609fff, - 0x65c35415, 0xb25ba11d, - 0x65bf8447, 0xb256a26a, 0x65bbb43b, 0xb251a3e7, 0x65b7e3f1, 0xb24ca594, - 0x65b41367, 0xb247a771, - 0x65b0429f, 0xb242a97e, 0x65ac7198, 0xb23dabbb, 0x65a8a052, 0xb238ae28, - 0x65a4cece, 0xb233b0c5, - 0x65a0fd0b, 0xb22eb392, 0x659d2b09, 0xb229b68f, 0x659958c9, 0xb224b9bc, - 0x6595864a, 0xb21fbd19, - 0x6591b38c, 0xb21ac0a6, 0x658de08f, 0xb215c463, 0x658a0d54, 0xb210c850, - 0x658639db, 0xb20bcc6d, - 0x65826622, 0xb206d0ba, 0x657e922b, 0xb201d537, 0x657abdf6, 0xb1fcd9e5, - 0x6576e982, 0xb1f7dec2, - 0x657314cf, 0xb1f2e3d0, 0x656f3fde, 0xb1ede90e, 0x656b6aae, 0xb1e8ee7c, - 0x6567953f, 0xb1e3f41a, - 0x6563bf92, 0xb1def9e9, 0x655fe9a7, 0xb1d9ffe7, 0x655c137d, 0xb1d50616, - 0x65583d14, 0xb1d00c75, - 0x6554666d, 0xb1cb1304, 0x65508f87, 0xb1c619c3, 0x654cb863, 0xb1c120b3, - 0x6548e101, 0xb1bc27d3, - 0x6545095f, 0xb1b72f23, 0x65413180, 0xb1b236a4, 0x653d5962, 0xb1ad3e55, - 0x65398105, 0xb1a84636, - 0x6535a86b, 0xb1a34e47, 0x6531cf91, 0xb19e5689, 0x652df679, 0xb1995efb, - 0x652a1d23, 0xb194679e, - 0x6526438f, 0xb18f7071, 0x652269bc, 0xb18a7974, 0x651e8faa, 0xb18582a8, - 0x651ab55b, 0xb1808c0c, - 0x6516dacd, 0xb17b95a0, 0x65130000, 0xb1769f65, 0x650f24f5, 0xb171a95b, - 0x650b49ac, 0xb16cb380, - 0x65076e25, 0xb167bdd7, 0x6503925f, 0xb162c85d, 0x64ffb65b, 0xb15dd315, - 0x64fbda18, 0xb158ddfd, - 0x64f7fd98, 0xb153e915, 0x64f420d9, 0xb14ef45e, 0x64f043dc, 0xb149ffd7, - 0x64ec66a0, 0xb1450b81, - 0x64e88926, 0xb140175b, 0x64e4ab6e, 0xb13b2367, 0x64e0cd78, 0xb1362fa2, - 0x64dcef44, 0xb1313c0e, - 0x64d910d1, 0xb12c48ab, 0x64d53220, 0xb1275579, 0x64d15331, 0xb1226277, - 0x64cd7404, 0xb11d6fa6, - 0x64c99498, 0xb1187d05, 0x64c5b4ef, 0xb1138a95, 0x64c1d507, 0xb10e9856, - 0x64bdf4e1, 0xb109a648, - 0x64ba147d, 0xb104b46a, 0x64b633da, 0xb0ffc2bd, 0x64b252fa, 0xb0fad140, - 0x64ae71dc, 0xb0f5dff5, - 0x64aa907f, 0xb0f0eeda, 0x64a6aee4, 0xb0ebfdf0, 0x64a2cd0c, 0xb0e70d37, - 0x649eeaf5, 0xb0e21cae, - 0x649b08a0, 0xb0dd2c56, 0x6497260d, 0xb0d83c2f, 0x6493433c, 0xb0d34c39, - 0x648f602d, 0xb0ce5c74, - 0x648b7ce0, 0xb0c96ce0, 0x64879955, 0xb0c47d7c, 0x6483b58c, 0xb0bf8e4a, - 0x647fd185, 0xb0ba9f48, - 0x647bed3f, 0xb0b5b077, 0x647808bc, 0xb0b0c1d7, 0x647423fb, 0xb0abd368, - 0x64703efc, 0xb0a6e52a, - 0x646c59bf, 0xb0a1f71d, 0x64687444, 0xb09d0941, 0x64648e8c, 0xb0981b96, - 0x6460a895, 0xb0932e1b, - 0x645cc260, 0xb08e40d2, 0x6458dbed, 0xb08953ba, 0x6454f53d, 0xb08466d3, - 0x64510e4e, 0xb07f7a1c, - 0x644d2722, 0xb07a8d97, 0x64493fb8, 0xb075a143, 0x64455810, 0xb070b520, - 0x6441702a, 0xb06bc92e, - 0x643d8806, 0xb066dd6d, 0x64399fa5, 0xb061f1de, 0x6435b706, 0xb05d067f, - 0x6431ce28, 0xb0581b51, - 0x642de50d, 0xb0533055, 0x6429fbb5, 0xb04e458a, 0x6426121e, 0xb0495af0, - 0x6422284a, 0xb0447087, - 0x641e3e38, 0xb03f864f, 0x641a53e8, 0xb03a9c49, 0x6416695a, 0xb035b273, - 0x64127e8f, 0xb030c8cf, - 0x640e9386, 0xb02bdf5c, 0x640aa83f, 0xb026f61b, 0x6406bcba, 0xb0220d0a, - 0x6402d0f8, 0xb01d242b, - 0x63fee4f8, 0xb0183b7d, 0x63faf8bb, 0xb0135301, 0x63f70c3f, 0xb00e6ab5, - 0x63f31f86, 0xb009829c, - 0x63ef3290, 0xb0049ab3, 0x63eb455c, 0xafffb2fc, 0x63e757ea, 0xaffacb76, - 0x63e36a3a, 0xaff5e421, - 0x63df7c4d, 0xaff0fcfe, 0x63db8e22, 0xafec160c, 0x63d79fba, 0xafe72f4c, - 0x63d3b114, 0xafe248bd, - 0x63cfc231, 0xafdd625f, 0x63cbd310, 0xafd87c33, 0x63c7e3b1, 0xafd39638, - 0x63c3f415, 0xafceb06f, - 0x63c0043b, 0xafc9cad7, 0x63bc1424, 0xafc4e571, 0x63b823cf, 0xafc0003c, - 0x63b4333d, 0xafbb1b39, - 0x63b0426d, 0xafb63667, 0x63ac5160, 0xafb151c7, 0x63a86015, 0xafac6d58, - 0x63a46e8d, 0xafa7891b, - 0x63a07cc7, 0xafa2a50f, 0x639c8ac4, 0xaf9dc135, 0x63989884, 0xaf98dd8d, - 0x6394a606, 0xaf93fa16, - 0x6390b34a, 0xaf8f16d1, 0x638cc051, 0xaf8a33bd, 0x6388cd1b, 0xaf8550db, - 0x6384d9a7, 0xaf806e2b, - 0x6380e5f6, 0xaf7b8bac, 0x637cf208, 0xaf76a95f, 0x6378fddc, 0xaf71c743, - 0x63750973, 0xaf6ce55a, - 0x637114cc, 0xaf6803a2, 0x636d1fe9, 0xaf63221c, 0x63692ac7, 0xaf5e40c7, - 0x63653569, 0xaf595fa4, - 0x63613fcd, 0xaf547eb3, 0x635d49f4, 0xaf4f9df4, 0x635953dd, 0xaf4abd66, - 0x63555d8a, 0xaf45dd0b, - 0x635166f9, 0xaf40fce1, 0x634d702b, 0xaf3c1ce9, 0x6349791f, 0xaf373d22, - 0x634581d6, 0xaf325d8e, - 0x63418a50, 0xaf2d7e2b, 0x633d928d, 0xaf289efa, 0x63399a8d, 0xaf23bffb, - 0x6335a24f, 0xaf1ee12e, - 0x6331a9d4, 0xaf1a0293, 0x632db11c, 0xaf15242a, 0x6329b827, 0xaf1045f3, - 0x6325bef5, 0xaf0b67ed, - 0x6321c585, 0xaf068a1a, 0x631dcbd9, 0xaf01ac78, 0x6319d1ef, 0xaefccf09, - 0x6315d7c8, 0xaef7f1cb, - 0x6311dd64, 0xaef314c0, 0x630de2c3, 0xaeee37e6, 0x6309e7e4, 0xaee95b3f, - 0x6305ecc9, 0xaee47ec9, - 0x6301f171, 0xaedfa285, 0x62fdf5db, 0xaedac674, 0x62f9fa09, 0xaed5ea95, - 0x62f5fdf9, 0xaed10ee7, - 0x62f201ac, 0xaecc336c, 0x62ee0523, 0xaec75823, 0x62ea085c, 0xaec27d0c, - 0x62e60b58, 0xaebda227, - 0x62e20e17, 0xaeb8c774, 0x62de109a, 0xaeb3ecf3, 0x62da12df, 0xaeaf12a4, - 0x62d614e7, 0xaeaa3888, - 0x62d216b3, 0xaea55e9e, 0x62ce1841, 0xaea084e6, 0x62ca1992, 0xae9bab60, - 0x62c61aa7, 0xae96d20c, - 0x62c21b7e, 0xae91f8eb, 0x62be1c19, 0xae8d1ffb, 0x62ba1c77, 0xae88473e, - 0x62b61c98, 0xae836eb4, - 0x62b21c7b, 0xae7e965b, 0x62ae1c23, 0xae79be35, 0x62aa1b8d, 0xae74e641, - 0x62a61aba, 0xae700e80, - 0x62a219aa, 0xae6b36f0, 0x629e185e, 0xae665f93, 0x629a16d5, 0xae618869, - 0x6296150f, 0xae5cb171, - 0x6292130c, 0xae57daab, 0x628e10cc, 0xae530417, 0x628a0e50, 0xae4e2db6, - 0x62860b97, 0xae495787, - 0x628208a1, 0xae44818b, 0x627e056e, 0xae3fabc1, 0x627a01fe, 0xae3ad629, - 0x6275fe52, 0xae3600c4, - 0x6271fa69, 0xae312b92, 0x626df643, 0xae2c5691, 0x6269f1e1, 0xae2781c4, - 0x6265ed42, 0xae22ad29, - 0x6261e866, 0xae1dd8c0, 0x625de34e, 0xae19048a, 0x6259ddf8, 0xae143086, - 0x6255d866, 0xae0f5cb5, - 0x6251d298, 0xae0a8916, 0x624dcc8d, 0xae05b5aa, 0x6249c645, 0xae00e271, - 0x6245bfc0, 0xadfc0f6a, - 0x6241b8ff, 0xadf73c96, 0x623db202, 0xadf269f4, 0x6239aac7, 0xaded9785, - 0x6235a351, 0xade8c548, - 0x62319b9d, 0xade3f33e, 0x622d93ad, 0xaddf2167, 0x62298b81, 0xadda4fc3, - 0x62258317, 0xadd57e51, - 0x62217a72, 0xadd0ad12, 0x621d7190, 0xadcbdc05, 0x62196871, 0xadc70b2c, - 0x62155f16, 0xadc23a85, - 0x6211557e, 0xadbd6a10, 0x620d4baa, 0xadb899cf, 0x62094199, 0xadb3c9c0, - 0x6205374c, 0xadaef9e4, - 0x62012cc2, 0xadaa2a3b, 0x61fd21fc, 0xada55ac4, 0x61f916f9, 0xada08b80, - 0x61f50bba, 0xad9bbc70, - 0x61f1003f, 0xad96ed92, 0x61ecf487, 0xad921ee6, 0x61e8e893, 0xad8d506e, - 0x61e4dc62, 0xad888229, - 0x61e0cff5, 0xad83b416, 0x61dcc34c, 0xad7ee636, 0x61d8b666, 0xad7a1889, - 0x61d4a944, 0xad754b0f, - 0x61d09be5, 0xad707dc8, 0x61cc8e4b, 0xad6bb0b4, 0x61c88074, 0xad66e3d3, - 0x61c47260, 0xad621725, - 0x61c06410, 0xad5d4aaa, 0x61bc5584, 0xad587e61, 0x61b846bc, 0xad53b24c, - 0x61b437b7, 0xad4ee66a, - 0x61b02876, 0xad4a1aba, 0x61ac18f9, 0xad454f3e, 0x61a80940, 0xad4083f5, - 0x61a3f94a, 0xad3bb8df, - 0x619fe918, 0xad36edfc, 0x619bd8aa, 0xad32234b, 0x6197c800, 0xad2d58ce, - 0x6193b719, 0xad288e85, - 0x618fa5f7, 0xad23c46e, 0x618b9498, 0xad1efa8a, 0x618782fd, 0xad1a30d9, - 0x61837126, 0xad15675c, - 0x617f5f12, 0xad109e12, 0x617b4cc3, 0xad0bd4fb, 0x61773a37, 0xad070c17, - 0x61732770, 0xad024366, - 0x616f146c, 0xacfd7ae8, 0x616b012c, 0xacf8b29e, 0x6166edb0, 0xacf3ea87, - 0x6162d9f8, 0xacef22a3, - 0x615ec603, 0xacea5af2, 0x615ab1d3, 0xace59375, 0x61569d67, 0xace0cc2b, - 0x615288be, 0xacdc0514, - 0x614e73da, 0xacd73e30, 0x614a5eba, 0xacd27780, 0x6146495d, 0xaccdb103, - 0x614233c5, 0xacc8eab9, - 0x613e1df0, 0xacc424a3, 0x613a07e0, 0xacbf5ec0, 0x6135f193, 0xacba9910, - 0x6131db0b, 0xacb5d394, - 0x612dc447, 0xacb10e4b, 0x6129ad46, 0xacac4935, 0x6125960a, 0xaca78453, - 0x61217e92, 0xaca2bfa4, - 0x611d66de, 0xac9dfb29, 0x61194eee, 0xac9936e1, 0x611536c2, 0xac9472cd, - 0x61111e5b, 0xac8faeec, - 0x610d05b7, 0xac8aeb3e, 0x6108ecd8, 0xac8627c4, 0x6104d3bc, 0xac81647e, - 0x6100ba65, 0xac7ca16b, - 0x60fca0d2, 0xac77de8b, 0x60f88703, 0xac731bdf, 0x60f46cf9, 0xac6e5967, - 0x60f052b2, 0xac699722, - 0x60ec3830, 0xac64d510, 0x60e81d72, 0xac601333, 0x60e40278, 0xac5b5189, - 0x60dfe743, 0xac569012, - 0x60dbcbd1, 0xac51cecf, 0x60d7b024, 0xac4d0dc0, 0x60d3943b, 0xac484ce4, - 0x60cf7817, 0xac438c3c, - 0x60cb5bb7, 0xac3ecbc7, 0x60c73f1b, 0xac3a0b87, 0x60c32243, 0xac354b7a, - 0x60bf0530, 0xac308ba0, - 0x60bae7e1, 0xac2bcbfa, 0x60b6ca56, 0xac270c88, 0x60b2ac8f, 0xac224d4a, - 0x60ae8e8d, 0xac1d8e40, - 0x60aa7050, 0xac18cf69, 0x60a651d7, 0xac1410c6, 0x60a23322, 0xac0f5256, - 0x609e1431, 0xac0a941b, - 0x6099f505, 0xac05d613, 0x6095d59d, 0xac01183f, 0x6091b5fa, 0xabfc5a9f, - 0x608d961b, 0xabf79d33, - 0x60897601, 0xabf2dffb, 0x608555ab, 0xabee22f6, 0x60813519, 0xabe96625, - 0x607d144c, 0xabe4a988, - 0x6078f344, 0xabdfed1f, 0x6074d200, 0xabdb30ea, 0x6070b080, 0xabd674e9, - 0x606c8ec5, 0xabd1b91c, - 0x60686ccf, 0xabccfd83, 0x60644a9d, 0xabc8421d, 0x6060282f, 0xabc386ec, - 0x605c0587, 0xabbecbee, - 0x6057e2a2, 0xabba1125, 0x6053bf82, 0xabb5568f, 0x604f9c27, 0xabb09c2e, - 0x604b7891, 0xababe200, - 0x604754bf, 0xaba72807, 0x604330b1, 0xaba26e41, 0x603f0c69, 0xab9db4b0, - 0x603ae7e5, 0xab98fb52, - 0x6036c325, 0xab944229, 0x60329e2a, 0xab8f8934, 0x602e78f4, 0xab8ad073, - 0x602a5383, 0xab8617e6, - 0x60262dd6, 0xab815f8d, 0x602207ee, 0xab7ca768, 0x601de1ca, 0xab77ef77, - 0x6019bb6b, 0xab7337bb, - 0x601594d1, 0xab6e8032, 0x60116dfc, 0xab69c8de, 0x600d46ec, 0xab6511be, - 0x60091fa0, 0xab605ad2, - 0x6004f819, 0xab5ba41a, 0x6000d057, 0xab56ed97, 0x5ffca859, 0xab523748, - 0x5ff88021, 0xab4d812d, - 0x5ff457ad, 0xab48cb46, 0x5ff02efe, 0xab441593, 0x5fec0613, 0xab3f6015, - 0x5fe7dcee, 0xab3aaacb, - 0x5fe3b38d, 0xab35f5b5, 0x5fdf89f2, 0xab3140d4, 0x5fdb601b, 0xab2c8c27, - 0x5fd73609, 0xab27d7ae, - 0x5fd30bbc, 0xab23236a, 0x5fcee133, 0xab1e6f5a, 0x5fcab670, 0xab19bb7e, - 0x5fc68b72, 0xab1507d7, - 0x5fc26038, 0xab105464, 0x5fbe34c4, 0xab0ba125, 0x5fba0914, 0xab06ee1b, - 0x5fb5dd29, 0xab023b46, - 0x5fb1b104, 0xaafd88a4, 0x5fad84a3, 0xaaf8d637, 0x5fa95807, 0xaaf423ff, - 0x5fa52b31, 0xaaef71fb, - 0x5fa0fe1f, 0xaaeac02c, 0x5f9cd0d2, 0xaae60e91, 0x5f98a34a, 0xaae15d2a, - 0x5f947588, 0xaadcabf8, - 0x5f90478a, 0xaad7fafb, 0x5f8c1951, 0xaad34a32, 0x5f87eade, 0xaace999d, - 0x5f83bc2f, 0xaac9e93e, - 0x5f7f8d46, 0xaac53912, 0x5f7b5e22, 0xaac0891c, 0x5f772ec2, 0xaabbd959, - 0x5f72ff28, 0xaab729cc, - 0x5f6ecf53, 0xaab27a73, 0x5f6a9f44, 0xaaadcb4f, 0x5f666ef9, 0xaaa91c5f, - 0x5f623e73, 0xaaa46da4, - 0x5f5e0db3, 0xaa9fbf1e, 0x5f59dcb8, 0xaa9b10cc, 0x5f55ab82, 0xaa9662af, - 0x5f517a11, 0xaa91b4c7, - 0x5f4d4865, 0xaa8d0713, 0x5f49167f, 0xaa885994, 0x5f44e45e, 0xaa83ac4a, - 0x5f40b202, 0xaa7eff34, - 0x5f3c7f6b, 0xaa7a5253, 0x5f384c9a, 0xaa75a5a8, 0x5f34198e, 0xaa70f930, - 0x5f2fe647, 0xaa6c4cee, - 0x5f2bb2c5, 0xaa67a0e0, 0x5f277f09, 0xaa62f507, 0x5f234b12, 0xaa5e4963, - 0x5f1f16e0, 0xaa599df4, - 0x5f1ae274, 0xaa54f2ba, 0x5f16adcc, 0xaa5047b4, 0x5f1278eb, 0xaa4b9ce3, - 0x5f0e43ce, 0xaa46f248, - 0x5f0a0e77, 0xaa4247e1, 0x5f05d8e6, 0xaa3d9daf, 0x5f01a31a, 0xaa38f3b1, - 0x5efd6d13, 0xaa3449e9, - 0x5ef936d1, 0xaa2fa056, 0x5ef50055, 0xaa2af6f7, 0x5ef0c99f, 0xaa264dce, - 0x5eec92ae, 0xaa21a4d9, - 0x5ee85b82, 0xaa1cfc1a, 0x5ee4241c, 0xaa18538f, 0x5edfec7b, 0xaa13ab3a, - 0x5edbb49f, 0xaa0f0319, - 0x5ed77c8a, 0xaa0a5b2e, 0x5ed34439, 0xaa05b377, 0x5ecf0baf, 0xaa010bf6, - 0x5ecad2e9, 0xa9fc64a9, - 0x5ec699e9, 0xa9f7bd92, 0x5ec260af, 0xa9f316b0, 0x5ebe273b, 0xa9ee7002, - 0x5eb9ed8b, 0xa9e9c98a, - 0x5eb5b3a2, 0xa9e52347, 0x5eb1797e, 0xa9e07d39, 0x5ead3f1f, 0xa9dbd761, - 0x5ea90487, 0xa9d731bd, - 0x5ea4c9b3, 0xa9d28c4e, 0x5ea08ea6, 0xa9cde715, 0x5e9c535e, 0xa9c94211, - 0x5e9817dc, 0xa9c49d42, - 0x5e93dc1f, 0xa9bff8a8, 0x5e8fa028, 0xa9bb5444, 0x5e8b63f7, 0xa9b6b014, - 0x5e87278b, 0xa9b20c1a, - 0x5e82eae5, 0xa9ad6855, 0x5e7eae05, 0xa9a8c4c5, 0x5e7a70ea, 0xa9a4216b, - 0x5e763395, 0xa99f7e46, - 0x5e71f606, 0xa99adb56, 0x5e6db83d, 0xa996389b, 0x5e697a39, 0xa9919616, - 0x5e653bfc, 0xa98cf3c6, - 0x5e60fd84, 0xa98851ac, 0x5e5cbed1, 0xa983afc6, 0x5e587fe5, 0xa97f0e16, - 0x5e5440be, 0xa97a6c9c, - 0x5e50015d, 0xa975cb57, 0x5e4bc1c2, 0xa9712a47, 0x5e4781ed, 0xa96c896c, - 0x5e4341de, 0xa967e8c7, - 0x5e3f0194, 0xa9634858, 0x5e3ac110, 0xa95ea81d, 0x5e368053, 0xa95a0819, - 0x5e323f5b, 0xa9556849, - 0x5e2dfe29, 0xa950c8b0, 0x5e29bcbd, 0xa94c294b, 0x5e257b17, 0xa9478a1c, - 0x5e213936, 0xa942eb23, - 0x5e1cf71c, 0xa93e4c5f, 0x5e18b4c8, 0xa939add1, 0x5e147239, 0xa9350f78, - 0x5e102f71, 0xa9307155, - 0x5e0bec6e, 0xa92bd367, 0x5e07a932, 0xa92735af, 0x5e0365bb, 0xa922982c, - 0x5dff220b, 0xa91dfadf, - 0x5dfade20, 0xa9195dc7, 0x5df699fc, 0xa914c0e6, 0x5df2559e, 0xa9102439, - 0x5dee1105, 0xa90b87c3, - 0x5de9cc33, 0xa906eb82, 0x5de58727, 0xa9024f76, 0x5de141e1, 0xa8fdb3a1, - 0x5ddcfc61, 0xa8f91801, - 0x5dd8b6a7, 0xa8f47c97, 0x5dd470b3, 0xa8efe162, 0x5dd02a85, 0xa8eb4663, - 0x5dcbe41d, 0xa8e6ab9a, - 0x5dc79d7c, 0xa8e21106, 0x5dc356a1, 0xa8dd76a9, 0x5dbf0f8c, 0xa8d8dc81, - 0x5dbac83d, 0xa8d4428f, - 0x5db680b4, 0xa8cfa8d2, 0x5db238f1, 0xa8cb0f4b, 0x5dadf0f5, 0xa8c675fb, - 0x5da9a8bf, 0xa8c1dce0, - 0x5da5604f, 0xa8bd43fa, 0x5da117a5, 0xa8b8ab4b, 0x5d9ccec2, 0xa8b412d1, - 0x5d9885a5, 0xa8af7a8e, - 0x5d943c4e, 0xa8aae280, 0x5d8ff2bd, 0xa8a64aa8, 0x5d8ba8f3, 0xa8a1b306, - 0x5d875eef, 0xa89d1b99, - 0x5d8314b1, 0xa8988463, 0x5d7eca39, 0xa893ed63, 0x5d7a7f88, 0xa88f5698, - 0x5d76349d, 0xa88ac004, - 0x5d71e979, 0xa88629a5, 0x5d6d9e1b, 0xa881937c, 0x5d695283, 0xa87cfd8a, - 0x5d6506b2, 0xa87867cd, - 0x5d60baa7, 0xa873d246, 0x5d5c6e62, 0xa86f3cf6, 0x5d5821e4, 0xa86aa7db, - 0x5d53d52d, 0xa86612f6, - 0x5d4f883b, 0xa8617e48, 0x5d4b3b10, 0xa85ce9cf, 0x5d46edac, 0xa858558d, - 0x5d42a00e, 0xa853c180, - 0x5d3e5237, 0xa84f2daa, 0x5d3a0426, 0xa84a9a0a, 0x5d35b5db, 0xa84606a0, - 0x5d316757, 0xa841736c, - 0x5d2d189a, 0xa83ce06e, 0x5d28c9a3, 0xa8384da6, 0x5d247a72, 0xa833bb14, - 0x5d202b09, 0xa82f28b9, - 0x5d1bdb65, 0xa82a9693, 0x5d178b89, 0xa82604a4, 0x5d133b72, 0xa82172eb, - 0x5d0eeb23, 0xa81ce169, - 0x5d0a9a9a, 0xa818501c, 0x5d0649d7, 0xa813bf06, 0x5d01f8dc, 0xa80f2e26, - 0x5cfda7a7, 0xa80a9d7c, - 0x5cf95638, 0xa8060d08, 0x5cf50490, 0xa8017ccb, 0x5cf0b2af, 0xa7fcecc4, - 0x5cec6095, 0xa7f85cf3, - 0x5ce80e41, 0xa7f3cd59, 0x5ce3bbb4, 0xa7ef3df5, 0x5cdf68ed, 0xa7eaaec7, - 0x5cdb15ed, 0xa7e61fd0, - 0x5cd6c2b5, 0xa7e1910f, 0x5cd26f42, 0xa7dd0284, 0x5cce1b97, 0xa7d8742f, - 0x5cc9c7b2, 0xa7d3e611, - 0x5cc57394, 0xa7cf582a, 0x5cc11f3d, 0xa7caca79, 0x5cbccaac, 0xa7c63cfe, - 0x5cb875e3, 0xa7c1afb9, - 0x5cb420e0, 0xa7bd22ac, 0x5cafcba4, 0xa7b895d4, 0x5cab762f, 0xa7b40933, - 0x5ca72080, 0xa7af7cc8, - 0x5ca2ca99, 0xa7aaf094, 0x5c9e7478, 0xa7a66497, 0x5c9a1e1e, 0xa7a1d8d0, - 0x5c95c78b, 0xa79d4d3f, - 0x5c9170bf, 0xa798c1e5, 0x5c8d19ba, 0xa79436c1, 0x5c88c27c, 0xa78fabd4, - 0x5c846b05, 0xa78b211e, - 0x5c801354, 0xa786969e, 0x5c7bbb6b, 0xa7820c55, 0x5c776348, 0xa77d8242, - 0x5c730aed, 0xa778f866, - 0x5c6eb258, 0xa7746ec0, 0x5c6a598b, 0xa76fe551, 0x5c660084, 0xa76b5c19, - 0x5c61a745, 0xa766d317, - 0x5c5d4dcc, 0xa7624a4d, 0x5c58f41a, 0xa75dc1b8, 0x5c549a30, 0xa759395b, - 0x5c50400d, 0xa754b134, - 0x5c4be5b0, 0xa7502943, 0x5c478b1b, 0xa74ba18a, 0x5c43304d, 0xa7471a07, - 0x5c3ed545, 0xa74292bb, - 0x5c3a7a05, 0xa73e0ba5, 0x5c361e8c, 0xa73984c7, 0x5c31c2db, 0xa734fe1f, - 0x5c2d66f0, 0xa73077ae, - 0x5c290acc, 0xa72bf174, 0x5c24ae70, 0xa7276b70, 0x5c2051db, 0xa722e5a3, - 0x5c1bf50d, 0xa71e600d, - 0x5c179806, 0xa719daae, 0x5c133ac6, 0xa7155586, 0x5c0edd4e, 0xa710d095, - 0x5c0a7f9c, 0xa70c4bda, - 0x5c0621b2, 0xa707c757, 0x5c01c38f, 0xa703430a, 0x5bfd6534, 0xa6febef4, - 0x5bf906a0, 0xa6fa3b15, - 0x5bf4a7d2, 0xa6f5b76d, 0x5bf048cd, 0xa6f133fc, 0x5bebe98e, 0xa6ecb0c2, - 0x5be78a17, 0xa6e82dbe, - 0x5be32a67, 0xa6e3aaf2, 0x5bdeca7f, 0xa6df285d, 0x5bda6a5d, 0xa6daa5fe, - 0x5bd60a03, 0xa6d623d7, - 0x5bd1a971, 0xa6d1a1e7, 0x5bcd48a6, 0xa6cd202d, 0x5bc8e7a2, 0xa6c89eab, - 0x5bc48666, 0xa6c41d60, - 0x5bc024f0, 0xa6bf9c4b, 0x5bbbc343, 0xa6bb1b6e, 0x5bb7615d, 0xa6b69ac8, - 0x5bb2ff3e, 0xa6b21a59, - 0x5bae9ce7, 0xa6ad9a21, 0x5baa3a57, 0xa6a91a20, 0x5ba5d78e, 0xa6a49a56, - 0x5ba1748d, 0xa6a01ac4, - 0x5b9d1154, 0xa69b9b68, 0x5b98ade2, 0xa6971c44, 0x5b944a37, 0xa6929d57, - 0x5b8fe654, 0xa68e1ea1, - 0x5b8b8239, 0xa689a022, 0x5b871de5, 0xa68521da, 0x5b82b958, 0xa680a3ca, - 0x5b7e5493, 0xa67c25f0, - 0x5b79ef96, 0xa677a84e, 0x5b758a60, 0xa6732ae3, 0x5b7124f2, 0xa66eadb0, - 0x5b6cbf4c, 0xa66a30b3, - 0x5b68596d, 0xa665b3ee, 0x5b63f355, 0xa6613760, 0x5b5f8d06, 0xa65cbb0a, - 0x5b5b267e, 0xa6583eeb, - 0x5b56bfbd, 0xa653c303, 0x5b5258c4, 0xa64f4752, 0x5b4df193, 0xa64acbd9, - 0x5b498a2a, 0xa6465097, - 0x5b452288, 0xa641d58c, 0x5b40baae, 0xa63d5ab9, 0x5b3c529c, 0xa638e01d, - 0x5b37ea51, 0xa63465b9, - 0x5b3381ce, 0xa62feb8b, 0x5b2f1913, 0xa62b7196, 0x5b2ab020, 0xa626f7d7, - 0x5b2646f4, 0xa6227e50, - 0x5b21dd90, 0xa61e0501, 0x5b1d73f4, 0xa6198be9, 0x5b190a20, 0xa6151308, - 0x5b14a014, 0xa6109a5f, - 0x5b1035cf, 0xa60c21ee, 0x5b0bcb52, 0xa607a9b4, 0x5b07609d, 0xa60331b1, - 0x5b02f5b0, 0xa5feb9e6, - 0x5afe8a8b, 0xa5fa4252, 0x5afa1f2e, 0xa5f5caf6, 0x5af5b398, 0xa5f153d2, - 0x5af147ca, 0xa5ecdce5, - 0x5aecdbc5, 0xa5e8662f, 0x5ae86f87, 0xa5e3efb1, 0x5ae40311, 0xa5df796b, - 0x5adf9663, 0xa5db035c, - 0x5adb297d, 0xa5d68d85, 0x5ad6bc5f, 0xa5d217e6, 0x5ad24f09, 0xa5cda27e, - 0x5acde17b, 0xa5c92d4e, - 0x5ac973b5, 0xa5c4b855, 0x5ac505b7, 0xa5c04395, 0x5ac09781, 0xa5bbcf0b, - 0x5abc2912, 0xa5b75aba, - 0x5ab7ba6c, 0xa5b2e6a0, 0x5ab34b8e, 0xa5ae72be, 0x5aaedc78, 0xa5a9ff14, - 0x5aaa6d2b, 0xa5a58ba1, - 0x5aa5fda5, 0xa5a11866, 0x5aa18de7, 0xa59ca563, 0x5a9d1df1, 0xa5983297, - 0x5a98adc4, 0xa593c004, - 0x5a943d5e, 0xa58f4da8, 0x5a8fccc1, 0xa58adb84, 0x5a8b5bec, 0xa5866997, - 0x5a86eadf, 0xa581f7e3, - 0x5a82799a, 0xa57d8666, 0x5a7e081d, 0xa5791521, 0x5a799669, 0xa574a414, - 0x5a75247c, 0xa570333f, - 0x5a70b258, 0xa56bc2a2, 0x5a6c3ffc, 0xa567523c, 0x5a67cd69, 0xa562e20f, - 0x5a635a9d, 0xa55e7219, - 0x5a5ee79a, 0xa55a025b, 0x5a5a745f, 0xa55592d5, 0x5a5600ec, 0xa5512388, - 0x5a518d42, 0xa54cb472, - 0x5a4d1960, 0xa5484594, 0x5a48a546, 0xa543d6ee, 0x5a4430f5, 0xa53f687f, - 0x5a3fbc6b, 0xa53afa49, - 0x5a3b47ab, 0xa5368c4b, 0x5a36d2b2, 0xa5321e85, 0x5a325d82, 0xa52db0f7, - 0x5a2de81a, 0xa52943a1, - 0x5a29727b, 0xa524d683, 0x5a24fca4, 0xa520699d, 0x5a208695, 0xa51bfcef, - 0x5a1c104f, 0xa5179079, - 0x5a1799d1, 0xa513243b, 0x5a13231b, 0xa50eb836, 0x5a0eac2e, 0xa50a4c68, - 0x5a0a350a, 0xa505e0d2, - 0x5a05bdae, 0xa5017575, 0x5a01461a, 0xa4fd0a50, 0x59fcce4f, 0xa4f89f63, - 0x59f8564c, 0xa4f434ae, - 0x59f3de12, 0xa4efca31, 0x59ef65a1, 0xa4eb5fec, 0x59eaecf8, 0xa4e6f5e0, - 0x59e67417, 0xa4e28c0c, - 0x59e1faff, 0xa4de2270, 0x59dd81b0, 0xa4d9b90c, 0x59d90829, 0xa4d54fe0, - 0x59d48e6a, 0xa4d0e6ed, - 0x59d01475, 0xa4cc7e32, 0x59cb9a47, 0xa4c815af, 0x59c71fe3, 0xa4c3ad64, - 0x59c2a547, 0xa4bf4552, - 0x59be2a74, 0xa4badd78, 0x59b9af69, 0xa4b675d6, 0x59b53427, 0xa4b20e6d, - 0x59b0b8ae, 0xa4ada73c, - 0x59ac3cfd, 0xa4a94043, 0x59a7c115, 0xa4a4d982, 0x59a344f6, 0xa4a072fa, - 0x599ec8a0, 0xa49c0cab, - 0x599a4c12, 0xa497a693, 0x5995cf4d, 0xa49340b4, 0x59915250, 0xa48edb0e, - 0x598cd51d, 0xa48a75a0, - 0x598857b2, 0xa486106a, 0x5983da10, 0xa481ab6d, 0x597f5c36, 0xa47d46a8, - 0x597ade26, 0xa478e21b, - 0x59765fde, 0xa4747dc7, 0x5971e15f, 0xa47019ac, 0x596d62a9, 0xa46bb5c9, - 0x5968e3bc, 0xa467521e, - 0x59646498, 0xa462eeac, 0x595fe53c, 0xa45e8b73, 0x595b65aa, 0xa45a2872, - 0x5956e5e0, 0xa455c5a9, - 0x595265df, 0xa4516319, 0x594de5a7, 0xa44d00c2, 0x59496538, 0xa4489ea3, - 0x5944e492, 0xa4443cbd, - 0x594063b5, 0xa43fdb10, 0x593be2a0, 0xa43b799a, 0x59376155, 0xa437185e, - 0x5932dfd3, 0xa432b75a, - 0x592e5e19, 0xa42e568f, 0x5929dc29, 0xa429f5fd, 0x59255a02, 0xa42595a3, - 0x5920d7a3, 0xa4213581, - 0x591c550e, 0xa41cd599, 0x5917d242, 0xa41875e9, 0x59134f3e, 0xa4141672, - 0x590ecc04, 0xa40fb733, - 0x590a4893, 0xa40b582e, 0x5905c4eb, 0xa406f960, 0x5901410c, 0xa4029acc, - 0x58fcbcf6, 0xa3fe3c71, - 0x58f838a9, 0xa3f9de4e, 0x58f3b426, 0xa3f58064, 0x58ef2f6b, 0xa3f122b2, - 0x58eaaa7a, 0xa3ecc53a, - 0x58e62552, 0xa3e867fa, 0x58e19ff3, 0xa3e40af3, 0x58dd1a5d, 0xa3dfae25, - 0x58d89490, 0xa3db5190, - 0x58d40e8c, 0xa3d6f534, 0x58cf8852, 0xa3d29910, 0x58cb01e1, 0xa3ce3d25, - 0x58c67b39, 0xa3c9e174, - 0x58c1f45b, 0xa3c585fb, 0x58bd6d45, 0xa3c12abb, 0x58b8e5f9, 0xa3bccfb3, - 0x58b45e76, 0xa3b874e5, - 0x58afd6bd, 0xa3b41a50, 0x58ab4ecc, 0xa3afbff3, 0x58a6c6a5, 0xa3ab65d0, - 0x58a23e48, 0xa3a70be6, - 0x589db5b3, 0xa3a2b234, 0x58992ce9, 0xa39e58bb, 0x5894a3e7, 0xa399ff7c, - 0x58901aaf, 0xa395a675, - 0x588b9140, 0xa3914da8, 0x5887079a, 0xa38cf513, 0x58827dbe, 0xa3889cb8, - 0x587df3ab, 0xa3844495, - 0x58796962, 0xa37fecac, 0x5874dee2, 0xa37b94fb, 0x5870542c, 0xa3773d84, - 0x586bc93f, 0xa372e646, - 0x58673e1b, 0xa36e8f41, 0x5862b2c1, 0xa36a3875, 0x585e2730, 0xa365e1e2, - 0x58599b69, 0xa3618b88, - 0x58550f6c, 0xa35d3567, 0x58508338, 0xa358df80, 0x584bf6cd, 0xa35489d1, - 0x58476a2c, 0xa350345c, - 0x5842dd54, 0xa34bdf20, 0x583e5047, 0xa3478a1d, 0x5839c302, 0xa3433554, - 0x58353587, 0xa33ee0c3, - 0x5830a7d6, 0xa33a8c6c, 0x582c19ef, 0xa336384e, 0x58278bd1, 0xa331e469, - 0x5822fd7c, 0xa32d90be, - 0x581e6ef1, 0xa3293d4b, 0x5819e030, 0xa324ea13, 0x58155139, 0xa3209713, - 0x5810c20b, 0xa31c444c, - 0x580c32a7, 0xa317f1bf, 0x5807a30d, 0xa3139f6b, 0x5803133c, 0xa30f4d51, - 0x57fe8335, 0xa30afb70, - 0x57f9f2f8, 0xa306a9c8, 0x57f56284, 0xa3025859, 0x57f0d1da, 0xa2fe0724, - 0x57ec40fa, 0xa2f9b629, - 0x57e7afe4, 0xa2f56566, 0x57e31e97, 0xa2f114dd, 0x57de8d15, 0xa2ecc48e, - 0x57d9fb5c, 0xa2e87477, - 0x57d5696d, 0xa2e4249b, 0x57d0d747, 0xa2dfd4f7, 0x57cc44ec, 0xa2db858e, - 0x57c7b25a, 0xa2d7365d, - 0x57c31f92, 0xa2d2e766, 0x57be8c94, 0xa2ce98a9, 0x57b9f960, 0xa2ca4a25, - 0x57b565f6, 0xa2c5fbda, - 0x57b0d256, 0xa2c1adc9, 0x57ac3e80, 0xa2bd5ff2, 0x57a7aa73, 0xa2b91254, - 0x57a31631, 0xa2b4c4f0, - 0x579e81b8, 0xa2b077c5, 0x5799ed0a, 0xa2ac2ad3, 0x57955825, 0xa2a7de1c, - 0x5790c30a, 0xa2a3919e, - 0x578c2dba, 0xa29f4559, 0x57879833, 0xa29af94e, 0x57830276, 0xa296ad7d, - 0x577e6c84, 0xa29261e5, - 0x5779d65b, 0xa28e1687, 0x57753ffc, 0xa289cb63, 0x5770a968, 0xa2858078, - 0x576c129d, 0xa28135c7, - 0x57677b9d, 0xa27ceb4f, 0x5762e467, 0xa278a111, 0x575e4cfa, 0xa274570d, - 0x5759b558, 0xa2700d43, - 0x57551d80, 0xa26bc3b2, 0x57508572, 0xa2677a5b, 0x574bed2f, 0xa263313e, - 0x574754b5, 0xa25ee85b, - 0x5742bc06, 0xa25a9fb1, 0x573e2320, 0xa2565741, 0x57398a05, 0xa2520f0b, - 0x5734f0b5, 0xa24dc70f, - 0x5730572e, 0xa2497f4c, 0x572bbd71, 0xa24537c3, 0x5727237f, 0xa240f074, - 0x57228957, 0xa23ca95f, - 0x571deefa, 0xa2386284, 0x57195466, 0xa2341be3, 0x5714b99d, 0xa22fd57b, - 0x57101e9e, 0xa22b8f4d, - 0x570b8369, 0xa2274959, 0x5706e7ff, 0xa223039f, 0x57024c5f, 0xa21ebe1f, - 0x56fdb08a, 0xa21a78d9, - 0x56f9147e, 0xa21633cd, 0x56f4783d, 0xa211eefb, 0x56efdbc7, 0xa20daa62, - 0x56eb3f1a, 0xa2096604, - 0x56e6a239, 0xa20521e0, 0x56e20521, 0xa200ddf5, 0x56dd67d4, 0xa1fc9a45, - 0x56d8ca51, 0xa1f856ce, - 0x56d42c99, 0xa1f41392, 0x56cf8eab, 0xa1efd08f, 0x56caf088, 0xa1eb8dc7, - 0x56c6522f, 0xa1e74b38, - 0x56c1b3a1, 0xa1e308e4, 0x56bd14dd, 0xa1dec6ca, 0x56b875e4, 0xa1da84e9, - 0x56b3d6b5, 0xa1d64343, - 0x56af3750, 0xa1d201d7, 0x56aa97b7, 0xa1cdc0a5, 0x56a5f7e7, 0xa1c97fad, - 0x56a157e3, 0xa1c53ef0, - 0x569cb7a8, 0xa1c0fe6c, 0x56981739, 0xa1bcbe22, 0x56937694, 0xa1b87e13, - 0x568ed5b9, 0xa1b43e3e, - 0x568a34a9, 0xa1affea3, 0x56859364, 0xa1abbf42, 0x5680f1ea, 0xa1a7801b, - 0x567c503a, 0xa1a3412f, - 0x5677ae54, 0xa19f027c, 0x56730c3a, 0xa19ac404, 0x566e69ea, 0xa19685c7, - 0x5669c765, 0xa19247c3, - 0x566524aa, 0xa18e09fa, 0x566081ba, 0xa189cc6b, 0x565bde95, 0xa1858f16, - 0x56573b3b, 0xa18151fb, - 0x565297ab, 0xa17d151b, 0x564df3e6, 0xa178d875, 0x56494fec, 0xa1749c09, - 0x5644abbc, 0xa1705fd8, - 0x56400758, 0xa16c23e1, 0x563b62be, 0xa167e824, 0x5636bdef, 0xa163aca2, - 0x563218eb, 0xa15f715a, - 0x562d73b2, 0xa15b364d, 0x5628ce43, 0xa156fb79, 0x5624289f, 0xa152c0e1, - 0x561f82c7, 0xa14e8682, - 0x561adcb9, 0xa14a4c5e, 0x56163676, 0xa1461275, 0x56118ffe, 0xa141d8c5, - 0x560ce950, 0xa13d9f51, - 0x5608426e, 0xa1396617, 0x56039b57, 0xa1352d17, 0x55fef40a, 0xa130f451, - 0x55fa4c89, 0xa12cbbc7, - 0x55f5a4d2, 0xa1288376, 0x55f0fce7, 0xa1244b61, 0x55ec54c6, 0xa1201385, - 0x55e7ac71, 0xa11bdbe4, - 0x55e303e6, 0xa117a47e, 0x55de5b27, 0xa1136d52, 0x55d9b232, 0xa10f3661, - 0x55d50909, 0xa10affab, - 0x55d05faa, 0xa106c92f, 0x55cbb617, 0xa10292ed, 0x55c70c4f, 0xa0fe5ce6, - 0x55c26251, 0xa0fa271a, - 0x55bdb81f, 0xa0f5f189, 0x55b90db8, 0xa0f1bc32, 0x55b4631d, 0xa0ed8715, - 0x55afb84c, 0xa0e95234, - 0x55ab0d46, 0xa0e51d8c, 0x55a6620c, 0xa0e0e920, 0x55a1b69d, 0xa0dcb4ee, - 0x559d0af9, 0xa0d880f7, - 0x55985f20, 0xa0d44d3b, 0x5593b312, 0xa0d019b9, 0x558f06d0, 0xa0cbe672, - 0x558a5a58, 0xa0c7b366, - 0x5585adad, 0xa0c38095, 0x558100cc, 0xa0bf4dfe, 0x557c53b6, 0xa0bb1ba2, - 0x5577a66c, 0xa0b6e981, - 0x5572f8ed, 0xa0b2b79b, 0x556e4b39, 0xa0ae85ef, 0x55699d51, 0xa0aa547e, - 0x5564ef34, 0xa0a62348, - 0x556040e2, 0xa0a1f24d, 0x555b925c, 0xa09dc18d, 0x5556e3a1, 0xa0999107, - 0x555234b1, 0xa09560bc, - 0x554d858d, 0xa09130ad, 0x5548d634, 0xa08d00d8, 0x554426a7, 0xa088d13e, - 0x553f76e4, 0xa084a1de, - 0x553ac6ee, 0xa08072ba, 0x553616c2, 0xa07c43d1, 0x55316663, 0xa0781522, - 0x552cb5ce, 0xa073e6af, - 0x55280505, 0xa06fb876, 0x55235408, 0xa06b8a78, 0x551ea2d6, 0xa0675cb6, - 0x5519f16f, 0xa0632f2e, - 0x55153fd4, 0xa05f01e1, 0x55108e05, 0xa05ad4cf, 0x550bdc01, 0xa056a7f9, - 0x550729c9, 0xa0527b5d, - 0x5502775c, 0xa04e4efc, 0x54fdc4ba, 0xa04a22d7, 0x54f911e5, 0xa045f6ec, - 0x54f45edb, 0xa041cb3c, - 0x54efab9c, 0xa03d9fc8, 0x54eaf829, 0xa039748e, 0x54e64482, 0xa0354990, - 0x54e190a6, 0xa0311ecd, - 0x54dcdc96, 0xa02cf444, 0x54d82852, 0xa028c9f7, 0x54d373d9, 0xa0249fe5, - 0x54cebf2c, 0xa020760e, - 0x54ca0a4b, 0xa01c4c73, 0x54c55535, 0xa0182312, 0x54c09feb, 0xa013f9ed, - 0x54bbea6d, 0xa00fd102, - 0x54b734ba, 0xa00ba853, 0x54b27ed3, 0xa0077fdf, 0x54adc8b8, 0xa00357a7, - 0x54a91269, 0x9fff2fa9, - 0x54a45be6, 0x9ffb07e7, 0x549fa52e, 0x9ff6e060, 0x549aee42, 0x9ff2b914, - 0x54963722, 0x9fee9204, - 0x54917fce, 0x9fea6b2f, 0x548cc845, 0x9fe64495, 0x54881089, 0x9fe21e36, - 0x54835898, 0x9fddf812, - 0x547ea073, 0x9fd9d22a, 0x5479e81a, 0x9fd5ac7d, 0x54752f8d, 0x9fd1870c, - 0x547076cc, 0x9fcd61d6, - 0x546bbdd7, 0x9fc93cdb, 0x546704ae, 0x9fc5181b, 0x54624b50, 0x9fc0f397, - 0x545d91bf, 0x9fbccf4f, - 0x5458d7f9, 0x9fb8ab41, 0x54541e00, 0x9fb4876f, 0x544f63d2, 0x9fb063d9, - 0x544aa971, 0x9fac407e, - 0x5445eedb, 0x9fa81d5e, 0x54413412, 0x9fa3fa79, 0x543c7914, 0x9f9fd7d1, - 0x5437bde3, 0x9f9bb563, - 0x5433027d, 0x9f979331, 0x542e46e4, 0x9f93713b, 0x54298b17, 0x9f8f4f80, - 0x5424cf16, 0x9f8b2e00, - 0x542012e1, 0x9f870cbc, 0x541b5678, 0x9f82ebb4, 0x541699db, 0x9f7ecae7, - 0x5411dd0a, 0x9f7aaa55, - 0x540d2005, 0x9f7689ff, 0x540862cd, 0x9f7269e5, 0x5403a561, 0x9f6e4a06, - 0x53fee7c1, 0x9f6a2a63, - 0x53fa29ed, 0x9f660afb, 0x53f56be5, 0x9f61ebcf, 0x53f0adaa, 0x9f5dccde, - 0x53ebef3a, 0x9f59ae29, - 0x53e73097, 0x9f558fb0, 0x53e271c0, 0x9f517173, 0x53ddb2b6, 0x9f4d5371, - 0x53d8f378, 0x9f4935aa, - 0x53d43406, 0x9f45181f, 0x53cf7460, 0x9f40fad0, 0x53cab486, 0x9f3cddbd, - 0x53c5f479, 0x9f38c0e5, - 0x53c13439, 0x9f34a449, 0x53bc73c4, 0x9f3087e9, 0x53b7b31c, 0x9f2c6bc5, - 0x53b2f240, 0x9f284fdc, - 0x53ae3131, 0x9f24342f, 0x53a96fee, 0x9f2018bd, 0x53a4ae77, 0x9f1bfd88, - 0x539feccd, 0x9f17e28e, - 0x539b2af0, 0x9f13c7d0, 0x539668de, 0x9f0fad4e, 0x5391a699, 0x9f0b9307, - 0x538ce421, 0x9f0778fd, - 0x53882175, 0x9f035f2e, 0x53835e95, 0x9eff459b, 0x537e9b82, 0x9efb2c44, - 0x5379d83c, 0x9ef71328, - 0x537514c2, 0x9ef2fa49, 0x53705114, 0x9eeee1a5, 0x536b8d33, 0x9eeac93e, - 0x5366c91f, 0x9ee6b112, - 0x536204d7, 0x9ee29922, 0x535d405c, 0x9ede816e, 0x53587bad, 0x9eda69f6, - 0x5353b6cb, 0x9ed652ba, - 0x534ef1b5, 0x9ed23bb9, 0x534a2c6c, 0x9ece24f5, 0x534566f0, 0x9eca0e6d, - 0x5340a140, 0x9ec5f820, - 0x533bdb5d, 0x9ec1e210, 0x53371547, 0x9ebdcc3b, 0x53324efd, 0x9eb9b6a3, - 0x532d8880, 0x9eb5a146, - 0x5328c1d0, 0x9eb18c26, 0x5323faec, 0x9ead7742, 0x531f33d5, 0x9ea96299, - 0x531a6c8b, 0x9ea54e2d, - 0x5315a50e, 0x9ea139fd, 0x5310dd5d, 0x9e9d2608, 0x530c1579, 0x9e991250, - 0x53074d62, 0x9e94fed4, - 0x53028518, 0x9e90eb94, 0x52fdbc9a, 0x9e8cd890, 0x52f8f3e9, 0x9e88c5c9, - 0x52f42b05, 0x9e84b33d, - 0x52ef61ee, 0x9e80a0ee, 0x52ea98a4, 0x9e7c8eda, 0x52e5cf27, 0x9e787d03, - 0x52e10576, 0x9e746b68, - 0x52dc3b92, 0x9e705a09, 0x52d7717b, 0x9e6c48e7, 0x52d2a732, 0x9e683800, - 0x52cddcb5, 0x9e642756, - 0x52c91204, 0x9e6016e8, 0x52c44721, 0x9e5c06b6, 0x52bf7c0b, 0x9e57f6c0, - 0x52bab0c2, 0x9e53e707, - 0x52b5e546, 0x9e4fd78a, 0x52b11996, 0x9e4bc849, 0x52ac4db4, 0x9e47b944, - 0x52a7819f, 0x9e43aa7c, - 0x52a2b556, 0x9e3f9bf0, 0x529de8db, 0x9e3b8da0, 0x52991c2d, 0x9e377f8c, - 0x52944f4c, 0x9e3371b5, - 0x528f8238, 0x9e2f641b, 0x528ab4f1, 0x9e2b56bc, 0x5285e777, 0x9e27499a, - 0x528119ca, 0x9e233cb4, - 0x527c4bea, 0x9e1f300b, 0x52777dd7, 0x9e1b239e, 0x5272af92, 0x9e17176d, - 0x526de11a, 0x9e130b79, - 0x5269126e, 0x9e0effc1, 0x52644390, 0x9e0af446, 0x525f7480, 0x9e06e907, - 0x525aa53c, 0x9e02de04, - 0x5255d5c5, 0x9dfed33e, 0x5251061c, 0x9dfac8b4, 0x524c3640, 0x9df6be67, - 0x52476631, 0x9df2b456, - 0x524295f0, 0x9deeaa82, 0x523dc57b, 0x9deaa0ea, 0x5238f4d4, 0x9de6978f, - 0x523423fb, 0x9de28e70, - 0x522f52ee, 0x9dde858e, 0x522a81af, 0x9dda7ce9, 0x5225b03d, 0x9dd6747f, - 0x5220de99, 0x9dd26c53, - 0x521c0cc2, 0x9dce6463, 0x52173ab8, 0x9dca5caf, 0x5212687b, 0x9dc65539, - 0x520d960c, 0x9dc24dfe, - 0x5208c36a, 0x9dbe4701, 0x5203f096, 0x9dba4040, 0x51ff1d8f, 0x9db639bb, - 0x51fa4a56, 0x9db23373, - 0x51f576ea, 0x9dae2d68, 0x51f0a34b, 0x9daa279a, 0x51ebcf7a, 0x9da62208, - 0x51e6fb76, 0x9da21cb2, - 0x51e22740, 0x9d9e179a, 0x51dd52d7, 0x9d9a12be, 0x51d87e3c, 0x9d960e1f, - 0x51d3a96f, 0x9d9209bd, - 0x51ced46e, 0x9d8e0597, 0x51c9ff3c, 0x9d8a01ae, 0x51c529d7, 0x9d85fe02, - 0x51c0543f, 0x9d81fa92, - 0x51bb7e75, 0x9d7df75f, 0x51b6a879, 0x9d79f469, 0x51b1d24a, 0x9d75f1b0, - 0x51acfbe9, 0x9d71ef34, - 0x51a82555, 0x9d6decf4, 0x51a34e8f, 0x9d69eaf1, 0x519e7797, 0x9d65e92b, - 0x5199a06d, 0x9d61e7a2, - 0x5194c910, 0x9d5de656, 0x518ff180, 0x9d59e546, 0x518b19bf, 0x9d55e473, - 0x518641cb, 0x9d51e3dd, - 0x518169a5, 0x9d4de385, 0x517c914c, 0x9d49e368, 0x5177b8c2, 0x9d45e389, - 0x5172e005, 0x9d41e3e7, - 0x516e0715, 0x9d3de482, 0x51692df4, 0x9d39e559, 0x516454a0, 0x9d35e66e, - 0x515f7b1a, 0x9d31e7bf, - 0x515aa162, 0x9d2de94d, 0x5155c778, 0x9d29eb19, 0x5150ed5c, 0x9d25ed21, - 0x514c130d, 0x9d21ef66, - 0x5147388c, 0x9d1df1e9, 0x51425dd9, 0x9d19f4a8, 0x513d82f4, 0x9d15f7a4, - 0x5138a7dd, 0x9d11fadd, - 0x5133cc94, 0x9d0dfe54, 0x512ef119, 0x9d0a0207, 0x512a156b, 0x9d0605f7, - 0x5125398c, 0x9d020a25, - 0x51205d7b, 0x9cfe0e8f, 0x511b8137, 0x9cfa1337, 0x5116a4c1, 0x9cf6181c, - 0x5111c81a, 0x9cf21d3d, - 0x510ceb40, 0x9cee229c, 0x51080e35, 0x9cea2838, 0x510330f7, 0x9ce62e11, - 0x50fe5388, 0x9ce23427, - 0x50f975e6, 0x9cde3a7b, 0x50f49813, 0x9cda410b, 0x50efba0d, 0x9cd647d9, - 0x50eadbd6, 0x9cd24ee4, - 0x50e5fd6d, 0x9cce562c, 0x50e11ed2, 0x9cca5db1, 0x50dc4005, 0x9cc66573, - 0x50d76106, 0x9cc26d73, - 0x50d281d5, 0x9cbe75b0, 0x50cda272, 0x9cba7e2a, 0x50c8c2de, 0x9cb686e1, - 0x50c3e317, 0x9cb28fd5, - 0x50bf031f, 0x9cae9907, 0x50ba22f5, 0x9caaa276, 0x50b5429a, 0x9ca6ac23, - 0x50b0620c, 0x9ca2b60c, - 0x50ab814d, 0x9c9ec033, 0x50a6a05c, 0x9c9aca97, 0x50a1bf39, 0x9c96d539, - 0x509cdde4, 0x9c92e017, - 0x5097fc5e, 0x9c8eeb34, 0x50931aa6, 0x9c8af68d, 0x508e38bd, 0x9c870224, - 0x508956a1, 0x9c830df8, - 0x50847454, 0x9c7f1a0a, 0x507f91d5, 0x9c7b2659, 0x507aaf25, 0x9c7732e5, - 0x5075cc43, 0x9c733faf, - 0x5070e92f, 0x9c6f4cb6, 0x506c05ea, 0x9c6b59fa, 0x50672273, 0x9c67677c, - 0x50623ecb, 0x9c63753c, - 0x505d5af1, 0x9c5f8339, 0x505876e5, 0x9c5b9173, 0x505392a8, 0x9c579feb, - 0x504eae39, 0x9c53aea0, - 0x5049c999, 0x9c4fbd93, 0x5044e4c7, 0x9c4bccc3, 0x503fffc4, 0x9c47dc31, - 0x503b1a8f, 0x9c43ebdc, - 0x50363529, 0x9c3ffbc5, 0x50314f91, 0x9c3c0beb, 0x502c69c8, 0x9c381c4f, - 0x502783cd, 0x9c342cf0, - 0x50229da1, 0x9c303dcf, 0x501db743, 0x9c2c4eec, 0x5018d0b4, 0x9c286046, - 0x5013e9f4, 0x9c2471de, - 0x500f0302, 0x9c2083b3, 0x500a1bdf, 0x9c1c95c6, 0x5005348a, 0x9c18a816, - 0x50004d04, 0x9c14baa4, - 0x4ffb654d, 0x9c10cd70, 0x4ff67d64, 0x9c0ce07a, 0x4ff1954b, 0x9c08f3c1, - 0x4fecacff, 0x9c050745, - 0x4fe7c483, 0x9c011b08, 0x4fe2dbd5, 0x9bfd2f08, 0x4fddf2f6, 0x9bf94346, - 0x4fd909e5, 0x9bf557c1, - 0x4fd420a4, 0x9bf16c7a, 0x4fcf3731, 0x9bed8171, 0x4fca4d8d, 0x9be996a6, - 0x4fc563b7, 0x9be5ac18, - 0x4fc079b1, 0x9be1c1c8, 0x4fbb8f79, 0x9bddd7b6, 0x4fb6a510, 0x9bd9ede2, - 0x4fb1ba76, 0x9bd6044b, - 0x4faccfab, 0x9bd21af3, 0x4fa7e4af, 0x9bce31d8, 0x4fa2f981, 0x9bca48fa, - 0x4f9e0e22, 0x9bc6605b, - 0x4f992293, 0x9bc277fa, 0x4f9436d2, 0x9bbe8fd6, 0x4f8f4ae0, 0x9bbaa7f0, - 0x4f8a5ebd, 0x9bb6c048, - 0x4f857269, 0x9bb2d8de, 0x4f8085e4, 0x9baef1b2, 0x4f7b992d, 0x9bab0ac3, - 0x4f76ac46, 0x9ba72413, - 0x4f71bf2e, 0x9ba33da0, 0x4f6cd1e5, 0x9b9f576b, 0x4f67e46a, 0x9b9b7174, - 0x4f62f6bf, 0x9b978bbc, - 0x4f5e08e3, 0x9b93a641, 0x4f591ad6, 0x9b8fc104, 0x4f542c98, 0x9b8bdc05, - 0x4f4f3e29, 0x9b87f744, - 0x4f4a4f89, 0x9b8412c1, 0x4f4560b8, 0x9b802e7b, 0x4f4071b6, 0x9b7c4a74, - 0x4f3b8284, 0x9b7866ab, - 0x4f369320, 0x9b748320, 0x4f31a38c, 0x9b709fd3, 0x4f2cb3c7, 0x9b6cbcc4, - 0x4f27c3d1, 0x9b68d9f3, - 0x4f22d3aa, 0x9b64f760, 0x4f1de352, 0x9b61150b, 0x4f18f2c9, 0x9b5d32f4, - 0x4f140210, 0x9b59511c, - 0x4f0f1126, 0x9b556f81, 0x4f0a200b, 0x9b518e24, 0x4f052ec0, 0x9b4dad06, - 0x4f003d43, 0x9b49cc26, - 0x4efb4b96, 0x9b45eb83, 0x4ef659b8, 0x9b420b1f, 0x4ef167aa, 0x9b3e2af9, - 0x4eec756b, 0x9b3a4b11, - 0x4ee782fb, 0x9b366b68, 0x4ee2905a, 0x9b328bfc, 0x4edd9d89, 0x9b2eaccf, - 0x4ed8aa87, 0x9b2acde0, - 0x4ed3b755, 0x9b26ef2f, 0x4ecec3f2, 0x9b2310bc, 0x4ec9d05e, 0x9b1f3288, - 0x4ec4dc99, 0x9b1b5492, - 0x4ebfe8a5, 0x9b1776da, 0x4ebaf47f, 0x9b139960, 0x4eb60029, 0x9b0fbc24, - 0x4eb10ba2, 0x9b0bdf27, - 0x4eac16eb, 0x9b080268, 0x4ea72203, 0x9b0425e8, 0x4ea22ceb, 0x9b0049a5, - 0x4e9d37a3, 0x9afc6da1, - 0x4e984229, 0x9af891db, 0x4e934c80, 0x9af4b654, 0x4e8e56a5, 0x9af0db0b, - 0x4e89609b, 0x9aed0000, - 0x4e846a60, 0x9ae92533, 0x4e7f73f4, 0x9ae54aa5, 0x4e7a7d58, 0x9ae17056, - 0x4e75868c, 0x9add9644, - 0x4e708f8f, 0x9ad9bc71, 0x4e6b9862, 0x9ad5e2dd, 0x4e66a105, 0x9ad20987, - 0x4e61a977, 0x9ace306f, - 0x4e5cb1b9, 0x9aca5795, 0x4e57b9ca, 0x9ac67efb, 0x4e52c1ab, 0x9ac2a69e, - 0x4e4dc95c, 0x9abece80, - 0x4e48d0dd, 0x9abaf6a1, 0x4e43d82d, 0x9ab71eff, 0x4e3edf4d, 0x9ab3479d, - 0x4e39e63d, 0x9aaf7079, - 0x4e34ecfc, 0x9aab9993, 0x4e2ff38b, 0x9aa7c2ec, 0x4e2af9ea, 0x9aa3ec83, - 0x4e260019, 0x9aa01659, - 0x4e210617, 0x9a9c406e, 0x4e1c0be6, 0x9a986ac1, 0x4e171184, 0x9a949552, - 0x4e1216f2, 0x9a90c022, - 0x4e0d1c30, 0x9a8ceb31, 0x4e08213e, 0x9a89167e, 0x4e03261b, 0x9a85420a, - 0x4dfe2ac9, 0x9a816dd5, - 0x4df92f46, 0x9a7d99de, 0x4df43393, 0x9a79c625, 0x4def37b0, 0x9a75f2ac, - 0x4dea3b9d, 0x9a721f71, - 0x4de53f5a, 0x9a6e4c74, 0x4de042e7, 0x9a6a79b6, 0x4ddb4644, 0x9a66a737, - 0x4dd64971, 0x9a62d4f7, - 0x4dd14c6e, 0x9a5f02f5, 0x4dcc4f3b, 0x9a5b3132, 0x4dc751d8, 0x9a575fae, - 0x4dc25445, 0x9a538e68, - 0x4dbd5682, 0x9a4fbd61, 0x4db8588f, 0x9a4bec99, 0x4db35a6c, 0x9a481c0f, - 0x4dae5c19, 0x9a444bc5, - 0x4da95d96, 0x9a407bb9, 0x4da45ee3, 0x9a3cabeb, 0x4d9f6001, 0x9a38dc5d, - 0x4d9a60ee, 0x9a350d0d, - 0x4d9561ac, 0x9a313dfc, 0x4d90623a, 0x9a2d6f2a, 0x4d8b6298, 0x9a29a097, - 0x4d8662c6, 0x9a25d243, - 0x4d8162c4, 0x9a22042d, 0x4d7c6293, 0x9a1e3656, 0x4d776231, 0x9a1a68be, - 0x4d7261a0, 0x9a169b65, - 0x4d6d60df, 0x9a12ce4b, 0x4d685fef, 0x9a0f016f, 0x4d635ece, 0x9a0b34d3, - 0x4d5e5d7e, 0x9a076875, - 0x4d595bfe, 0x9a039c57, 0x4d545a4f, 0x99ffd077, 0x4d4f5870, 0x99fc04d6, - 0x4d4a5661, 0x99f83974, - 0x4d455422, 0x99f46e51, 0x4d4051b4, 0x99f0a36d, 0x4d3b4f16, 0x99ecd8c8, - 0x4d364c48, 0x99e90e62, - 0x4d31494b, 0x99e5443b, 0x4d2c461e, 0x99e17a53, 0x4d2742c2, 0x99ddb0aa, - 0x4d223f36, 0x99d9e73f, - 0x4d1d3b7a, 0x99d61e14, 0x4d18378f, 0x99d25528, 0x4d133374, 0x99ce8c7b, - 0x4d0e2f2a, 0x99cac40d, - 0x4d092ab0, 0x99c6fbde, 0x4d042607, 0x99c333ee, 0x4cff212e, 0x99bf6c3d, - 0x4cfa1c26, 0x99bba4cb, - 0x4cf516ee, 0x99b7dd99, 0x4cf01187, 0x99b416a5, 0x4ceb0bf0, 0x99b04ff0, - 0x4ce6062a, 0x99ac897b, - 0x4ce10034, 0x99a8c345, 0x4cdbfa0f, 0x99a4fd4d, 0x4cd6f3bb, 0x99a13795, - 0x4cd1ed37, 0x999d721c, - 0x4ccce684, 0x9999ace3, 0x4cc7dfa1, 0x9995e7e8, 0x4cc2d88f, 0x9992232d, - 0x4cbdd14e, 0x998e5eb1, - 0x4cb8c9dd, 0x998a9a74, 0x4cb3c23d, 0x9986d676, 0x4caeba6e, 0x998312b7, - 0x4ca9b26f, 0x997f4f38, - 0x4ca4aa41, 0x997b8bf8, 0x4c9fa1e4, 0x9977c8f7, 0x4c9a9958, 0x99740635, - 0x4c95909c, 0x997043b2, - 0x4c9087b1, 0x996c816f, 0x4c8b7e97, 0x9968bf6b, 0x4c86754e, 0x9964fda7, - 0x4c816bd5, 0x99613c22, - 0x4c7c622d, 0x995d7adc, 0x4c775856, 0x9959b9d5, 0x4c724e50, 0x9955f90d, - 0x4c6d441b, 0x99523885, - 0x4c6839b7, 0x994e783d, 0x4c632f23, 0x994ab833, 0x4c5e2460, 0x9946f869, - 0x4c59196f, 0x994338df, - 0x4c540e4e, 0x993f7993, 0x4c4f02fe, 0x993bba87, 0x4c49f77f, 0x9937fbbb, - 0x4c44ebd1, 0x99343d2e, - 0x4c3fdff4, 0x99307ee0, 0x4c3ad3e7, 0x992cc0d2, 0x4c35c7ac, 0x99290303, - 0x4c30bb42, 0x99254574, - 0x4c2baea9, 0x99218824, 0x4c26a1e1, 0x991dcb13, 0x4c2194e9, 0x991a0e42, - 0x4c1c87c3, 0x991651b1, - 0x4c177a6e, 0x9912955f, 0x4c126cea, 0x990ed94c, 0x4c0d5f37, 0x990b1d79, - 0x4c085156, 0x990761e5, - 0x4c034345, 0x9903a691, 0x4bfe3505, 0x98ffeb7d, 0x4bf92697, 0x98fc30a8, - 0x4bf417f9, 0x98f87612, - 0x4bef092d, 0x98f4bbbc, 0x4be9fa32, 0x98f101a6, 0x4be4eb08, 0x98ed47cf, - 0x4bdfdbaf, 0x98e98e38, - 0x4bdacc28, 0x98e5d4e0, 0x4bd5bc72, 0x98e21bc8, 0x4bd0ac8d, 0x98de62f0, - 0x4bcb9c79, 0x98daaa57, - 0x4bc68c36, 0x98d6f1fe, 0x4bc17bc5, 0x98d339e4, 0x4bbc6b25, 0x98cf820b, - 0x4bb75a56, 0x98cbca70, - 0x4bb24958, 0x98c81316, 0x4bad382c, 0x98c45bfb, 0x4ba826d1, 0x98c0a520, - 0x4ba31548, 0x98bcee84, - 0x4b9e0390, 0x98b93828, 0x4b98f1a9, 0x98b5820c, 0x4b93df93, 0x98b1cc30, - 0x4b8ecd4f, 0x98ae1693, - 0x4b89badd, 0x98aa6136, 0x4b84a83b, 0x98a6ac19, 0x4b7f956b, 0x98a2f73c, - 0x4b7a826d, 0x989f429e, - 0x4b756f40, 0x989b8e40, 0x4b705be4, 0x9897da22, 0x4b6b485a, 0x98942643, - 0x4b6634a2, 0x989072a5, - 0x4b6120bb, 0x988cbf46, 0x4b5c0ca5, 0x98890c27, 0x4b56f861, 0x98855948, - 0x4b51e3ee, 0x9881a6a9, - 0x4b4ccf4d, 0x987df449, 0x4b47ba7e, 0x987a422a, 0x4b42a580, 0x9876904a, - 0x4b3d9053, 0x9872deaa, - 0x4b387af9, 0x986f2d4a, 0x4b336570, 0x986b7c2a, 0x4b2e4fb8, 0x9867cb4a, - 0x4b2939d2, 0x98641aa9, - 0x4b2423be, 0x98606a49, 0x4b1f0d7b, 0x985cba28, 0x4b19f70a, 0x98590a48, - 0x4b14e06b, 0x98555aa7, - 0x4b0fc99d, 0x9851ab46, 0x4b0ab2a1, 0x984dfc26, 0x4b059b77, 0x984a4d45, - 0x4b00841f, 0x98469ea4, - 0x4afb6c98, 0x9842f043, 0x4af654e3, 0x983f4223, 0x4af13d00, 0x983b9442, - 0x4aec24ee, 0x9837e6a1, - 0x4ae70caf, 0x98343940, 0x4ae1f441, 0x98308c1f, 0x4adcdba5, 0x982cdf3f, - 0x4ad7c2da, 0x9829329e, - 0x4ad2a9e2, 0x9825863d, 0x4acd90bb, 0x9821da1d, 0x4ac87767, 0x981e2e3c, - 0x4ac35de4, 0x981a829c, - 0x4abe4433, 0x9816d73b, 0x4ab92a54, 0x98132c1b, 0x4ab41046, 0x980f813b, - 0x4aaef60b, 0x980bd69b, - 0x4aa9dba2, 0x98082c3b, 0x4aa4c10b, 0x9804821b, 0x4a9fa645, 0x9800d83c, - 0x4a9a8b52, 0x97fd2e9c, - 0x4a957030, 0x97f9853d, 0x4a9054e1, 0x97f5dc1e, 0x4a8b3963, 0x97f2333f, - 0x4a861db8, 0x97ee8aa0, - 0x4a8101de, 0x97eae242, 0x4a7be5d7, 0x97e73a23, 0x4a76c9a2, 0x97e39245, - 0x4a71ad3e, 0x97dfeaa7, - 0x4a6c90ad, 0x97dc4349, 0x4a6773ee, 0x97d89c2c, 0x4a625701, 0x97d4f54f, - 0x4a5d39e6, 0x97d14eb2, - 0x4a581c9e, 0x97cda855, 0x4a52ff27, 0x97ca0239, 0x4a4de182, 0x97c65c5c, - 0x4a48c3b0, 0x97c2b6c1, - 0x4a43a5b0, 0x97bf1165, 0x4a3e8782, 0x97bb6c4a, 0x4a396926, 0x97b7c76f, - 0x4a344a9d, 0x97b422d4, - 0x4a2f2be6, 0x97b07e7a, 0x4a2a0d01, 0x97acda60, 0x4a24edee, 0x97a93687, - 0x4a1fcead, 0x97a592ed, - 0x4a1aaf3f, 0x97a1ef94, 0x4a158fa3, 0x979e4c7c, 0x4a106fda, 0x979aa9a4, - 0x4a0b4fe2, 0x9797070c, - 0x4a062fbd, 0x979364b5, 0x4a010f6b, 0x978fc29e, 0x49fbeeea, 0x978c20c8, - 0x49f6ce3c, 0x97887f32, - 0x49f1ad61, 0x9784dddc, 0x49ec8c57, 0x97813cc7, 0x49e76b21, 0x977d9bf2, - 0x49e249bc, 0x9779fb5e, - 0x49dd282a, 0x97765b0a, 0x49d8066b, 0x9772baf7, 0x49d2e47e, 0x976f1b24, - 0x49cdc263, 0x976b7b92, - 0x49c8a01b, 0x9767dc41, 0x49c37da5, 0x97643d2f, 0x49be5b02, 0x97609e5f, - 0x49b93832, 0x975cffcf, - 0x49b41533, 0x9759617f, 0x49aef208, 0x9755c370, 0x49a9ceaf, 0x975225a1, - 0x49a4ab28, 0x974e8813, - 0x499f8774, 0x974aeac6, 0x499a6393, 0x97474db9, 0x49953f84, 0x9743b0ed, - 0x49901b48, 0x97401462, - 0x498af6df, 0x973c7817, 0x4985d248, 0x9738dc0d, 0x4980ad84, 0x97354043, - 0x497b8892, 0x9731a4ba, - 0x49766373, 0x972e0971, 0x49713e27, 0x972a6e6a, 0x496c18ae, 0x9726d3a3, - 0x4966f307, 0x9723391c, - 0x4961cd33, 0x971f9ed7, 0x495ca732, 0x971c04d2, 0x49578103, 0x97186b0d, - 0x49525aa7, 0x9714d18a, - 0x494d341e, 0x97113847, 0x49480d68, 0x970d9f45, 0x4942e684, 0x970a0683, - 0x493dbf74, 0x97066e03, - 0x49389836, 0x9702d5c3, 0x493370cb, 0x96ff3dc4, 0x492e4933, 0x96fba605, - 0x4929216e, 0x96f80e88, - 0x4923f97b, 0x96f4774b, 0x491ed15c, 0x96f0e04f, 0x4919a90f, 0x96ed4994, - 0x49148095, 0x96e9b319, - 0x490f57ee, 0x96e61ce0, 0x490a2f1b, 0x96e286e7, 0x4905061a, 0x96def12f, - 0x48ffdcec, 0x96db5bb8, - 0x48fab391, 0x96d7c682, 0x48f58a09, 0x96d4318d, 0x48f06054, 0x96d09cd8, - 0x48eb3672, 0x96cd0865, - 0x48e60c62, 0x96c97432, 0x48e0e227, 0x96c5e040, 0x48dbb7be, 0x96c24c8f, - 0x48d68d28, 0x96beb91f, - 0x48d16265, 0x96bb25f0, 0x48cc3775, 0x96b79302, 0x48c70c59, 0x96b40055, - 0x48c1e10f, 0x96b06de9, - 0x48bcb599, 0x96acdbbe, 0x48b789f5, 0x96a949d3, 0x48b25e25, 0x96a5b82a, - 0x48ad3228, 0x96a226c2, - 0x48a805ff, 0x969e959b, 0x48a2d9a8, 0x969b04b4, 0x489dad25, 0x9697740f, - 0x48988074, 0x9693e3ab, - 0x48935397, 0x96905388, 0x488e268e, 0x968cc3a5, 0x4888f957, 0x96893404, - 0x4883cbf4, 0x9685a4a4, - 0x487e9e64, 0x96821585, 0x487970a7, 0x967e86a7, 0x487442be, 0x967af80a, - 0x486f14a8, 0x967769af, - 0x4869e665, 0x9673db94, 0x4864b7f5, 0x96704dba, 0x485f8959, 0x966cc022, - 0x485a5a90, 0x966932cb, - 0x48552b9b, 0x9665a5b4, 0x484ffc79, 0x966218df, 0x484acd2a, 0x965e8c4b, - 0x48459daf, 0x965afff9, - 0x48406e08, 0x965773e7, 0x483b3e33, 0x9653e817, 0x48360e32, 0x96505c88, - 0x4830de05, 0x964cd139, - 0x482badab, 0x9649462d, 0x48267d24, 0x9645bb61, 0x48214c71, 0x964230d7, - 0x481c1b92, 0x963ea68d, - 0x4816ea86, 0x963b1c86, 0x4811b94d, 0x963792bf, 0x480c87e8, 0x96340939, - 0x48075657, 0x96307ff5, - 0x48022499, 0x962cf6f2, 0x47fcf2af, 0x96296e31, 0x47f7c099, 0x9625e5b0, - 0x47f28e56, 0x96225d71, - 0x47ed5be6, 0x961ed574, 0x47e8294a, 0x961b4db7, 0x47e2f682, 0x9617c63c, - 0x47ddc38e, 0x96143f02, - 0x47d8906d, 0x9610b80a, 0x47d35d20, 0x960d3153, 0x47ce29a7, 0x9609aadd, - 0x47c8f601, 0x960624a9, - 0x47c3c22f, 0x96029eb6, 0x47be8e31, 0x95ff1904, 0x47b95a06, 0x95fb9394, - 0x47b425af, 0x95f80e65, - 0x47aef12c, 0x95f48977, 0x47a9bc7d, 0x95f104cb, 0x47a487a2, 0x95ed8061, - 0x479f529a, 0x95e9fc38, - 0x479a1d67, 0x95e67850, 0x4794e807, 0x95e2f4a9, 0x478fb27b, 0x95df7145, - 0x478a7cc2, 0x95dbee21, - 0x478546de, 0x95d86b3f, 0x478010cd, 0x95d4e89f, 0x477ada91, 0x95d16640, - 0x4775a428, 0x95cde423, - 0x47706d93, 0x95ca6247, 0x476b36d3, 0x95c6e0ac, 0x4765ffe6, 0x95c35f53, - 0x4760c8cd, 0x95bfde3c, - 0x475b9188, 0x95bc5d66, 0x47565a17, 0x95b8dcd2, 0x4751227a, 0x95b55c7f, - 0x474beab1, 0x95b1dc6e, - 0x4746b2bc, 0x95ae5c9f, 0x47417a9b, 0x95aadd11, 0x473c424e, 0x95a75dc4, - 0x473709d5, 0x95a3deb9, - 0x4731d131, 0x95a05ff0, 0x472c9860, 0x959ce169, 0x47275f63, 0x95996323, - 0x4722263b, 0x9595e51e, - 0x471cece7, 0x9592675c, 0x4717b367, 0x958ee9db, 0x471279ba, 0x958b6c9b, - 0x470d3fe3, 0x9587ef9e, - 0x470805df, 0x958472e2, 0x4702cbaf, 0x9580f667, 0x46fd9154, 0x957d7a2f, - 0x46f856cd, 0x9579fe38, - 0x46f31c1a, 0x95768283, 0x46ede13b, 0x9573070f, 0x46e8a631, 0x956f8bdd, - 0x46e36afb, 0x956c10ed, - 0x46de2f99, 0x9568963f, 0x46d8f40b, 0x95651bd2, 0x46d3b852, 0x9561a1a8, - 0x46ce7c6d, 0x955e27bf, - 0x46c9405c, 0x955aae17, 0x46c40420, 0x955734b2, 0x46bec7b8, 0x9553bb8e, - 0x46b98b24, 0x955042ac, - 0x46b44e65, 0x954cca0c, 0x46af117a, 0x954951ae, 0x46a9d464, 0x9545d992, - 0x46a49722, 0x954261b7, - 0x469f59b4, 0x953eea1e, 0x469a1c1b, 0x953b72c7, 0x4694de56, 0x9537fbb2, - 0x468fa066, 0x953484df, - 0x468a624a, 0x95310e4e, 0x46852403, 0x952d97fe, 0x467fe590, 0x952a21f1, - 0x467aa6f2, 0x9526ac25, - 0x46756828, 0x9523369c, 0x46702933, 0x951fc154, 0x466aea12, 0x951c4c4e, - 0x4665aac6, 0x9518d78a, - 0x46606b4e, 0x95156308, 0x465b2bab, 0x9511eec8, 0x4655ebdd, 0x950e7aca, - 0x4650abe3, 0x950b070e, - 0x464b6bbe, 0x95079394, 0x46462b6d, 0x9504205c, 0x4640eaf2, 0x9500ad66, - 0x463baa4a, 0x94fd3ab1, - 0x46366978, 0x94f9c83f, 0x4631287a, 0x94f6560f, 0x462be751, 0x94f2e421, - 0x4626a5fd, 0x94ef7275, - 0x4621647d, 0x94ec010b, 0x461c22d2, 0x94e88fe3, 0x4616e0fc, 0x94e51efd, - 0x46119efa, 0x94e1ae59, - 0x460c5cce, 0x94de3df8, 0x46071a76, 0x94dacdd8, 0x4601d7f3, 0x94d75dfa, - 0x45fc9545, 0x94d3ee5f, - 0x45f7526b, 0x94d07f05, 0x45f20f67, 0x94cd0fee, 0x45eccc37, 0x94c9a119, - 0x45e788dc, 0x94c63286, - 0x45e24556, 0x94c2c435, 0x45dd01a5, 0x94bf5627, 0x45d7bdc9, 0x94bbe85a, - 0x45d279c2, 0x94b87ad0, - 0x45cd358f, 0x94b50d87, 0x45c7f132, 0x94b1a081, 0x45c2acaa, 0x94ae33be, - 0x45bd67f6, 0x94aac73c, - 0x45b82318, 0x94a75afd, 0x45b2de0e, 0x94a3eeff, 0x45ad98da, 0x94a08344, - 0x45a8537a, 0x949d17cc, - 0x45a30df0, 0x9499ac95, 0x459dc83b, 0x949641a1, 0x4598825a, 0x9492d6ef, - 0x45933c4f, 0x948f6c7f, - 0x458df619, 0x948c0252, 0x4588afb8, 0x94889867, 0x4583692c, 0x94852ebe, - 0x457e2275, 0x9481c557, - 0x4578db93, 0x947e5c33, 0x45739487, 0x947af351, 0x456e4d4f, 0x94778ab1, - 0x456905ed, 0x94742254, - 0x4563be60, 0x9470ba39, 0x455e76a8, 0x946d5260, 0x45592ec6, 0x9469eaca, - 0x4553e6b8, 0x94668376, - 0x454e9e80, 0x94631c65, 0x4549561d, 0x945fb596, 0x45440d90, 0x945c4f09, - 0x453ec4d7, 0x9458e8bf, - 0x45397bf4, 0x945582b7, 0x453432e6, 0x94521cf1, 0x452ee9ae, 0x944eb76e, - 0x4529a04b, 0x944b522d, - 0x452456bd, 0x9447ed2f, 0x451f0d04, 0x94448873, 0x4519c321, 0x944123fa, - 0x45147913, 0x943dbfc3, - 0x450f2edb, 0x943a5bcf, 0x4509e478, 0x9436f81d, 0x450499eb, 0x943394ad, - 0x44ff4f32, 0x94303180, - 0x44fa0450, 0x942cce96, 0x44f4b943, 0x94296bee, 0x44ef6e0b, 0x94260989, - 0x44ea22a9, 0x9422a766, - 0x44e4d71c, 0x941f4585, 0x44df8b64, 0x941be3e8, 0x44da3f83, 0x9418828c, - 0x44d4f376, 0x94152174, - 0x44cfa740, 0x9411c09e, 0x44ca5adf, 0x940e600a, 0x44c50e53, 0x940affb9, - 0x44bfc19d, 0x94079fab, - 0x44ba74bd, 0x94043fdf, 0x44b527b2, 0x9400e056, 0x44afda7d, 0x93fd810f, - 0x44aa8d1d, 0x93fa220b, - 0x44a53f93, 0x93f6c34a, 0x449ff1df, 0x93f364cb, 0x449aa400, 0x93f0068f, - 0x449555f7, 0x93eca896, - 0x449007c4, 0x93e94adf, 0x448ab967, 0x93e5ed6b, 0x44856adf, 0x93e2903a, - 0x44801c2d, 0x93df334c, - 0x447acd50, 0x93dbd6a0, 0x44757e4a, 0x93d87a36, 0x44702f19, 0x93d51e10, - 0x446adfbe, 0x93d1c22c, - 0x44659039, 0x93ce668b, 0x44604089, 0x93cb0b2d, 0x445af0b0, 0x93c7b011, - 0x4455a0ac, 0x93c45539, - 0x4450507e, 0x93c0faa3, 0x444b0026, 0x93bda04f, 0x4445afa4, 0x93ba463f, - 0x44405ef8, 0x93b6ec71, - 0x443b0e21, 0x93b392e6, 0x4435bd21, 0x93b0399e, 0x44306bf6, 0x93ace099, - 0x442b1aa2, 0x93a987d6, - 0x4425c923, 0x93a62f57, 0x4420777b, 0x93a2d71a, 0x441b25a8, 0x939f7f20, - 0x4415d3ab, 0x939c2769, - 0x44108184, 0x9398cff5, 0x440b2f34, 0x939578c3, 0x4405dcb9, 0x939221d5, - 0x44008a14, 0x938ecb29, - 0x43fb3746, 0x938b74c1, 0x43f5e44d, 0x93881e9b, 0x43f0912b, 0x9384c8b8, - 0x43eb3ddf, 0x93817318, - 0x43e5ea68, 0x937e1dbb, 0x43e096c8, 0x937ac8a1, 0x43db42fe, 0x937773ca, - 0x43d5ef0a, 0x93741f35, - 0x43d09aed, 0x9370cae4, 0x43cb46a5, 0x936d76d6, 0x43c5f234, 0x936a230a, - 0x43c09d99, 0x9366cf82, - 0x43bb48d4, 0x93637c3d, 0x43b5f3e5, 0x9360293a, 0x43b09ecc, 0x935cd67b, - 0x43ab498a, 0x935983ff, - 0x43a5f41e, 0x935631c5, 0x43a09e89, 0x9352dfcf, 0x439b48c9, 0x934f8e1c, - 0x4395f2e0, 0x934c3cab, - 0x43909ccd, 0x9348eb7e, 0x438b4691, 0x93459a94, 0x4385f02a, 0x934249ed, - 0x4380999b, 0x933ef989, - 0x437b42e1, 0x933ba968, 0x4375ebfe, 0x9338598a, 0x437094f1, 0x933509f0, - 0x436b3dbb, 0x9331ba98, - 0x4365e65b, 0x932e6b84, 0x43608ed2, 0x932b1cb2, 0x435b371f, 0x9327ce24, - 0x4355df42, 0x93247fd9, - 0x4350873c, 0x932131d1, 0x434b2f0c, 0x931de40c, 0x4345d6b3, 0x931a968b, - 0x43407e31, 0x9317494c, - 0x433b2585, 0x9313fc51, 0x4335ccaf, 0x9310af99, 0x433073b0, 0x930d6324, - 0x432b1a87, 0x930a16f3, - 0x4325c135, 0x9306cb04, 0x432067ba, 0x93037f59, 0x431b0e15, 0x930033f1, - 0x4315b447, 0x92fce8cc, - 0x43105a50, 0x92f99deb, 0x430b002f, 0x92f6534c, 0x4305a5e5, 0x92f308f1, - 0x43004b71, 0x92efbeda, - 0x42faf0d4, 0x92ec7505, 0x42f5960e, 0x92e92b74, 0x42f03b1e, 0x92e5e226, - 0x42eae005, 0x92e2991c, - 0x42e584c3, 0x92df5054, 0x42e02958, 0x92dc07d0, 0x42dacdc3, 0x92d8bf90, - 0x42d57205, 0x92d57792, - 0x42d0161e, 0x92d22fd9, 0x42caba0e, 0x92cee862, 0x42c55dd4, 0x92cba12f, - 0x42c00172, 0x92c85a3f, - 0x42baa4e6, 0x92c51392, 0x42b54831, 0x92c1cd29, 0x42afeb53, 0x92be8703, - 0x42aa8e4b, 0x92bb4121, - 0x42a5311b, 0x92b7fb82, 0x429fd3c1, 0x92b4b626, 0x429a763f, 0x92b1710e, - 0x42951893, 0x92ae2c3a, - 0x428fbabe, 0x92aae7a8, 0x428a5cc0, 0x92a7a35a, 0x4284fe99, 0x92a45f50, - 0x427fa049, 0x92a11b89, - 0x427a41d0, 0x929dd806, 0x4274e32e, 0x929a94c6, 0x426f8463, 0x929751c9, - 0x426a256f, 0x92940f10, - 0x4264c653, 0x9290cc9b, 0x425f670d, 0x928d8a69, 0x425a079e, 0x928a487a, - 0x4254a806, 0x928706cf, - 0x424f4845, 0x9283c568, 0x4249e85c, 0x92808444, 0x42448849, 0x927d4363, - 0x423f280e, 0x927a02c7, - 0x4239c7aa, 0x9276c26d, 0x4234671d, 0x92738258, 0x422f0667, 0x92704286, - 0x4229a588, 0x926d02f7, - 0x42244481, 0x9269c3ac, 0x421ee350, 0x926684a5, 0x421981f7, 0x926345e1, - 0x42142075, 0x92600761, - 0x420ebecb, 0x925cc924, 0x42095cf7, 0x92598b2b, 0x4203fafb, 0x92564d76, - 0x41fe98d6, 0x92531005, - 0x41f93689, 0x924fd2d7, 0x41f3d413, 0x924c95ec, 0x41ee7174, 0x92495946, - 0x41e90eac, 0x92461ce3, - 0x41e3abbc, 0x9242e0c4, 0x41de48a3, 0x923fa4e8, 0x41d8e561, 0x923c6950, - 0x41d381f7, 0x92392dfc, - 0x41ce1e65, 0x9235f2ec, 0x41c8baa9, 0x9232b81f, 0x41c356c5, 0x922f7d96, - 0x41bdf2b9, 0x922c4351, - 0x41b88e84, 0x9229094f, 0x41b32a26, 0x9225cf91, 0x41adc5a0, 0x92229617, - 0x41a860f1, 0x921f5ce1, - 0x41a2fc1a, 0x921c23ef, 0x419d971b, 0x9218eb40, 0x419831f3, 0x9215b2d5, - 0x4192cca2, 0x92127aae, - 0x418d6729, 0x920f42cb, 0x41880188, 0x920c0b2c, 0x41829bbe, 0x9208d3d0, - 0x417d35cb, 0x92059cb8, - 0x4177cfb1, 0x920265e4, 0x4172696e, 0x91ff2f54, 0x416d0302, 0x91fbf908, - 0x41679c6f, 0x91f8c300, - 0x416235b2, 0x91f58d3b, 0x415ccece, 0x91f257bb, 0x415767c1, 0x91ef227e, - 0x4152008c, 0x91ebed85, - 0x414c992f, 0x91e8b8d0, 0x414731a9, 0x91e5845f, 0x4141c9fb, 0x91e25032, - 0x413c6225, 0x91df1c49, - 0x4136fa27, 0x91dbe8a4, 0x41319200, 0x91d8b542, 0x412c29b1, 0x91d58225, - 0x4126c13a, 0x91d24f4c, - 0x4121589b, 0x91cf1cb6, 0x411befd3, 0x91cbea65, 0x411686e4, 0x91c8b857, - 0x41111dcc, 0x91c5868e, - 0x410bb48c, 0x91c25508, 0x41064b24, 0x91bf23c7, 0x4100e194, 0x91bbf2c9, - 0x40fb77dc, 0x91b8c210, - 0x40f60dfb, 0x91b5919a, 0x40f0a3f3, 0x91b26169, 0x40eb39c3, 0x91af317c, - 0x40e5cf6a, 0x91ac01d2, - 0x40e064ea, 0x91a8d26d, 0x40dafa41, 0x91a5a34c, 0x40d58f71, 0x91a2746f, - 0x40d02478, 0x919f45d6, - 0x40cab958, 0x919c1781, 0x40c54e0f, 0x9198e970, 0x40bfe29f, 0x9195bba3, - 0x40ba7706, 0x91928e1a, - 0x40b50b46, 0x918f60d6, 0x40af9f5e, 0x918c33d5, 0x40aa334e, 0x91890719, - 0x40a4c716, 0x9185daa1, - 0x409f5ab6, 0x9182ae6d, 0x4099ee2e, 0x917f827d, 0x4094817f, 0x917c56d1, - 0x408f14a7, 0x91792b6a, - 0x4089a7a8, 0x91760047, 0x40843a81, 0x9172d567, 0x407ecd32, 0x916faacc, - 0x40795fbc, 0x916c8076, - 0x4073f21d, 0x91695663, 0x406e8457, 0x91662c95, 0x40691669, 0x9163030b, - 0x4063a854, 0x915fd9c5, - 0x405e3a16, 0x915cb0c3, 0x4058cbb1, 0x91598806, 0x40535d24, 0x91565f8d, - 0x404dee70, 0x91533758, - 0x40487f94, 0x91500f67, 0x40431090, 0x914ce7bb, 0x403da165, 0x9149c053, - 0x40383212, 0x9146992f, - 0x4032c297, 0x91437250, 0x402d52f5, 0x91404bb5, 0x4027e32b, 0x913d255e, - 0x4022733a, 0x9139ff4b, - 0x401d0321, 0x9136d97d, 0x401792e0, 0x9133b3f3, 0x40122278, 0x91308eae, - 0x400cb1e9, 0x912d69ad, - 0x40074132, 0x912a44f0, 0x4001d053, 0x91272078, 0x3ffc5f4d, 0x9123fc44, - 0x3ff6ee1f, 0x9120d854, - 0x3ff17cca, 0x911db4a9, 0x3fec0b4e, 0x911a9142, 0x3fe699aa, 0x91176e1f, - 0x3fe127df, 0x91144b41, - 0x3fdbb5ec, 0x911128a8, 0x3fd643d2, 0x910e0653, 0x3fd0d191, 0x910ae442, - 0x3fcb5f28, 0x9107c276, - 0x3fc5ec98, 0x9104a0ee, 0x3fc079e0, 0x91017faa, 0x3fbb0702, 0x90fe5eab, - 0x3fb593fb, 0x90fb3df1, - 0x3fb020ce, 0x90f81d7b, 0x3faaad79, 0x90f4fd4a, 0x3fa539fd, 0x90f1dd5d, - 0x3f9fc65a, 0x90eebdb4, - 0x3f9a5290, 0x90eb9e50, 0x3f94de9e, 0x90e87f31, 0x3f8f6a85, 0x90e56056, - 0x3f89f645, 0x90e241bf, - 0x3f8481dd, 0x90df236e, 0x3f7f0d4f, 0x90dc0560, 0x3f799899, 0x90d8e798, - 0x3f7423bc, 0x90d5ca13, - 0x3f6eaeb8, 0x90d2acd4, 0x3f69398d, 0x90cf8fd9, 0x3f63c43b, 0x90cc7322, - 0x3f5e4ec2, 0x90c956b1, - 0x3f58d921, 0x90c63a83, 0x3f53635a, 0x90c31e9b, 0x3f4ded6b, 0x90c002f7, - 0x3f487755, 0x90bce797, - 0x3f430119, 0x90b9cc7d, 0x3f3d8ab5, 0x90b6b1a6, 0x3f38142a, 0x90b39715, - 0x3f329d79, 0x90b07cc8, - 0x3f2d26a0, 0x90ad62c0, 0x3f27afa1, 0x90aa48fd, 0x3f22387a, 0x90a72f7e, - 0x3f1cc12c, 0x90a41644, - 0x3f1749b8, 0x90a0fd4e, 0x3f11d21d, 0x909de49e, 0x3f0c5a5a, 0x909acc32, - 0x3f06e271, 0x9097b40a, - 0x3f016a61, 0x90949c28, 0x3efbf22a, 0x9091848a, 0x3ef679cc, 0x908e6d31, - 0x3ef10148, 0x908b561c, - 0x3eeb889c, 0x90883f4d, 0x3ee60fca, 0x908528c2, 0x3ee096d1, 0x9082127c, - 0x3edb1db1, 0x907efc7a, - 0x3ed5a46b, 0x907be6be, 0x3ed02afd, 0x9078d146, 0x3ecab169, 0x9075bc13, - 0x3ec537ae, 0x9072a725, - 0x3ebfbdcd, 0x906f927c, 0x3eba43c4, 0x906c7e17, 0x3eb4c995, 0x906969f8, - 0x3eaf4f40, 0x9066561d, - 0x3ea9d4c3, 0x90634287, 0x3ea45a21, 0x90602f35, 0x3e9edf57, 0x905d1c29, - 0x3e996467, 0x905a0962, - 0x3e93e950, 0x9056f6df, 0x3e8e6e12, 0x9053e4a1, 0x3e88f2ae, 0x9050d2a9, - 0x3e837724, 0x904dc0f5, - 0x3e7dfb73, 0x904aaf86, 0x3e787f9b, 0x90479e5c, 0x3e73039d, 0x90448d76, - 0x3e6d8778, 0x90417cd6, - 0x3e680b2c, 0x903e6c7b, 0x3e628ebb, 0x903b5c64, 0x3e5d1222, 0x90384c93, - 0x3e579564, 0x90353d06, - 0x3e52187f, 0x90322dbf, 0x3e4c9b73, 0x902f1ebc, 0x3e471e41, 0x902c0fff, - 0x3e41a0e8, 0x90290186, - 0x3e3c2369, 0x9025f352, 0x3e36a5c4, 0x9022e564, 0x3e3127f9, 0x901fd7ba, - 0x3e2baa07, 0x901cca55, - 0x3e262bee, 0x9019bd36, 0x3e20adaf, 0x9016b05b, 0x3e1b2f4a, 0x9013a3c5, - 0x3e15b0bf, 0x90109775, - 0x3e10320d, 0x900d8b69, 0x3e0ab336, 0x900a7fa3, 0x3e053437, 0x90077422, - 0x3dffb513, 0x900468e5, - 0x3dfa35c8, 0x90015dee, 0x3df4b657, 0x8ffe533c, 0x3def36c0, 0x8ffb48cf, - 0x3de9b703, 0x8ff83ea7, - 0x3de4371f, 0x8ff534c4, 0x3ddeb716, 0x8ff22b26, 0x3dd936e6, 0x8fef21ce, - 0x3dd3b690, 0x8fec18ba, - 0x3dce3614, 0x8fe90fec, 0x3dc8b571, 0x8fe60763, 0x3dc334a9, 0x8fe2ff1f, - 0x3dbdb3ba, 0x8fdff720, - 0x3db832a6, 0x8fdcef66, 0x3db2b16b, 0x8fd9e7f2, 0x3dad300b, 0x8fd6e0c2, - 0x3da7ae84, 0x8fd3d9d8, - 0x3da22cd7, 0x8fd0d333, 0x3d9cab04, 0x8fcdccd3, 0x3d97290b, 0x8fcac6b9, - 0x3d91a6ed, 0x8fc7c0e3, - 0x3d8c24a8, 0x8fc4bb53, 0x3d86a23d, 0x8fc1b608, 0x3d811fac, 0x8fbeb103, - 0x3d7b9cf6, 0x8fbbac42, - 0x3d761a19, 0x8fb8a7c7, 0x3d709717, 0x8fb5a391, 0x3d6b13ee, 0x8fb29fa0, - 0x3d6590a0, 0x8faf9bf5, - 0x3d600d2c, 0x8fac988f, 0x3d5a8992, 0x8fa9956e, 0x3d5505d2, 0x8fa69293, - 0x3d4f81ec, 0x8fa38ffc, - 0x3d49fde1, 0x8fa08dab, 0x3d4479b0, 0x8f9d8ba0, 0x3d3ef559, 0x8f9a89da, - 0x3d3970dc, 0x8f978859, - 0x3d33ec39, 0x8f94871d, 0x3d2e6771, 0x8f918627, 0x3d28e282, 0x8f8e8576, - 0x3d235d6f, 0x8f8b850a, - 0x3d1dd835, 0x8f8884e4, 0x3d1852d6, 0x8f858503, 0x3d12cd51, 0x8f828568, - 0x3d0d47a6, 0x8f7f8612, - 0x3d07c1d6, 0x8f7c8701, 0x3d023be0, 0x8f798836, 0x3cfcb5c4, 0x8f7689b0, - 0x3cf72f83, 0x8f738b70, - 0x3cf1a91c, 0x8f708d75, 0x3cec2290, 0x8f6d8fbf, 0x3ce69bde, 0x8f6a924f, - 0x3ce11507, 0x8f679525, - 0x3cdb8e09, 0x8f649840, 0x3cd606e7, 0x8f619ba0, 0x3cd07f9f, 0x8f5e9f46, - 0x3ccaf831, 0x8f5ba331, - 0x3cc5709e, 0x8f58a761, 0x3cbfe8e5, 0x8f55abd8, 0x3cba6107, 0x8f52b093, - 0x3cb4d904, 0x8f4fb595, - 0x3caf50da, 0x8f4cbadb, 0x3ca9c88c, 0x8f49c067, 0x3ca44018, 0x8f46c639, - 0x3c9eb77f, 0x8f43cc50, - 0x3c992ec0, 0x8f40d2ad, 0x3c93a5dc, 0x8f3dd950, 0x3c8e1cd3, 0x8f3ae038, - 0x3c8893a4, 0x8f37e765, - 0x3c830a50, 0x8f34eed8, 0x3c7d80d6, 0x8f31f691, 0x3c77f737, 0x8f2efe8f, - 0x3c726d73, 0x8f2c06d3, - 0x3c6ce38a, 0x8f290f5c, 0x3c67597b, 0x8f26182b, 0x3c61cf48, 0x8f232140, - 0x3c5c44ee, 0x8f202a9a, - 0x3c56ba70, 0x8f1d343a, 0x3c512fcc, 0x8f1a3e1f, 0x3c4ba504, 0x8f17484b, - 0x3c461a16, 0x8f1452bb, - 0x3c408f03, 0x8f115d72, 0x3c3b03ca, 0x8f0e686e, 0x3c35786d, 0x8f0b73b0, - 0x3c2fecea, 0x8f087f37, - 0x3c2a6142, 0x8f058b04, 0x3c24d575, 0x8f029717, 0x3c1f4983, 0x8effa370, - 0x3c19bd6c, 0x8efcb00e, - 0x3c143130, 0x8ef9bcf2, 0x3c0ea4cf, 0x8ef6ca1c, 0x3c091849, 0x8ef3d78b, - 0x3c038b9e, 0x8ef0e540, - 0x3bfdfecd, 0x8eedf33b, 0x3bf871d8, 0x8eeb017c, 0x3bf2e4be, 0x8ee81002, - 0x3bed577e, 0x8ee51ece, - 0x3be7ca1a, 0x8ee22de0, 0x3be23c91, 0x8edf3d38, 0x3bdcaee3, 0x8edc4cd5, - 0x3bd72110, 0x8ed95cb8, - 0x3bd19318, 0x8ed66ce1, 0x3bcc04fb, 0x8ed37d50, 0x3bc676b9, 0x8ed08e05, - 0x3bc0e853, 0x8ecd9eff, - 0x3bbb59c7, 0x8ecab040, 0x3bb5cb17, 0x8ec7c1c6, 0x3bb03c42, 0x8ec4d392, - 0x3baaad48, 0x8ec1e5a4, - 0x3ba51e29, 0x8ebef7fb, 0x3b9f8ee5, 0x8ebc0a99, 0x3b99ff7d, 0x8eb91d7c, - 0x3b946ff0, 0x8eb630a6, - 0x3b8ee03e, 0x8eb34415, 0x3b895068, 0x8eb057ca, 0x3b83c06c, 0x8ead6bc5, - 0x3b7e304c, 0x8eaa8006, - 0x3b78a007, 0x8ea7948c, 0x3b730f9e, 0x8ea4a959, 0x3b6d7f10, 0x8ea1be6c, - 0x3b67ee5d, 0x8e9ed3c4, - 0x3b625d86, 0x8e9be963, 0x3b5ccc8a, 0x8e98ff47, 0x3b573b69, 0x8e961571, - 0x3b51aa24, 0x8e932be2, - 0x3b4c18ba, 0x8e904298, 0x3b46872c, 0x8e8d5994, 0x3b40f579, 0x8e8a70d7, - 0x3b3b63a1, 0x8e87885f, - 0x3b35d1a5, 0x8e84a02d, 0x3b303f84, 0x8e81b841, 0x3b2aad3f, 0x8e7ed09b, - 0x3b251ad6, 0x8e7be93c, - 0x3b1f8848, 0x8e790222, 0x3b19f595, 0x8e761b4e, 0x3b1462be, 0x8e7334c1, - 0x3b0ecfc3, 0x8e704e79, - 0x3b093ca3, 0x8e6d6877, 0x3b03a95e, 0x8e6a82bc, 0x3afe15f6, 0x8e679d47, - 0x3af88269, 0x8e64b817, - 0x3af2eeb7, 0x8e61d32e, 0x3aed5ae1, 0x8e5eee8b, 0x3ae7c6e7, 0x8e5c0a2e, - 0x3ae232c9, 0x8e592617, - 0x3adc9e86, 0x8e564246, 0x3ad70a1f, 0x8e535ebb, 0x3ad17593, 0x8e507b76, - 0x3acbe0e3, 0x8e4d9878, - 0x3ac64c0f, 0x8e4ab5bf, 0x3ac0b717, 0x8e47d34d, 0x3abb21fb, 0x8e44f121, - 0x3ab58cba, 0x8e420f3b, - 0x3aaff755, 0x8e3f2d9b, 0x3aaa61cc, 0x8e3c4c41, 0x3aa4cc1e, 0x8e396b2e, - 0x3a9f364d, 0x8e368a61, - 0x3a99a057, 0x8e33a9da, 0x3a940a3e, 0x8e30c999, 0x3a8e7400, 0x8e2de99e, - 0x3a88dd9d, 0x8e2b09e9, - 0x3a834717, 0x8e282a7b, 0x3a7db06d, 0x8e254b53, 0x3a78199f, 0x8e226c71, - 0x3a7282ac, 0x8e1f8dd6, - 0x3a6ceb96, 0x8e1caf80, 0x3a67545b, 0x8e19d171, 0x3a61bcfd, 0x8e16f3a9, - 0x3a5c257a, 0x8e141626, - 0x3a568dd4, 0x8e1138ea, 0x3a50f609, 0x8e0e5bf4, 0x3a4b5e1b, 0x8e0b7f44, - 0x3a45c608, 0x8e08a2db, - 0x3a402dd2, 0x8e05c6b7, 0x3a3a9577, 0x8e02eadb, 0x3a34fcf9, 0x8e000f44, - 0x3a2f6457, 0x8dfd33f4, - 0x3a29cb91, 0x8dfa58ea, 0x3a2432a7, 0x8df77e27, 0x3a1e9999, 0x8df4a3a9, - 0x3a190068, 0x8df1c973, - 0x3a136712, 0x8deeef82, 0x3a0dcd99, 0x8dec15d8, 0x3a0833fc, 0x8de93c74, - 0x3a029a3b, 0x8de66357, - 0x39fd0056, 0x8de38a80, 0x39f7664e, 0x8de0b1ef, 0x39f1cc21, 0x8dddd9a5, - 0x39ec31d1, 0x8ddb01a1, - 0x39e6975e, 0x8dd829e4, 0x39e0fcc6, 0x8dd5526d, 0x39db620b, 0x8dd27b3c, - 0x39d5c72c, 0x8dcfa452, - 0x39d02c2a, 0x8dcccdaf, 0x39ca9104, 0x8dc9f751, 0x39c4f5ba, 0x8dc7213b, - 0x39bf5a4d, 0x8dc44b6a, - 0x39b9bebc, 0x8dc175e0, 0x39b42307, 0x8dbea09d, 0x39ae872f, 0x8dbbcba0, - 0x39a8eb33, 0x8db8f6ea, - 0x39a34f13, 0x8db6227a, 0x399db2d0, 0x8db34e50, 0x3998166a, 0x8db07a6d, - 0x399279e0, 0x8dada6d1, - 0x398cdd32, 0x8daad37b, 0x39874061, 0x8da8006c, 0x3981a36d, 0x8da52da3, - 0x397c0655, 0x8da25b21, - 0x39766919, 0x8d9f88e5, 0x3970cbba, 0x8d9cb6f0, 0x396b2e38, 0x8d99e541, - 0x39659092, 0x8d9713d9, - 0x395ff2c9, 0x8d9442b8, 0x395a54dd, 0x8d9171dd, 0x3954b6cd, 0x8d8ea148, - 0x394f1899, 0x8d8bd0fb, - 0x39497a43, 0x8d8900f3, 0x3943dbc9, 0x8d863133, 0x393e3d2c, 0x8d8361b9, - 0x39389e6b, 0x8d809286, - 0x3932ff87, 0x8d7dc399, 0x392d6080, 0x8d7af4f3, 0x3927c155, 0x8d782694, - 0x39222208, 0x8d75587b, - 0x391c8297, 0x8d728aa9, 0x3916e303, 0x8d6fbd1d, 0x3911434b, 0x8d6cefd9, - 0x390ba371, 0x8d6a22db, - 0x39060373, 0x8d675623, 0x39006352, 0x8d6489b3, 0x38fac30e, 0x8d61bd89, - 0x38f522a6, 0x8d5ef1a5, - 0x38ef821c, 0x8d5c2609, 0x38e9e16e, 0x8d595ab3, 0x38e4409e, 0x8d568fa4, - 0x38de9faa, 0x8d53c4db, - 0x38d8fe93, 0x8d50fa59, 0x38d35d59, 0x8d4e301f, 0x38cdbbfc, 0x8d4b662a, - 0x38c81a7c, 0x8d489c7d, - 0x38c278d9, 0x8d45d316, 0x38bcd713, 0x8d4309f6, 0x38b7352a, 0x8d40411d, - 0x38b1931e, 0x8d3d788b, - 0x38abf0ef, 0x8d3ab03f, 0x38a64e9d, 0x8d37e83a, 0x38a0ac29, 0x8d35207d, - 0x389b0991, 0x8d325905, - 0x389566d6, 0x8d2f91d5, 0x388fc3f8, 0x8d2ccaec, 0x388a20f8, 0x8d2a0449, - 0x38847dd5, 0x8d273ded, - 0x387eda8e, 0x8d2477d8, 0x38793725, 0x8d21b20a, 0x38739399, 0x8d1eec83, - 0x386defeb, 0x8d1c2742, - 0x38684c19, 0x8d196249, 0x3862a825, 0x8d169d96, 0x385d040d, 0x8d13d92a, - 0x38575fd4, 0x8d111505, - 0x3851bb77, 0x8d0e5127, 0x384c16f7, 0x8d0b8d90, 0x38467255, 0x8d08ca40, - 0x3840cd90, 0x8d060737, - 0x383b28a9, 0x8d034474, 0x3835839f, 0x8d0081f9, 0x382fde72, 0x8cfdbfc4, - 0x382a3922, 0x8cfafdd7, - 0x382493b0, 0x8cf83c30, 0x381eee1b, 0x8cf57ad0, 0x38194864, 0x8cf2b9b8, - 0x3813a28a, 0x8ceff8e6, - 0x380dfc8d, 0x8ced385b, 0x3808566e, 0x8cea7818, 0x3802b02c, 0x8ce7b81b, - 0x37fd09c8, 0x8ce4f865, - 0x37f76341, 0x8ce238f6, 0x37f1bc97, 0x8cdf79ce, 0x37ec15cb, 0x8cdcbaee, - 0x37e66edd, 0x8cd9fc54, - 0x37e0c7cc, 0x8cd73e01, 0x37db2099, 0x8cd47ff6, 0x37d57943, 0x8cd1c231, - 0x37cfd1cb, 0x8ccf04b3, - 0x37ca2a30, 0x8ccc477d, 0x37c48273, 0x8cc98a8e, 0x37beda93, 0x8cc6cde5, - 0x37b93292, 0x8cc41184, - 0x37b38a6d, 0x8cc1556a, 0x37ade227, 0x8cbe9996, 0x37a839be, 0x8cbbde0a, - 0x37a29132, 0x8cb922c6, - 0x379ce885, 0x8cb667c8, 0x37973fb5, 0x8cb3ad11, 0x379196c3, 0x8cb0f2a1, - 0x378bedae, 0x8cae3879, - 0x37864477, 0x8cab7e98, 0x37809b1e, 0x8ca8c4fd, 0x377af1a3, 0x8ca60baa, - 0x37754806, 0x8ca3529f, - 0x376f9e46, 0x8ca099da, 0x3769f464, 0x8c9de15c, 0x37644a60, 0x8c9b2926, - 0x375ea03a, 0x8c987137, - 0x3758f5f2, 0x8c95b98f, 0x37534b87, 0x8c93022e, 0x374da0fa, 0x8c904b14, - 0x3747f64c, 0x8c8d9442, - 0x37424b7b, 0x8c8addb7, 0x373ca088, 0x8c882773, 0x3736f573, 0x8c857176, - 0x37314a3c, 0x8c82bbc0, - 0x372b9ee3, 0x8c800652, 0x3725f367, 0x8c7d512b, 0x372047ca, 0x8c7a9c4b, - 0x371a9c0b, 0x8c77e7b3, - 0x3714f02a, 0x8c753362, 0x370f4427, 0x8c727f58, 0x37099802, 0x8c6fcb95, - 0x3703ebbb, 0x8c6d181a, - 0x36fe3f52, 0x8c6a64e5, 0x36f892c7, 0x8c67b1f9, 0x36f2e61a, 0x8c64ff53, - 0x36ed394b, 0x8c624cf5, - 0x36e78c5b, 0x8c5f9ade, 0x36e1df48, 0x8c5ce90e, 0x36dc3214, 0x8c5a3786, - 0x36d684be, 0x8c578645, - 0x36d0d746, 0x8c54d54c, 0x36cb29ac, 0x8c522499, 0x36c57bf0, 0x8c4f742f, - 0x36bfce13, 0x8c4cc40b, - 0x36ba2014, 0x8c4a142f, 0x36b471f3, 0x8c47649a, 0x36aec3b0, 0x8c44b54d, - 0x36a9154c, 0x8c420647, - 0x36a366c6, 0x8c3f5788, 0x369db81e, 0x8c3ca911, 0x36980954, 0x8c39fae1, - 0x36925a69, 0x8c374cf9, - 0x368cab5c, 0x8c349f58, 0x3686fc2e, 0x8c31f1ff, 0x36814cde, 0x8c2f44ed, - 0x367b9d6c, 0x8c2c9822, - 0x3675edd9, 0x8c29eb9f, 0x36703e24, 0x8c273f63, 0x366a8e4d, 0x8c24936f, - 0x3664de55, 0x8c21e7c2, - 0x365f2e3b, 0x8c1f3c5d, 0x36597e00, 0x8c1c913f, 0x3653cda3, 0x8c19e669, - 0x364e1d25, 0x8c173bda, - 0x36486c86, 0x8c149192, 0x3642bbc4, 0x8c11e792, 0x363d0ae2, 0x8c0f3dda, - 0x363759de, 0x8c0c9469, - 0x3631a8b8, 0x8c09eb40, 0x362bf771, 0x8c07425e, 0x36264609, 0x8c0499c4, - 0x3620947f, 0x8c01f171, - 0x361ae2d3, 0x8bff4966, 0x36153107, 0x8bfca1a3, 0x360f7f19, 0x8bf9fa27, - 0x3609cd0a, 0x8bf752f2, - 0x36041ad9, 0x8bf4ac05, 0x35fe6887, 0x8bf20560, 0x35f8b614, 0x8bef5f02, - 0x35f3037f, 0x8becb8ec, - 0x35ed50c9, 0x8bea131e, 0x35e79df2, 0x8be76d97, 0x35e1eafa, 0x8be4c857, - 0x35dc37e0, 0x8be22360, - 0x35d684a6, 0x8bdf7eb0, 0x35d0d14a, 0x8bdcda47, 0x35cb1dcc, 0x8bda3626, - 0x35c56a2e, 0x8bd7924d, - 0x35bfb66e, 0x8bd4eebc, 0x35ba028e, 0x8bd24b72, 0x35b44e8c, 0x8bcfa870, - 0x35ae9a69, 0x8bcd05b5, - 0x35a8e625, 0x8bca6343, 0x35a331c0, 0x8bc7c117, 0x359d7d39, 0x8bc51f34, - 0x3597c892, 0x8bc27d98, - 0x359213c9, 0x8bbfdc44, 0x358c5ee0, 0x8bbd3b38, 0x3586a9d5, 0x8bba9a73, - 0x3580f4aa, 0x8bb7f9f6, - 0x357b3f5d, 0x8bb559c1, 0x357589f0, 0x8bb2b9d4, 0x356fd461, 0x8bb01a2e, - 0x356a1eb2, 0x8bad7ad0, - 0x356468e2, 0x8baadbba, 0x355eb2f0, 0x8ba83cec, 0x3558fcde, 0x8ba59e65, - 0x355346ab, 0x8ba30026, - 0x354d9057, 0x8ba0622f, 0x3547d9e2, 0x8b9dc480, 0x3542234c, 0x8b9b2718, - 0x353c6c95, 0x8b9889f8, - 0x3536b5be, 0x8b95ed21, 0x3530fec6, 0x8b935090, 0x352b47ad, 0x8b90b448, - 0x35259073, 0x8b8e1848, - 0x351fd918, 0x8b8b7c8f, 0x351a219c, 0x8b88e11e, 0x35146a00, 0x8b8645f5, - 0x350eb243, 0x8b83ab14, - 0x3508fa66, 0x8b81107b, 0x35034267, 0x8b7e7629, 0x34fd8a48, 0x8b7bdc20, - 0x34f7d208, 0x8b79425e, - 0x34f219a8, 0x8b76a8e4, 0x34ec6127, 0x8b740fb3, 0x34e6a885, 0x8b7176c8, - 0x34e0efc2, 0x8b6ede26, - 0x34db36df, 0x8b6c45cc, 0x34d57ddc, 0x8b69adba, 0x34cfc4b7, 0x8b6715ef, - 0x34ca0b73, 0x8b647e6d, - 0x34c4520d, 0x8b61e733, 0x34be9887, 0x8b5f5040, 0x34b8dee1, 0x8b5cb995, - 0x34b3251a, 0x8b5a2333, - 0x34ad6b32, 0x8b578d18, 0x34a7b12a, 0x8b54f745, 0x34a1f702, 0x8b5261ba, - 0x349c3cb9, 0x8b4fcc77, - 0x34968250, 0x8b4d377c, 0x3490c7c6, 0x8b4aa2ca, 0x348b0d1c, 0x8b480e5f, - 0x34855251, 0x8b457a3c, - 0x347f9766, 0x8b42e661, 0x3479dc5b, 0x8b4052ce, 0x3474212f, 0x8b3dbf83, - 0x346e65e3, 0x8b3b2c80, - 0x3468aa76, 0x8b3899c6, 0x3462eee9, 0x8b360753, 0x345d333c, 0x8b337528, - 0x3457776f, 0x8b30e345, - 0x3451bb81, 0x8b2e51ab, 0x344bff73, 0x8b2bc058, 0x34464345, 0x8b292f4e, - 0x344086f6, 0x8b269e8b, - 0x343aca87, 0x8b240e11, 0x34350df8, 0x8b217ddf, 0x342f5149, 0x8b1eedf4, - 0x3429947a, 0x8b1c5e52, - 0x3423d78a, 0x8b19cef8, 0x341e1a7b, 0x8b173fe6, 0x34185d4b, 0x8b14b11d, - 0x34129ffb, 0x8b12229b, - 0x340ce28b, 0x8b0f9462, 0x340724fb, 0x8b0d0670, 0x3401674a, 0x8b0a78c7, - 0x33fba97a, 0x8b07eb66, - 0x33f5eb89, 0x8b055e4d, 0x33f02d79, 0x8b02d17c, 0x33ea6f48, 0x8b0044f3, - 0x33e4b0f8, 0x8afdb8b3, - 0x33def287, 0x8afb2cbb, 0x33d933f7, 0x8af8a10b, 0x33d37546, 0x8af615a3, - 0x33cdb676, 0x8af38a83, - 0x33c7f785, 0x8af0ffac, 0x33c23875, 0x8aee751c, 0x33bc7944, 0x8aebead5, - 0x33b6b9f4, 0x8ae960d6, - 0x33b0fa84, 0x8ae6d720, 0x33ab3af4, 0x8ae44db1, 0x33a57b44, 0x8ae1c48b, - 0x339fbb74, 0x8adf3bad, - 0x3399fb85, 0x8adcb318, 0x33943b75, 0x8ada2aca, 0x338e7b46, 0x8ad7a2c5, - 0x3388baf7, 0x8ad51b08, - 0x3382fa88, 0x8ad29394, 0x337d39f9, 0x8ad00c67, 0x3377794b, 0x8acd8583, - 0x3371b87d, 0x8acafee8, - 0x336bf78f, 0x8ac87894, 0x33663682, 0x8ac5f289, 0x33607554, 0x8ac36cc6, - 0x335ab407, 0x8ac0e74c, - 0x3354f29b, 0x8abe6219, 0x334f310e, 0x8abbdd30, 0x33496f62, 0x8ab9588e, - 0x3343ad97, 0x8ab6d435, - 0x333debab, 0x8ab45024, 0x333829a1, 0x8ab1cc5c, 0x33326776, 0x8aaf48db, - 0x332ca52c, 0x8aacc5a4, - 0x3326e2c3, 0x8aaa42b4, 0x33212039, 0x8aa7c00d, 0x331b5d91, 0x8aa53daf, - 0x33159ac8, 0x8aa2bb99, - 0x330fd7e1, 0x8aa039cb, 0x330a14da, 0x8a9db845, 0x330451b3, 0x8a9b3708, - 0x32fe8e6d, 0x8a98b614, - 0x32f8cb07, 0x8a963567, 0x32f30782, 0x8a93b504, 0x32ed43de, 0x8a9134e8, - 0x32e7801a, 0x8a8eb516, - 0x32e1bc36, 0x8a8c358b, 0x32dbf834, 0x8a89b649, 0x32d63412, 0x8a873750, - 0x32d06fd0, 0x8a84b89e, - 0x32caab6f, 0x8a823a36, 0x32c4e6ef, 0x8a7fbc16, 0x32bf2250, 0x8a7d3e3e, - 0x32b95d91, 0x8a7ac0af, - 0x32b398b3, 0x8a784368, 0x32add3b6, 0x8a75c66a, 0x32a80e99, 0x8a7349b4, - 0x32a2495d, 0x8a70cd47, - 0x329c8402, 0x8a6e5123, 0x3296be88, 0x8a6bd547, 0x3290f8ef, 0x8a6959b3, - 0x328b3336, 0x8a66de68, - 0x32856d5e, 0x8a646365, 0x327fa767, 0x8a61e8ab, 0x3279e151, 0x8a5f6e3a, - 0x32741b1c, 0x8a5cf411, - 0x326e54c7, 0x8a5a7a31, 0x32688e54, 0x8a580099, 0x3262c7c1, 0x8a55874a, - 0x325d0110, 0x8a530e43, - 0x32573a3f, 0x8a509585, 0x3251734f, 0x8a4e1d10, 0x324bac40, 0x8a4ba4e3, - 0x3245e512, 0x8a492cff, - 0x32401dc6, 0x8a46b564, 0x323a565a, 0x8a443e11, 0x32348ecf, 0x8a41c706, - 0x322ec725, 0x8a3f5045, - 0x3228ff5c, 0x8a3cd9cc, 0x32233775, 0x8a3a639b, 0x321d6f6e, 0x8a37edb3, - 0x3217a748, 0x8a357814, - 0x3211df04, 0x8a3302be, 0x320c16a1, 0x8a308db0, 0x32064e1e, 0x8a2e18eb, - 0x3200857d, 0x8a2ba46e, - 0x31fabcbd, 0x8a29303b, 0x31f4f3df, 0x8a26bc50, 0x31ef2ae1, 0x8a2448ad, - 0x31e961c5, 0x8a21d554, - 0x31e39889, 0x8a1f6243, 0x31ddcf30, 0x8a1cef7a, 0x31d805b7, 0x8a1a7cfb, - 0x31d23c1f, 0x8a180ac4, - 0x31cc7269, 0x8a1598d6, 0x31c6a894, 0x8a132731, 0x31c0dea1, 0x8a10b5d4, - 0x31bb148f, 0x8a0e44c0, - 0x31b54a5e, 0x8a0bd3f5, 0x31af800e, 0x8a096373, 0x31a9b5a0, 0x8a06f339, - 0x31a3eb13, 0x8a048348, - 0x319e2067, 0x8a0213a0, 0x3198559d, 0x89ffa441, 0x31928ab4, 0x89fd352b, - 0x318cbfad, 0x89fac65d, - 0x3186f487, 0x89f857d8, 0x31812943, 0x89f5e99c, 0x317b5de0, 0x89f37ba9, - 0x3175925e, 0x89f10dff, - 0x316fc6be, 0x89eea09d, 0x3169fb00, 0x89ec3384, 0x31642f23, 0x89e9c6b4, - 0x315e6328, 0x89e75a2d, - 0x3158970e, 0x89e4edef, 0x3152cad5, 0x89e281fa, 0x314cfe7f, 0x89e0164d, - 0x31473209, 0x89ddaae9, - 0x31416576, 0x89db3fcf, 0x313b98c4, 0x89d8d4fd, 0x3135cbf4, 0x89d66a74, - 0x312fff05, 0x89d40033, - 0x312a31f8, 0x89d1963c, 0x312464cd, 0x89cf2c8e, 0x311e9783, 0x89ccc328, - 0x3118ca1b, 0x89ca5a0c, - 0x3112fc95, 0x89c7f138, 0x310d2ef0, 0x89c588ae, 0x3107612e, 0x89c3206c, - 0x3101934d, 0x89c0b873, - 0x30fbc54d, 0x89be50c3, 0x30f5f730, 0x89bbe95c, 0x30f028f4, 0x89b9823e, - 0x30ea5a9a, 0x89b71b69, - 0x30e48c22, 0x89b4b4dd, 0x30debd8c, 0x89b24e9a, 0x30d8eed8, 0x89afe8a0, - 0x30d32006, 0x89ad82ef, - 0x30cd5115, 0x89ab1d87, 0x30c78206, 0x89a8b868, 0x30c1b2da, 0x89a65391, - 0x30bbe38f, 0x89a3ef04, - 0x30b61426, 0x89a18ac0, 0x30b0449f, 0x899f26c5, 0x30aa74fa, 0x899cc313, - 0x30a4a537, 0x899a5faa, - 0x309ed556, 0x8997fc8a, 0x30990557, 0x899599b3, 0x3093353a, 0x89933725, - 0x308d64ff, 0x8990d4e0, - 0x308794a6, 0x898e72e4, 0x3081c42f, 0x898c1131, 0x307bf39b, 0x8989afc8, - 0x307622e8, 0x89874ea7, - 0x30705217, 0x8984edcf, 0x306a8129, 0x89828d41, 0x3064b01d, 0x89802cfc, - 0x305edef3, 0x897dccff, - 0x30590dab, 0x897b6d4c, 0x30533c45, 0x89790de2, 0x304d6ac1, 0x8976aec1, - 0x30479920, 0x89744fe9, - 0x3041c761, 0x8971f15a, 0x303bf584, 0x896f9315, 0x30362389, 0x896d3518, - 0x30305171, 0x896ad765, - 0x302a7f3a, 0x896879fb, 0x3024ace6, 0x89661cda, 0x301eda75, 0x8963c002, - 0x301907e6, 0x89616373, - 0x30133539, 0x895f072e, 0x300d626e, 0x895cab31, 0x30078f86, 0x895a4f7e, - 0x3001bc80, 0x8957f414, - 0x2ffbe95d, 0x895598f3, 0x2ff6161c, 0x89533e1c, 0x2ff042bd, 0x8950e38e, - 0x2fea6f41, 0x894e8948, - 0x2fe49ba7, 0x894c2f4c, 0x2fdec7f0, 0x8949d59a, 0x2fd8f41b, 0x89477c30, - 0x2fd32028, 0x89452310, - 0x2fcd4c19, 0x8942ca39, 0x2fc777eb, 0x894071ab, 0x2fc1a3a0, 0x893e1967, - 0x2fbbcf38, 0x893bc16b, - 0x2fb5fab2, 0x893969b9, 0x2fb0260f, 0x89371250, 0x2faa514f, 0x8934bb31, - 0x2fa47c71, 0x8932645b, - 0x2f9ea775, 0x89300dce, 0x2f98d25d, 0x892db78a, 0x2f92fd26, 0x892b6190, - 0x2f8d27d3, 0x89290bdf, - 0x2f875262, 0x8926b677, 0x2f817cd4, 0x89246159, 0x2f7ba729, 0x89220c84, - 0x2f75d160, 0x891fb7f8, - 0x2f6ffb7a, 0x891d63b5, 0x2f6a2577, 0x891b0fbc, 0x2f644f56, 0x8918bc0c, - 0x2f5e7919, 0x891668a6, - 0x2f58a2be, 0x89141589, 0x2f52cc46, 0x8911c2b5, 0x2f4cf5b0, 0x890f702b, - 0x2f471efe, 0x890d1dea, - 0x2f41482e, 0x890acbf2, 0x2f3b7141, 0x89087a44, 0x2f359a37, 0x890628df, - 0x2f2fc310, 0x8903d7c4, - 0x2f29ebcc, 0x890186f2, 0x2f24146b, 0x88ff3669, 0x2f1e3ced, 0x88fce62a, - 0x2f186551, 0x88fa9634, - 0x2f128d99, 0x88f84687, 0x2f0cb5c3, 0x88f5f724, 0x2f06ddd1, 0x88f3a80b, - 0x2f0105c1, 0x88f1593b, - 0x2efb2d95, 0x88ef0ab4, 0x2ef5554b, 0x88ecbc77, 0x2eef7ce5, 0x88ea6e83, - 0x2ee9a461, 0x88e820d9, - 0x2ee3cbc1, 0x88e5d378, 0x2eddf304, 0x88e38660, 0x2ed81a29, 0x88e13992, - 0x2ed24132, 0x88deed0e, - 0x2ecc681e, 0x88dca0d3, 0x2ec68eed, 0x88da54e1, 0x2ec0b5a0, 0x88d8093a, - 0x2ebadc35, 0x88d5bddb, - 0x2eb502ae, 0x88d372c6, 0x2eaf290a, 0x88d127fb, 0x2ea94f49, 0x88cedd79, - 0x2ea3756b, 0x88cc9340, - 0x2e9d9b70, 0x88ca4951, 0x2e97c159, 0x88c7ffac, 0x2e91e725, 0x88c5b650, - 0x2e8c0cd4, 0x88c36d3e, - 0x2e863267, 0x88c12475, 0x2e8057dd, 0x88bedbf6, 0x2e7a7d36, 0x88bc93c0, - 0x2e74a272, 0x88ba4bd4, - 0x2e6ec792, 0x88b80432, 0x2e68ec95, 0x88b5bcd9, 0x2e63117c, 0x88b375ca, - 0x2e5d3646, 0x88b12f04, - 0x2e575af3, 0x88aee888, 0x2e517f84, 0x88aca255, 0x2e4ba3f8, 0x88aa5c6c, - 0x2e45c850, 0x88a816cd, - 0x2e3fec8b, 0x88a5d177, 0x2e3a10aa, 0x88a38c6b, 0x2e3434ac, 0x88a147a9, - 0x2e2e5891, 0x889f0330, - 0x2e287c5a, 0x889cbf01, 0x2e22a007, 0x889a7b1b, 0x2e1cc397, 0x88983780, - 0x2e16e70b, 0x8895f42d, - 0x2e110a62, 0x8893b125, 0x2e0b2d9d, 0x88916e66, 0x2e0550bb, 0x888f2bf1, - 0x2dff73bd, 0x888ce9c5, - 0x2df996a3, 0x888aa7e3, 0x2df3b96c, 0x8888664b, 0x2deddc19, 0x888624fd, - 0x2de7feaa, 0x8883e3f8, - 0x2de2211e, 0x8881a33d, 0x2ddc4376, 0x887f62cb, 0x2dd665b2, 0x887d22a4, - 0x2dd087d1, 0x887ae2c6, - 0x2dcaa9d5, 0x8878a332, 0x2dc4cbbc, 0x887663e7, 0x2dbeed86, 0x887424e7, - 0x2db90f35, 0x8871e630, - 0x2db330c7, 0x886fa7c2, 0x2dad523d, 0x886d699f, 0x2da77397, 0x886b2bc5, - 0x2da194d5, 0x8868ee35, - 0x2d9bb5f6, 0x8866b0ef, 0x2d95d6fc, 0x886473f2, 0x2d8ff7e5, 0x88623740, - 0x2d8a18b3, 0x885ffad7, - 0x2d843964, 0x885dbeb8, 0x2d7e59f9, 0x885b82e3, 0x2d787a72, 0x88594757, - 0x2d729acf, 0x88570c16, - 0x2d6cbb10, 0x8854d11e, 0x2d66db35, 0x88529670, 0x2d60fb3e, 0x88505c0b, - 0x2d5b1b2b, 0x884e21f1, - 0x2d553afc, 0x884be821, 0x2d4f5ab1, 0x8849ae9a, 0x2d497a4a, 0x8847755d, - 0x2d4399c7, 0x88453c6a, - 0x2d3db928, 0x884303c1, 0x2d37d86d, 0x8840cb61, 0x2d31f797, 0x883e934c, - 0x2d2c16a4, 0x883c5b81, - 0x2d263596, 0x883a23ff, 0x2d20546b, 0x8837ecc7, 0x2d1a7325, 0x8835b5d9, - 0x2d1491c4, 0x88337f35, - 0x2d0eb046, 0x883148db, 0x2d08ceac, 0x882f12cb, 0x2d02ecf7, 0x882cdd04, - 0x2cfd0b26, 0x882aa788, - 0x2cf72939, 0x88287256, 0x2cf14731, 0x88263d6d, 0x2ceb650d, 0x882408ce, - 0x2ce582cd, 0x8821d47a, - 0x2cdfa071, 0x881fa06f, 0x2cd9bdfa, 0x881d6cae, 0x2cd3db67, 0x881b3937, - 0x2ccdf8b8, 0x8819060a, - 0x2cc815ee, 0x8816d327, 0x2cc23308, 0x8814a08f, 0x2cbc5006, 0x88126e40, - 0x2cb66ce9, 0x88103c3b, - 0x2cb089b1, 0x880e0a7f, 0x2caaa65c, 0x880bd90e, 0x2ca4c2ed, 0x8809a7e7, - 0x2c9edf61, 0x8807770a, - 0x2c98fbba, 0x88054677, 0x2c9317f8, 0x8803162e, 0x2c8d341a, 0x8800e62f, - 0x2c875021, 0x87feb67a, - 0x2c816c0c, 0x87fc870f, 0x2c7b87dc, 0x87fa57ee, 0x2c75a390, 0x87f82917, - 0x2c6fbf29, 0x87f5fa8b, - 0x2c69daa6, 0x87f3cc48, 0x2c63f609, 0x87f19e4f, 0x2c5e114f, 0x87ef70a0, - 0x2c582c7b, 0x87ed433c, - 0x2c52478a, 0x87eb1621, 0x2c4c627f, 0x87e8e950, 0x2c467d58, 0x87e6bcca, - 0x2c409816, 0x87e4908e, - 0x2c3ab2b9, 0x87e2649b, 0x2c34cd40, 0x87e038f3, 0x2c2ee7ad, 0x87de0d95, - 0x2c2901fd, 0x87dbe281, - 0x2c231c33, 0x87d9b7b7, 0x2c1d364e, 0x87d78d38, 0x2c17504d, 0x87d56302, - 0x2c116a31, 0x87d33916, - 0x2c0b83fa, 0x87d10f75, 0x2c059da7, 0x87cee61e, 0x2bffb73a, 0x87ccbd11, - 0x2bf9d0b1, 0x87ca944e, - 0x2bf3ea0d, 0x87c86bd5, 0x2bee034e, 0x87c643a6, 0x2be81c74, 0x87c41bc2, - 0x2be2357f, 0x87c1f427, - 0x2bdc4e6f, 0x87bfccd7, 0x2bd66744, 0x87bda5d1, 0x2bd07ffe, 0x87bb7f16, - 0x2bca989d, 0x87b958a4, - 0x2bc4b120, 0x87b7327d, 0x2bbec989, 0x87b50c9f, 0x2bb8e1d7, 0x87b2e70c, - 0x2bb2fa0a, 0x87b0c1c4, - 0x2bad1221, 0x87ae9cc5, 0x2ba72a1e, 0x87ac7811, 0x2ba14200, 0x87aa53a6, - 0x2b9b59c7, 0x87a82f87, - 0x2b957173, 0x87a60bb1, 0x2b8f8905, 0x87a3e825, 0x2b89a07b, 0x87a1c4e4, - 0x2b83b7d7, 0x879fa1ed, - 0x2b7dcf17, 0x879d7f41, 0x2b77e63d, 0x879b5cde, 0x2b71fd48, 0x87993ac6, - 0x2b6c1438, 0x879718f8, - 0x2b662b0e, 0x8794f774, 0x2b6041c9, 0x8792d63b, 0x2b5a5868, 0x8790b54c, - 0x2b546eee, 0x878e94a7, - 0x2b4e8558, 0x878c744d, 0x2b489ba8, 0x878a543d, 0x2b42b1dd, 0x87883477, - 0x2b3cc7f7, 0x878614fb, - 0x2b36ddf7, 0x8783f5ca, 0x2b30f3dc, 0x8781d6e3, 0x2b2b09a6, 0x877fb846, - 0x2b251f56, 0x877d99f4, - 0x2b1f34eb, 0x877b7bec, 0x2b194a66, 0x87795e2f, 0x2b135fc6, 0x877740bb, - 0x2b0d750b, 0x87752392, - 0x2b078a36, 0x877306b4, 0x2b019f46, 0x8770ea20, 0x2afbb43c, 0x876ecdd6, - 0x2af5c917, 0x876cb1d6, - 0x2aefddd8, 0x876a9621, 0x2ae9f27e, 0x87687ab7, 0x2ae4070a, 0x87665f96, - 0x2ade1b7c, 0x876444c1, - 0x2ad82fd2, 0x87622a35, 0x2ad2440f, 0x87600ff4, 0x2acc5831, 0x875df5fd, - 0x2ac66c39, 0x875bdc51, - 0x2ac08026, 0x8759c2ef, 0x2aba93f9, 0x8757a9d8, 0x2ab4a7b1, 0x8755910b, - 0x2aaebb50, 0x87537888, - 0x2aa8ced3, 0x87516050, 0x2aa2e23d, 0x874f4862, 0x2a9cf58c, 0x874d30bf, - 0x2a9708c1, 0x874b1966, - 0x2a911bdc, 0x87490258, 0x2a8b2edc, 0x8746eb94, 0x2a8541c3, 0x8744d51b, - 0x2a7f548e, 0x8742beec, - 0x2a796740, 0x8740a907, 0x2a7379d8, 0x873e936d, 0x2a6d8c55, 0x873c7e1e, - 0x2a679eb8, 0x873a6919, - 0x2a61b101, 0x8738545e, 0x2a5bc330, 0x87363fee, 0x2a55d545, 0x87342bc9, - 0x2a4fe740, 0x873217ee, - 0x2a49f920, 0x8730045d, 0x2a440ae7, 0x872df117, 0x2a3e1c93, 0x872bde1c, - 0x2a382e25, 0x8729cb6b, - 0x2a323f9e, 0x8727b905, 0x2a2c50fc, 0x8725a6e9, 0x2a266240, 0x87239518, - 0x2a20736a, 0x87218391, - 0x2a1a847b, 0x871f7255, 0x2a149571, 0x871d6163, 0x2a0ea64d, 0x871b50bc, - 0x2a08b710, 0x87194060, - 0x2a02c7b8, 0x8717304e, 0x29fcd847, 0x87152087, 0x29f6e8bb, 0x8713110a, - 0x29f0f916, 0x871101d8, - 0x29eb0957, 0x870ef2f1, 0x29e5197e, 0x870ce454, 0x29df298b, 0x870ad602, - 0x29d9397f, 0x8708c7fa, - 0x29d34958, 0x8706ba3d, 0x29cd5918, 0x8704acca, 0x29c768be, 0x87029fa3, - 0x29c1784a, 0x870092c5, - 0x29bb87bc, 0x86fe8633, 0x29b59715, 0x86fc79eb, 0x29afa654, 0x86fa6dee, - 0x29a9b579, 0x86f8623b, - 0x29a3c485, 0x86f656d3, 0x299dd377, 0x86f44bb6, 0x2997e24f, 0x86f240e3, - 0x2991f10e, 0x86f0365c, - 0x298bffb2, 0x86ee2c1e, 0x29860e3e, 0x86ec222c, 0x29801caf, 0x86ea1884, - 0x297a2b07, 0x86e80f27, - 0x29743946, 0x86e60614, 0x296e476b, 0x86e3fd4c, 0x29685576, 0x86e1f4cf, - 0x29626368, 0x86dfec9d, - 0x295c7140, 0x86dde4b5, 0x29567eff, 0x86dbdd18, 0x29508ca4, 0x86d9d5c6, - 0x294a9a30, 0x86d7cebf, - 0x2944a7a2, 0x86d5c802, 0x293eb4fb, 0x86d3c190, 0x2938c23a, 0x86d1bb69, - 0x2932cf60, 0x86cfb58c, - 0x292cdc6d, 0x86cdaffa, 0x2926e960, 0x86cbaab3, 0x2920f63a, 0x86c9a5b7, - 0x291b02fa, 0x86c7a106, - 0x29150fa1, 0x86c59c9f, 0x290f1c2f, 0x86c39883, 0x290928a3, 0x86c194b2, - 0x290334ff, 0x86bf912c, - 0x28fd4140, 0x86bd8df0, 0x28f74d69, 0x86bb8b00, 0x28f15978, 0x86b9885a, - 0x28eb656e, 0x86b785ff, - 0x28e5714b, 0x86b583ee, 0x28df7d0e, 0x86b38229, 0x28d988b8, 0x86b180ae, - 0x28d3944a, 0x86af7f7e, - 0x28cd9fc1, 0x86ad7e99, 0x28c7ab20, 0x86ab7dff, 0x28c1b666, 0x86a97db0, - 0x28bbc192, 0x86a77dab, - 0x28b5cca5, 0x86a57df2, 0x28afd7a0, 0x86a37e83, 0x28a9e281, 0x86a17f5f, - 0x28a3ed49, 0x869f8086, - 0x289df7f8, 0x869d81f8, 0x2898028e, 0x869b83b4, 0x28920d0a, 0x869985bc, - 0x288c176e, 0x8697880f, - 0x288621b9, 0x86958aac, 0x28802beb, 0x86938d94, 0x287a3604, 0x869190c7, - 0x28744004, 0x868f9445, - 0x286e49ea, 0x868d980e, 0x286853b8, 0x868b9c22, 0x28625d6d, 0x8689a081, - 0x285c670a, 0x8687a52b, - 0x2856708d, 0x8685aa20, 0x285079f7, 0x8683af5f, 0x284a8349, 0x8681b4ea, - 0x28448c81, 0x867fbabf, - 0x283e95a1, 0x867dc0e0, 0x28389ea8, 0x867bc74b, 0x2832a796, 0x8679ce01, - 0x282cb06c, 0x8677d503, - 0x2826b928, 0x8675dc4f, 0x2820c1cc, 0x8673e3e6, 0x281aca57, 0x8671ebc8, - 0x2814d2c9, 0x866ff3f6, - 0x280edb23, 0x866dfc6e, 0x2808e364, 0x866c0531, 0x2802eb8c, 0x866a0e3f, - 0x27fcf39c, 0x86681798, - 0x27f6fb92, 0x8666213c, 0x27f10371, 0x86642b2c, 0x27eb0b36, 0x86623566, - 0x27e512e3, 0x86603feb, - 0x27df1a77, 0x865e4abb, 0x27d921f3, 0x865c55d7, 0x27d32956, 0x865a613d, - 0x27cd30a1, 0x86586cee, - 0x27c737d3, 0x865678eb, 0x27c13eec, 0x86548532, 0x27bb45ed, 0x865291c4, - 0x27b54cd6, 0x86509ea2, - 0x27af53a6, 0x864eabcb, 0x27a95a5d, 0x864cb93e, 0x27a360fc, 0x864ac6fd, - 0x279d6783, 0x8648d507, - 0x27976df1, 0x8646e35c, 0x27917447, 0x8644f1fc, 0x278b7a84, 0x864300e7, - 0x278580a9, 0x8641101d, - 0x277f86b5, 0x863f1f9e, 0x27798caa, 0x863d2f6b, 0x27739285, 0x863b3f82, - 0x276d9849, 0x86394fe5, - 0x27679df4, 0x86376092, 0x2761a387, 0x8635718b, 0x275ba901, 0x863382cf, - 0x2755ae64, 0x8631945e, - 0x274fb3ae, 0x862fa638, 0x2749b8e0, 0x862db85e, 0x2743bdf9, 0x862bcace, - 0x273dc2fa, 0x8629dd8a, - 0x2737c7e3, 0x8627f091, 0x2731ccb4, 0x862603e3, 0x272bd16d, 0x86241780, - 0x2725d60e, 0x86222b68, - 0x271fda96, 0x86203f9c, 0x2719df06, 0x861e541a, 0x2713e35f, 0x861c68e4, - 0x270de79f, 0x861a7df9, - 0x2707ebc7, 0x86189359, 0x2701efd7, 0x8616a905, 0x26fbf3ce, 0x8614befb, - 0x26f5f7ae, 0x8612d53d, - 0x26effb76, 0x8610ebca, 0x26e9ff26, 0x860f02a3, 0x26e402bd, 0x860d19c6, - 0x26de063d, 0x860b3135, - 0x26d809a5, 0x860948ef, 0x26d20cf5, 0x860760f4, 0x26cc102d, 0x86057944, - 0x26c6134d, 0x860391e0, - 0x26c01655, 0x8601aac7, 0x26ba1945, 0x85ffc3f9, 0x26b41c1d, 0x85fddd76, - 0x26ae1edd, 0x85fbf73f, - 0x26a82186, 0x85fa1153, 0x26a22416, 0x85f82bb2, 0x269c268f, 0x85f6465c, - 0x269628f0, 0x85f46152, - 0x26902b39, 0x85f27c93, 0x268a2d6b, 0x85f09820, 0x26842f84, 0x85eeb3f7, - 0x267e3186, 0x85ecd01a, - 0x26783370, 0x85eaec88, 0x26723543, 0x85e90942, 0x266c36fe, 0x85e72647, - 0x266638a1, 0x85e54397, - 0x26603a2c, 0x85e36132, 0x265a3b9f, 0x85e17f19, 0x26543cfb, 0x85df9d4b, - 0x264e3e40, 0x85ddbbc9, - 0x26483f6c, 0x85dbda91, 0x26424082, 0x85d9f9a5, 0x263c417f, 0x85d81905, - 0x26364265, 0x85d638b0, - 0x26304333, 0x85d458a6, 0x262a43ea, 0x85d278e7, 0x26244489, 0x85d09974, - 0x261e4511, 0x85ceba4d, - 0x26184581, 0x85ccdb70, 0x261245da, 0x85cafcdf, 0x260c461b, 0x85c91e9a, - 0x26064645, 0x85c740a0, - 0x26004657, 0x85c562f1, 0x25fa4652, 0x85c3858d, 0x25f44635, 0x85c1a875, - 0x25ee4601, 0x85bfcba9, - 0x25e845b6, 0x85bdef28, 0x25e24553, 0x85bc12f2, 0x25dc44d9, 0x85ba3707, - 0x25d64447, 0x85b85b68, - 0x25d0439f, 0x85b68015, 0x25ca42de, 0x85b4a50d, 0x25c44207, 0x85b2ca50, - 0x25be4118, 0x85b0efdf, - 0x25b84012, 0x85af15b9, 0x25b23ef5, 0x85ad3bdf, 0x25ac3dc0, 0x85ab6250, - 0x25a63c74, 0x85a9890d, - 0x25a03b11, 0x85a7b015, 0x259a3997, 0x85a5d768, 0x25943806, 0x85a3ff07, - 0x258e365d, 0x85a226f2, - 0x2588349d, 0x85a04f28, 0x258232c6, 0x859e77a9, 0x257c30d8, 0x859ca076, - 0x25762ed3, 0x859ac98f, - 0x25702cb7, 0x8598f2f3, 0x256a2a83, 0x85971ca2, 0x25642839, 0x8595469d, - 0x255e25d7, 0x859370e4, - 0x2558235f, 0x85919b76, 0x255220cf, 0x858fc653, 0x254c1e28, 0x858df17c, - 0x25461b6b, 0x858c1cf1, - 0x25401896, 0x858a48b1, 0x253a15aa, 0x858874bd, 0x253412a8, 0x8586a114, - 0x252e0f8e, 0x8584cdb7, - 0x25280c5e, 0x8582faa5, 0x25220916, 0x858127df, 0x251c05b8, 0x857f5564, - 0x25160243, 0x857d8335, - 0x250ffeb7, 0x857bb152, 0x2509fb14, 0x8579dfba, 0x2503f75a, 0x85780e6e, - 0x24fdf389, 0x85763d6d, - 0x24f7efa2, 0x85746cb8, 0x24f1eba4, 0x85729c4e, 0x24ebe78f, 0x8570cc30, - 0x24e5e363, 0x856efc5e, - 0x24dfdf20, 0x856d2cd7, 0x24d9dac7, 0x856b5d9c, 0x24d3d657, 0x85698ead, - 0x24cdd1d0, 0x8567c009, - 0x24c7cd33, 0x8565f1b0, 0x24c1c87f, 0x856423a4, 0x24bbc3b4, 0x856255e3, - 0x24b5bed2, 0x8560886d, - 0x24afb9da, 0x855ebb44, 0x24a9b4cb, 0x855cee66, 0x24a3afa6, 0x855b21d3, - 0x249daa6a, 0x8559558c, - 0x2497a517, 0x85578991, 0x24919fae, 0x8555bde2, 0x248b9a2f, 0x8553f27e, - 0x24859498, 0x85522766, - 0x247f8eec, 0x85505c99, 0x24798928, 0x854e9219, 0x2473834f, 0x854cc7e3, - 0x246d7d5e, 0x854afdfa, - 0x24677758, 0x8549345c, 0x2461713a, 0x85476b0a, 0x245b6b07, 0x8545a204, - 0x245564bd, 0x8543d949, - 0x244f5e5c, 0x854210db, 0x244957e5, 0x854048b7, 0x24435158, 0x853e80e0, - 0x243d4ab4, 0x853cb954, - 0x243743fa, 0x853af214, 0x24313d2a, 0x85392b20, 0x242b3644, 0x85376477, - 0x24252f47, 0x85359e1a, - 0x241f2833, 0x8533d809, 0x2419210a, 0x85321244, 0x241319ca, 0x85304cca, - 0x240d1274, 0x852e879d, - 0x24070b08, 0x852cc2bb, 0x24010385, 0x852afe24, 0x23fafbec, 0x852939da, - 0x23f4f43e, 0x852775db, - 0x23eeec78, 0x8525b228, 0x23e8e49d, 0x8523eec1, 0x23e2dcac, 0x85222ba5, - 0x23dcd4a4, 0x852068d6, - 0x23d6cc87, 0x851ea652, 0x23d0c453, 0x851ce41a, 0x23cabc09, 0x851b222e, - 0x23c4b3a9, 0x8519608d, - 0x23beab33, 0x85179f39, 0x23b8a2a7, 0x8515de30, 0x23b29a05, 0x85141d73, - 0x23ac914d, 0x85125d02, - 0x23a6887f, 0x85109cdd, 0x23a07f9a, 0x850edd03, 0x239a76a0, 0x850d1d75, - 0x23946d90, 0x850b5e34, - 0x238e646a, 0x85099f3e, 0x23885b2e, 0x8507e094, 0x238251dd, 0x85062235, - 0x237c4875, 0x85046423, - 0x23763ef7, 0x8502a65c, 0x23703564, 0x8500e8e2, 0x236a2bba, 0x84ff2bb3, - 0x236421fb, 0x84fd6ed0, - 0x235e1826, 0x84fbb239, 0x23580e3b, 0x84f9f5ee, 0x2352043b, 0x84f839ee, - 0x234bfa24, 0x84f67e3b, - 0x2345eff8, 0x84f4c2d4, 0x233fe5b6, 0x84f307b8, 0x2339db5e, 0x84f14ce8, - 0x2333d0f1, 0x84ef9265, - 0x232dc66d, 0x84edd82d, 0x2327bbd5, 0x84ec1e41, 0x2321b126, 0x84ea64a1, - 0x231ba662, 0x84e8ab4d, - 0x23159b88, 0x84e6f244, 0x230f9098, 0x84e53988, 0x23098593, 0x84e38118, - 0x23037a78, 0x84e1c8f3, - 0x22fd6f48, 0x84e0111b, 0x22f76402, 0x84de598f, 0x22f158a7, 0x84dca24e, - 0x22eb4d36, 0x84daeb5a, - 0x22e541af, 0x84d934b1, 0x22df3613, 0x84d77e54, 0x22d92a61, 0x84d5c844, - 0x22d31e9a, 0x84d4127f, - 0x22cd12bd, 0x84d25d06, 0x22c706cb, 0x84d0a7da, 0x22c0fac4, 0x84cef2f9, - 0x22baeea7, 0x84cd3e64, - 0x22b4e274, 0x84cb8a1b, 0x22aed62c, 0x84c9d61f, 0x22a8c9cf, 0x84c8226e, - 0x22a2bd5d, 0x84c66f09, - 0x229cb0d5, 0x84c4bbf0, 0x2296a437, 0x84c30924, 0x22909785, 0x84c156a3, - 0x228a8abd, 0x84bfa46e, - 0x22847de0, 0x84bdf286, 0x227e70ed, 0x84bc40e9, 0x227863e5, 0x84ba8f98, - 0x227256c8, 0x84b8de94, - 0x226c4996, 0x84b72ddb, 0x22663c4e, 0x84b57d6f, 0x22602ef1, 0x84b3cd4f, - 0x225a217f, 0x84b21d7a, - 0x225413f8, 0x84b06df2, 0x224e065c, 0x84aebeb6, 0x2247f8aa, 0x84ad0fc6, - 0x2241eae3, 0x84ab6122, - 0x223bdd08, 0x84a9b2ca, 0x2235cf17, 0x84a804be, 0x222fc111, 0x84a656fe, - 0x2229b2f6, 0x84a4a98a, - 0x2223a4c5, 0x84a2fc62, 0x221d9680, 0x84a14f87, 0x22178826, 0x849fa2f7, - 0x221179b7, 0x849df6b4, - 0x220b6b32, 0x849c4abd, 0x22055c99, 0x849a9f12, 0x21ff4dea, 0x8498f3b3, - 0x21f93f27, 0x849748a0, - 0x21f3304f, 0x84959dd9, 0x21ed2162, 0x8493f35e, 0x21e71260, 0x84924930, - 0x21e10349, 0x84909f4e, - 0x21daf41d, 0x848ef5b7, 0x21d4e4dc, 0x848d4c6d, 0x21ced586, 0x848ba36f, - 0x21c8c61c, 0x8489fabe, - 0x21c2b69c, 0x84885258, 0x21bca708, 0x8486aa3e, 0x21b6975f, 0x84850271, - 0x21b087a1, 0x84835af0, - 0x21aa77cf, 0x8481b3bb, 0x21a467e7, 0x84800cd2, 0x219e57eb, 0x847e6636, - 0x219847da, 0x847cbfe5, - 0x219237b5, 0x847b19e1, 0x218c277a, 0x84797429, 0x2186172b, 0x8477cebd, - 0x218006c8, 0x8476299e, - 0x2179f64f, 0x847484ca, 0x2173e5c2, 0x8472e043, 0x216dd521, 0x84713c08, - 0x2167c46b, 0x846f9819, - 0x2161b3a0, 0x846df477, 0x215ba2c0, 0x846c5120, 0x215591cc, 0x846aae16, - 0x214f80c4, 0x84690b58, - 0x21496fa7, 0x846768e7, 0x21435e75, 0x8465c6c1, 0x213d4d2f, 0x846424e8, - 0x21373bd4, 0x8462835b, - 0x21312a65, 0x8460e21a, 0x212b18e1, 0x845f4126, 0x21250749, 0x845da07e, - 0x211ef59d, 0x845c0022, - 0x2118e3dc, 0x845a6012, 0x2112d206, 0x8458c04f, 0x210cc01d, 0x845720d8, - 0x2106ae1e, 0x845581ad, - 0x21009c0c, 0x8453e2cf, 0x20fa89e5, 0x8452443d, 0x20f477aa, 0x8450a5f7, - 0x20ee655a, 0x844f07fd, - 0x20e852f6, 0x844d6a50, 0x20e2407e, 0x844bccef, 0x20dc2df2, 0x844a2fda, - 0x20d61b51, 0x84489311, - 0x20d0089c, 0x8446f695, 0x20c9f5d3, 0x84455a66, 0x20c3e2f5, 0x8443be82, - 0x20bdd003, 0x844222eb, - 0x20b7bcfe, 0x844087a0, 0x20b1a9e4, 0x843eeca2, 0x20ab96b5, 0x843d51f0, - 0x20a58373, 0x843bb78a, - 0x209f701c, 0x843a1d70, 0x20995cb2, 0x843883a3, 0x20934933, 0x8436ea23, - 0x208d35a0, 0x843550ee, - 0x208721f9, 0x8433b806, 0x20810e3e, 0x84321f6b, 0x207afa6f, 0x8430871b, - 0x2074e68c, 0x842eef18, - 0x206ed295, 0x842d5762, 0x2068be8a, 0x842bbff8, 0x2062aa6b, 0x842a28da, - 0x205c9638, 0x84289209, - 0x205681f1, 0x8426fb84, 0x20506d96, 0x8425654b, 0x204a5927, 0x8423cf5f, - 0x204444a4, 0x842239bf, - 0x203e300d, 0x8420a46c, 0x20381b63, 0x841f0f65, 0x203206a4, 0x841d7aaa, - 0x202bf1d2, 0x841be63c, - 0x2025dcec, 0x841a521a, 0x201fc7f2, 0x8418be45, 0x2019b2e4, 0x84172abc, - 0x20139dc2, 0x84159780, - 0x200d888d, 0x84140490, 0x20077344, 0x841271ec, 0x20015de7, 0x8410df95, - 0x1ffb4876, 0x840f4d8a, - 0x1ff532f2, 0x840dbbcc, 0x1fef1d59, 0x840c2a5a, 0x1fe907ae, 0x840a9935, - 0x1fe2f1ee, 0x8409085c, - 0x1fdcdc1b, 0x840777d0, 0x1fd6c634, 0x8405e790, 0x1fd0b03a, 0x8404579d, - 0x1fca9a2b, 0x8402c7f6, - 0x1fc4840a, 0x8401389b, 0x1fbe6dd4, 0x83ffa98d, 0x1fb8578b, 0x83fe1acc, - 0x1fb2412f, 0x83fc8c57, - 0x1fac2abf, 0x83fafe2e, 0x1fa6143b, 0x83f97052, 0x1f9ffda4, 0x83f7e2c3, - 0x1f99e6fa, 0x83f65580, - 0x1f93d03c, 0x83f4c889, 0x1f8db96a, 0x83f33bdf, 0x1f87a285, 0x83f1af82, - 0x1f818b8d, 0x83f02371, - 0x1f7b7481, 0x83ee97ad, 0x1f755d61, 0x83ed0c35, 0x1f6f462f, 0x83eb810a, - 0x1f692ee9, 0x83e9f62b, - 0x1f63178f, 0x83e86b99, 0x1f5d0022, 0x83e6e153, 0x1f56e8a2, 0x83e5575a, - 0x1f50d10e, 0x83e3cdad, - 0x1f4ab968, 0x83e2444d, 0x1f44a1ad, 0x83e0bb3a, 0x1f3e89e0, 0x83df3273, - 0x1f3871ff, 0x83dda9f9, - 0x1f325a0b, 0x83dc21cb, 0x1f2c4204, 0x83da99ea, 0x1f2629ea, 0x83d91255, - 0x1f2011bc, 0x83d78b0d, - 0x1f19f97b, 0x83d60412, 0x1f13e127, 0x83d47d63, 0x1f0dc8c0, 0x83d2f701, - 0x1f07b045, 0x83d170eb, - 0x1f0197b8, 0x83cfeb22, 0x1efb7f17, 0x83ce65a6, 0x1ef56664, 0x83cce076, - 0x1eef4d9d, 0x83cb5b93, - 0x1ee934c3, 0x83c9d6fc, 0x1ee31bd6, 0x83c852b2, 0x1edd02d6, 0x83c6ceb5, - 0x1ed6e9c3, 0x83c54b04, - 0x1ed0d09d, 0x83c3c7a0, 0x1ecab763, 0x83c24488, 0x1ec49e17, 0x83c0c1be, - 0x1ebe84b8, 0x83bf3f3f, - 0x1eb86b46, 0x83bdbd0e, 0x1eb251c1, 0x83bc3b29, 0x1eac3829, 0x83bab991, - 0x1ea61e7e, 0x83b93845, - 0x1ea004c1, 0x83b7b746, 0x1e99eaf0, 0x83b63694, 0x1e93d10c, 0x83b4b62e, - 0x1e8db716, 0x83b33616, - 0x1e879d0d, 0x83b1b649, 0x1e8182f1, 0x83b036ca, 0x1e7b68c2, 0x83aeb797, - 0x1e754e80, 0x83ad38b1, - 0x1e6f342c, 0x83abba17, 0x1e6919c4, 0x83aa3bca, 0x1e62ff4a, 0x83a8bdca, - 0x1e5ce4be, 0x83a74017, - 0x1e56ca1e, 0x83a5c2b0, 0x1e50af6c, 0x83a44596, 0x1e4a94a7, 0x83a2c8c9, - 0x1e4479cf, 0x83a14c48, - 0x1e3e5ee5, 0x839fd014, 0x1e3843e8, 0x839e542d, 0x1e3228d9, 0x839cd893, - 0x1e2c0db6, 0x839b5d45, - 0x1e25f282, 0x8399e244, 0x1e1fd73a, 0x83986790, 0x1e19bbe0, 0x8396ed29, - 0x1e13a074, 0x8395730e, - 0x1e0d84f5, 0x8393f940, 0x1e076963, 0x83927fbf, 0x1e014dbf, 0x8391068a, - 0x1dfb3208, 0x838f8da2, - 0x1df5163f, 0x838e1507, 0x1deefa63, 0x838c9cb9, 0x1de8de75, 0x838b24b8, - 0x1de2c275, 0x8389ad03, - 0x1ddca662, 0x8388359b, 0x1dd68a3c, 0x8386be80, 0x1dd06e04, 0x838547b2, - 0x1dca51ba, 0x8383d130, - 0x1dc4355e, 0x83825afb, 0x1dbe18ef, 0x8380e513, 0x1db7fc6d, 0x837f6f78, - 0x1db1dfda, 0x837dfa2a, - 0x1dabc334, 0x837c8528, 0x1da5a67c, 0x837b1074, 0x1d9f89b1, 0x83799c0c, - 0x1d996cd4, 0x837827f0, - 0x1d934fe5, 0x8376b422, 0x1d8d32e4, 0x837540a1, 0x1d8715d0, 0x8373cd6c, - 0x1d80f8ab, 0x83725a84, - 0x1d7adb73, 0x8370e7e9, 0x1d74be29, 0x836f759b, 0x1d6ea0cc, 0x836e039a, - 0x1d68835e, 0x836c91e5, - 0x1d6265dd, 0x836b207d, 0x1d5c484b, 0x8369af63, 0x1d562aa6, 0x83683e95, - 0x1d500cef, 0x8366ce14, - 0x1d49ef26, 0x83655ddf, 0x1d43d14b, 0x8363edf8, 0x1d3db35e, 0x83627e5d, - 0x1d37955e, 0x83610f10, - 0x1d31774d, 0x835fa00f, 0x1d2b592a, 0x835e315b, 0x1d253af5, 0x835cc2f4, - 0x1d1f1cae, 0x835b54da, - 0x1d18fe54, 0x8359e70d, 0x1d12dfe9, 0x8358798c, 0x1d0cc16c, 0x83570c59, - 0x1d06a2dd, 0x83559f72, - 0x1d00843d, 0x835432d8, 0x1cfa658a, 0x8352c68c, 0x1cf446c5, 0x83515a8c, - 0x1cee27ef, 0x834feed9, - 0x1ce80906, 0x834e8373, 0x1ce1ea0c, 0x834d185a, 0x1cdbcb00, 0x834bad8e, - 0x1cd5abe3, 0x834a430e, - 0x1ccf8cb3, 0x8348d8dc, 0x1cc96d72, 0x83476ef6, 0x1cc34e1f, 0x8346055e, - 0x1cbd2eba, 0x83449c12, - 0x1cb70f43, 0x83433314, 0x1cb0efbb, 0x8341ca62, 0x1caad021, 0x834061fd, - 0x1ca4b075, 0x833ef9e6, - 0x1c9e90b8, 0x833d921b, 0x1c9870e9, 0x833c2a9d, 0x1c925109, 0x833ac36c, - 0x1c8c3116, 0x83395c88, - 0x1c861113, 0x8337f5f1, 0x1c7ff0fd, 0x83368fa7, 0x1c79d0d6, 0x833529aa, - 0x1c73b09d, 0x8333c3fa, - 0x1c6d9053, 0x83325e97, 0x1c676ff8, 0x8330f981, 0x1c614f8b, 0x832f94b8, - 0x1c5b2f0c, 0x832e303c, - 0x1c550e7c, 0x832ccc0d, 0x1c4eedda, 0x832b682b, 0x1c48cd27, 0x832a0496, - 0x1c42ac62, 0x8328a14d, - 0x1c3c8b8c, 0x83273e52, 0x1c366aa5, 0x8325dba4, 0x1c3049ac, 0x83247943, - 0x1c2a28a2, 0x8323172f, - 0x1c240786, 0x8321b568, 0x1c1de659, 0x832053ee, 0x1c17c51b, 0x831ef2c1, - 0x1c11a3cb, 0x831d91e1, - 0x1c0b826a, 0x831c314e, 0x1c0560f8, 0x831ad109, 0x1bff3f75, 0x83197110, - 0x1bf91de0, 0x83181164, - 0x1bf2fc3a, 0x8316b205, 0x1becda83, 0x831552f4, 0x1be6b8ba, 0x8313f42f, - 0x1be096e0, 0x831295b7, - 0x1bda74f6, 0x8311378d, 0x1bd452f9, 0x830fd9af, 0x1bce30ec, 0x830e7c1f, - 0x1bc80ece, 0x830d1edc, - 0x1bc1ec9e, 0x830bc1e6, 0x1bbbca5e, 0x830a653c, 0x1bb5a80c, 0x830908e0, - 0x1baf85a9, 0x8307acd1, - 0x1ba96335, 0x83065110, 0x1ba340b0, 0x8304f59b, 0x1b9d1e1a, 0x83039a73, - 0x1b96fb73, 0x83023f98, - 0x1b90d8bb, 0x8300e50b, 0x1b8ab5f2, 0x82ff8acb, 0x1b849317, 0x82fe30d7, - 0x1b7e702c, 0x82fcd731, - 0x1b784d30, 0x82fb7dd8, 0x1b722a23, 0x82fa24cc, 0x1b6c0705, 0x82f8cc0d, - 0x1b65e3d7, 0x82f7739c, - 0x1b5fc097, 0x82f61b77, 0x1b599d46, 0x82f4c3a0, 0x1b5379e5, 0x82f36c15, - 0x1b4d5672, 0x82f214d8, - 0x1b4732ef, 0x82f0bde8, 0x1b410f5b, 0x82ef6745, 0x1b3aebb6, 0x82ee10ef, - 0x1b34c801, 0x82ecbae7, - 0x1b2ea43a, 0x82eb652b, 0x1b288063, 0x82ea0fbd, 0x1b225c7b, 0x82e8ba9c, - 0x1b1c3883, 0x82e765c8, - 0x1b161479, 0x82e61141, 0x1b0ff05f, 0x82e4bd07, 0x1b09cc34, 0x82e3691b, - 0x1b03a7f9, 0x82e2157c, - 0x1afd83ad, 0x82e0c22a, 0x1af75f50, 0x82df6f25, 0x1af13ae3, 0x82de1c6d, - 0x1aeb1665, 0x82dcca02, - 0x1ae4f1d6, 0x82db77e5, 0x1adecd37, 0x82da2615, 0x1ad8a887, 0x82d8d492, - 0x1ad283c7, 0x82d7835c, - 0x1acc5ef6, 0x82d63274, 0x1ac63a14, 0x82d4e1d8, 0x1ac01522, 0x82d3918a, - 0x1ab9f020, 0x82d24189, - 0x1ab3cb0d, 0x82d0f1d5, 0x1aada5e9, 0x82cfa26f, 0x1aa780b6, 0x82ce5356, - 0x1aa15b71, 0x82cd048a, - 0x1a9b361d, 0x82cbb60b, 0x1a9510b7, 0x82ca67d9, 0x1a8eeb42, 0x82c919f5, - 0x1a88c5bc, 0x82c7cc5e, - 0x1a82a026, 0x82c67f14, 0x1a7c7a7f, 0x82c53217, 0x1a7654c8, 0x82c3e568, - 0x1a702f01, 0x82c29906, - 0x1a6a0929, 0x82c14cf1, 0x1a63e341, 0x82c00129, 0x1a5dbd49, 0x82beb5af, - 0x1a579741, 0x82bd6a82, - 0x1a517128, 0x82bc1fa2, 0x1a4b4aff, 0x82bad50f, 0x1a4524c6, 0x82b98aca, - 0x1a3efe7c, 0x82b840d2, - 0x1a38d823, 0x82b6f727, 0x1a32b1b9, 0x82b5adca, 0x1a2c8b3f, 0x82b464ba, - 0x1a2664b5, 0x82b31bf7, - 0x1a203e1b, 0x82b1d381, 0x1a1a1771, 0x82b08b59, 0x1a13f0b6, 0x82af437e, - 0x1a0dc9ec, 0x82adfbf0, - 0x1a07a311, 0x82acb4b0, 0x1a017c27, 0x82ab6dbd, 0x19fb552c, 0x82aa2717, - 0x19f52e22, 0x82a8e0bf, - 0x19ef0707, 0x82a79ab3, 0x19e8dfdc, 0x82a654f6, 0x19e2b8a2, 0x82a50f85, - 0x19dc9157, 0x82a3ca62, - 0x19d669fc, 0x82a2858c, 0x19d04292, 0x82a14104, 0x19ca1b17, 0x829ffcc8, - 0x19c3f38d, 0x829eb8db, - 0x19bdcbf3, 0x829d753a, 0x19b7a449, 0x829c31e7, 0x19b17c8f, 0x829aeee1, - 0x19ab54c5, 0x8299ac29, - 0x19a52ceb, 0x829869be, 0x199f0502, 0x829727a0, 0x1998dd09, 0x8295e5cf, - 0x1992b4ff, 0x8294a44c, - 0x198c8ce7, 0x82936317, 0x198664be, 0x8292222e, 0x19803c86, 0x8290e194, - 0x197a143e, 0x828fa146, - 0x1973ebe6, 0x828e6146, 0x196dc37e, 0x828d2193, 0x19679b07, 0x828be22e, - 0x19617280, 0x828aa316, - 0x195b49ea, 0x8289644b, 0x19552144, 0x828825ce, 0x194ef88e, 0x8286e79e, - 0x1948cfc8, 0x8285a9bb, - 0x1942a6f3, 0x82846c26, 0x193c7e0f, 0x82832edf, 0x1936551b, 0x8281f1e4, - 0x19302c17, 0x8280b538, - 0x192a0304, 0x827f78d8, 0x1923d9e1, 0x827e3cc6, 0x191db0af, 0x827d0102, - 0x1917876d, 0x827bc58a, - 0x19115e1c, 0x827a8a61, 0x190b34bb, 0x82794f84, 0x19050b4b, 0x827814f6, - 0x18fee1cb, 0x8276dab4, - 0x18f8b83c, 0x8275a0c0, 0x18f28e9e, 0x8274671a, 0x18ec64f0, 0x82732dc0, - 0x18e63b33, 0x8271f4b5, - 0x18e01167, 0x8270bbf7, 0x18d9e78b, 0x826f8386, 0x18d3bda0, 0x826e4b62, - 0x18cd93a5, 0x826d138d, - 0x18c7699b, 0x826bdc04, 0x18c13f82, 0x826aa4c9, 0x18bb155a, 0x82696ddc, - 0x18b4eb22, 0x8268373c, - 0x18aec0db, 0x826700e9, 0x18a89685, 0x8265cae4, 0x18a26c20, 0x8264952d, - 0x189c41ab, 0x82635fc2, - 0x18961728, 0x82622aa6, 0x188fec95, 0x8260f5d7, 0x1889c1f3, 0x825fc155, - 0x18839742, 0x825e8d21, - 0x187d6c82, 0x825d593a, 0x187741b2, 0x825c25a1, 0x187116d4, 0x825af255, - 0x186aebe6, 0x8259bf57, - 0x1864c0ea, 0x82588ca7, 0x185e95de, 0x82575a44, 0x18586ac3, 0x8256282e, - 0x18523f9a, 0x8254f666, - 0x184c1461, 0x8253c4eb, 0x1845e919, 0x825293be, 0x183fbdc3, 0x825162df, - 0x1839925d, 0x8250324d, - 0x183366e9, 0x824f0208, 0x182d3b65, 0x824dd211, 0x18270fd3, 0x824ca268, - 0x1820e431, 0x824b730c, - 0x181ab881, 0x824a43fe, 0x18148cc2, 0x8249153d, 0x180e60f4, 0x8247e6ca, - 0x18083518, 0x8246b8a4, - 0x1802092c, 0x82458acc, 0x17fbdd32, 0x82445d41, 0x17f5b129, 0x82433004, - 0x17ef8511, 0x82420315, - 0x17e958ea, 0x8240d673, 0x17e32cb5, 0x823faa1e, 0x17dd0070, 0x823e7e18, - 0x17d6d41d, 0x823d525e, - 0x17d0a7bc, 0x823c26f3, 0x17ca7b4c, 0x823afbd5, 0x17c44ecd, 0x8239d104, - 0x17be223f, 0x8238a681, - 0x17b7f5a3, 0x82377c4c, 0x17b1c8f8, 0x82365264, 0x17ab9c3e, 0x823528ca, - 0x17a56f76, 0x8233ff7e, - 0x179f429f, 0x8232d67f, 0x179915ba, 0x8231adce, 0x1792e8c6, 0x8230856a, - 0x178cbbc4, 0x822f5d54, - 0x17868eb3, 0x822e358b, 0x17806194, 0x822d0e10, 0x177a3466, 0x822be6e3, - 0x17740729, 0x822ac004, - 0x176dd9de, 0x82299971, 0x1767ac85, 0x8228732d, 0x17617f1d, 0x82274d36, - 0x175b51a7, 0x8226278d, - 0x17552422, 0x82250232, 0x174ef68f, 0x8223dd24, 0x1748c8ee, 0x8222b863, - 0x17429b3e, 0x822193f1, - 0x173c6d80, 0x82206fcc, 0x17363fb4, 0x821f4bf5, 0x173011d9, 0x821e286b, - 0x1729e3f0, 0x821d052f, - 0x1723b5f9, 0x821be240, 0x171d87f3, 0x821abfa0, 0x171759df, 0x82199d4d, - 0x17112bbd, 0x82187b47, - 0x170afd8d, 0x82175990, 0x1704cf4f, 0x82163826, 0x16fea102, 0x82151709, - 0x16f872a7, 0x8213f63a, - 0x16f2443e, 0x8212d5b9, 0x16ec15c7, 0x8211b586, 0x16e5e741, 0x821095a0, - 0x16dfb8ae, 0x820f7608, - 0x16d98a0c, 0x820e56be, 0x16d35b5c, 0x820d37c1, 0x16cd2c9f, 0x820c1912, - 0x16c6fdd3, 0x820afab1, - 0x16c0cef9, 0x8209dc9e, 0x16baa011, 0x8208bed8, 0x16b4711b, 0x8207a160, - 0x16ae4217, 0x82068435, - 0x16a81305, 0x82056758, 0x16a1e3e5, 0x82044ac9, 0x169bb4b7, 0x82032e88, - 0x1695857b, 0x82021294, - 0x168f5632, 0x8200f6ef, 0x168926da, 0x81ffdb96, 0x1682f774, 0x81fec08c, - 0x167cc801, 0x81fda5cf, - 0x1676987f, 0x81fc8b60, 0x167068f0, 0x81fb713f, 0x166a3953, 0x81fa576c, - 0x166409a8, 0x81f93de6, - 0x165dd9f0, 0x81f824ae, 0x1657aa29, 0x81f70bc3, 0x16517a55, 0x81f5f327, - 0x164b4a73, 0x81f4dad8, - 0x16451a83, 0x81f3c2d7, 0x163eea86, 0x81f2ab24, 0x1638ba7a, 0x81f193be, - 0x16328a61, 0x81f07ca6, - 0x162c5a3b, 0x81ef65dc, 0x16262a06, 0x81ee4f60, 0x161ff9c4, 0x81ed3932, - 0x1619c975, 0x81ec2351, - 0x16139918, 0x81eb0dbe, 0x160d68ad, 0x81e9f879, 0x16073834, 0x81e8e381, - 0x160107ae, 0x81e7ced8, - 0x15fad71b, 0x81e6ba7c, 0x15f4a679, 0x81e5a66e, 0x15ee75cb, 0x81e492ad, - 0x15e8450e, 0x81e37f3b, - 0x15e21445, 0x81e26c16, 0x15dbe36d, 0x81e1593f, 0x15d5b288, 0x81e046b6, - 0x15cf8196, 0x81df347b, - 0x15c95097, 0x81de228d, 0x15c31f89, 0x81dd10ee, 0x15bcee6f, 0x81dbff9c, - 0x15b6bd47, 0x81daee98, - 0x15b08c12, 0x81d9dde1, 0x15aa5acf, 0x81d8cd79, 0x15a4297f, 0x81d7bd5e, - 0x159df821, 0x81d6ad92, - 0x1597c6b7, 0x81d59e13, 0x1591953e, 0x81d48ee1, 0x158b63b9, 0x81d37ffe, - 0x15853226, 0x81d27169, - 0x157f0086, 0x81d16321, 0x1578ced9, 0x81d05527, 0x15729d1f, 0x81cf477b, - 0x156c6b57, 0x81ce3a1d, - 0x15663982, 0x81cd2d0c, 0x156007a0, 0x81cc204a, 0x1559d5b1, 0x81cb13d5, - 0x1553a3b4, 0x81ca07af, - 0x154d71aa, 0x81c8fbd6, 0x15473f94, 0x81c7f04b, 0x15410d70, 0x81c6e50d, - 0x153adb3f, 0x81c5da1e, - 0x1534a901, 0x81c4cf7d, 0x152e76b5, 0x81c3c529, 0x1528445d, 0x81c2bb23, - 0x152211f8, 0x81c1b16b, - 0x151bdf86, 0x81c0a801, 0x1515ad06, 0x81bf9ee5, 0x150f7a7a, 0x81be9617, - 0x150947e1, 0x81bd8d97, - 0x1503153a, 0x81bc8564, 0x14fce287, 0x81bb7d7f, 0x14f6afc7, 0x81ba75e9, - 0x14f07cf9, 0x81b96ea0, - 0x14ea4a1f, 0x81b867a5, 0x14e41738, 0x81b760f8, 0x14dde445, 0x81b65a99, - 0x14d7b144, 0x81b55488, - 0x14d17e36, 0x81b44ec4, 0x14cb4b1c, 0x81b3494f, 0x14c517f4, 0x81b24427, - 0x14bee4c0, 0x81b13f4e, - 0x14b8b17f, 0x81b03ac2, 0x14b27e32, 0x81af3684, 0x14ac4ad7, 0x81ae3294, - 0x14a61770, 0x81ad2ef2, - 0x149fe3fc, 0x81ac2b9e, 0x1499b07c, 0x81ab2898, 0x14937cee, 0x81aa25e0, - 0x148d4954, 0x81a92376, - 0x148715ae, 0x81a82159, 0x1480e1fa, 0x81a71f8b, 0x147aae3a, 0x81a61e0b, - 0x14747a6d, 0x81a51cd8, - 0x146e4694, 0x81a41bf4, 0x146812ae, 0x81a31b5d, 0x1461debc, 0x81a21b14, - 0x145baabd, 0x81a11b1a, - 0x145576b1, 0x81a01b6d, 0x144f4299, 0x819f1c0e, 0x14490e74, 0x819e1cfd, - 0x1442da43, 0x819d1e3a, - 0x143ca605, 0x819c1fc5, 0x143671bb, 0x819b219e, 0x14303d65, 0x819a23c5, - 0x142a0902, 0x8199263a, - 0x1423d492, 0x819828fd, 0x141da016, 0x81972c0e, 0x14176b8e, 0x81962f6d, - 0x141136f9, 0x8195331a, - 0x140b0258, 0x81943715, 0x1404cdaa, 0x81933b5e, 0x13fe98f1, 0x81923ff4, - 0x13f8642a, 0x819144d9, - 0x13f22f58, 0x81904a0c, 0x13ebfa79, 0x818f4f8d, 0x13e5c58e, 0x818e555c, - 0x13df9097, 0x818d5b78, - 0x13d95b93, 0x818c61e3, 0x13d32683, 0x818b689c, 0x13ccf167, 0x818a6fa3, - 0x13c6bc3f, 0x818976f8, - 0x13c0870a, 0x81887e9a, 0x13ba51ca, 0x8187868b, 0x13b41c7d, 0x81868eca, - 0x13ade724, 0x81859757, - 0x13a7b1bf, 0x8184a032, 0x13a17c4d, 0x8183a95b, 0x139b46d0, 0x8182b2d1, - 0x13951146, 0x8181bc96, - 0x138edbb1, 0x8180c6a9, 0x1388a60f, 0x817fd10a, 0x13827062, 0x817edbb9, - 0x137c3aa8, 0x817de6b6, - 0x137604e2, 0x817cf201, 0x136fcf10, 0x817bfd9b, 0x13699933, 0x817b0982, - 0x13636349, 0x817a15b7, - 0x135d2d53, 0x8179223a, 0x1356f752, 0x81782f0b, 0x1350c144, 0x81773c2b, - 0x134a8b2b, 0x81764998, - 0x13445505, 0x81755754, 0x133e1ed4, 0x8174655d, 0x1337e897, 0x817373b5, - 0x1331b24e, 0x8172825a, - 0x132b7bf9, 0x8171914e, 0x13254599, 0x8170a090, 0x131f0f2c, 0x816fb020, - 0x1318d8b4, 0x816ebffe, - 0x1312a230, 0x816dd02a, 0x130c6ba0, 0x816ce0a4, 0x13063505, 0x816bf16c, - 0x12fffe5d, 0x816b0282, - 0x12f9c7aa, 0x816a13e6, 0x12f390ec, 0x81692599, 0x12ed5a21, 0x81683799, - 0x12e7234b, 0x816749e8, - 0x12e0ec6a, 0x81665c84, 0x12dab57c, 0x81656f6f, 0x12d47e83, 0x816482a8, - 0x12ce477f, 0x8163962f, - 0x12c8106f, 0x8162aa04, 0x12c1d953, 0x8161be27, 0x12bba22b, 0x8160d298, - 0x12b56af9, 0x815fe758, - 0x12af33ba, 0x815efc65, 0x12a8fc70, 0x815e11c1, 0x12a2c51b, 0x815d276a, - 0x129c8dba, 0x815c3d62, - 0x1296564d, 0x815b53a8, 0x12901ed5, 0x815a6a3c, 0x1289e752, 0x8159811e, - 0x1283afc3, 0x8158984e, - 0x127d7829, 0x8157afcd, 0x12774083, 0x8156c799, 0x127108d2, 0x8155dfb4, - 0x126ad116, 0x8154f81d, - 0x1264994e, 0x815410d4, 0x125e617b, 0x815329d9, 0x1258299c, 0x8152432c, - 0x1251f1b3, 0x81515ccd, - 0x124bb9be, 0x815076bd, 0x124581bd, 0x814f90fb, 0x123f49b2, 0x814eab86, - 0x1239119b, 0x814dc660, - 0x1232d979, 0x814ce188, 0x122ca14b, 0x814bfcff, 0x12266913, 0x814b18c3, - 0x122030cf, 0x814a34d6, - 0x1219f880, 0x81495136, 0x1213c026, 0x81486de5, 0x120d87c1, 0x81478ae2, - 0x12074f50, 0x8146a82e, - 0x120116d5, 0x8145c5c7, 0x11fade4e, 0x8144e3ae, 0x11f4a5bd, 0x814401e4, - 0x11ee6d20, 0x81432068, - 0x11e83478, 0x81423f3a, 0x11e1fbc5, 0x81415e5a, 0x11dbc307, 0x81407dc9, - 0x11d58a3e, 0x813f9d86, - 0x11cf516a, 0x813ebd90, 0x11c9188b, 0x813ddde9, 0x11c2dfa2, 0x813cfe91, - 0x11bca6ad, 0x813c1f86, - 0x11b66dad, 0x813b40ca, 0x11b034a2, 0x813a625b, 0x11a9fb8d, 0x8139843b, - 0x11a3c26c, 0x8138a66a, - 0x119d8941, 0x8137c8e6, 0x1197500a, 0x8136ebb1, 0x119116c9, 0x81360ec9, - 0x118add7d, 0x81353230, - 0x1184a427, 0x813455e6, 0x117e6ac5, 0x813379e9, 0x11783159, 0x81329e3b, - 0x1171f7e2, 0x8131c2db, - 0x116bbe60, 0x8130e7c9, 0x116584d3, 0x81300d05, 0x115f4b3c, 0x812f3290, - 0x1159119a, 0x812e5868, - 0x1152d7ed, 0x812d7e8f, 0x114c9e35, 0x812ca505, 0x11466473, 0x812bcbc8, - 0x11402aa6, 0x812af2da, - 0x1139f0cf, 0x812a1a3a, 0x1133b6ed, 0x812941e8, 0x112d7d00, 0x812869e4, - 0x11274309, 0x8127922f, - 0x11210907, 0x8126bac8, 0x111acefb, 0x8125e3af, 0x111494e4, 0x81250ce4, - 0x110e5ac2, 0x81243668, - 0x11082096, 0x8123603a, 0x1101e65f, 0x81228a5a, 0x10fbac1e, 0x8121b4c8, - 0x10f571d3, 0x8120df85, - 0x10ef377d, 0x81200a90, 0x10e8fd1c, 0x811f35e9, 0x10e2c2b2, 0x811e6191, - 0x10dc883c, 0x811d8d86, - 0x10d64dbd, 0x811cb9ca, 0x10d01333, 0x811be65d, 0x10c9d89e, 0x811b133d, - 0x10c39dff, 0x811a406c, - 0x10bd6356, 0x81196de9, 0x10b728a3, 0x81189bb4, 0x10b0ede5, 0x8117c9ce, - 0x10aab31d, 0x8116f836, - 0x10a4784b, 0x811626ec, 0x109e3d6e, 0x811555f1, 0x10980287, 0x81148544, - 0x1091c796, 0x8113b4e5, - 0x108b8c9b, 0x8112e4d4, 0x10855195, 0x81121512, 0x107f1686, 0x8111459e, - 0x1078db6c, 0x81107678, - 0x1072a048, 0x810fa7a0, 0x106c651a, 0x810ed917, 0x106629e1, 0x810e0adc, - 0x105fee9f, 0x810d3cf0, - 0x1059b352, 0x810c6f52, 0x105377fc, 0x810ba202, 0x104d3c9b, 0x810ad500, - 0x10470130, 0x810a084d, - 0x1040c5bb, 0x81093be8, 0x103a8a3d, 0x81086fd1, 0x10344eb4, 0x8107a409, - 0x102e1321, 0x8106d88f, - 0x1027d784, 0x81060d63, 0x10219bdd, 0x81054286, 0x101b602d, 0x810477f7, - 0x10152472, 0x8103adb6, - 0x100ee8ad, 0x8102e3c4, 0x1008acdf, 0x81021a20, 0x10027107, 0x810150ca, - 0xffc3524, 0x810087c3, - 0xff5f938, 0x80ffbf0a, 0xfefbd42, 0x80fef69f, 0xfe98143, 0x80fe2e83, - 0xfe34539, 0x80fd66b5, - 0xfdd0926, 0x80fc9f35, 0xfd6cd08, 0x80fbd804, 0xfd090e1, 0x80fb1121, - 0xfca54b1, 0x80fa4a8c, - 0xfc41876, 0x80f98446, 0xfbddc32, 0x80f8be4e, 0xfb79fe4, 0x80f7f8a4, - 0xfb1638d, 0x80f73349, - 0xfab272b, 0x80f66e3c, 0xfa4eac0, 0x80f5a97e, 0xf9eae4c, 0x80f4e50e, - 0xf9871ce, 0x80f420ec, - 0xf923546, 0x80f35d19, 0xf8bf8b4, 0x80f29994, 0xf85bc19, 0x80f1d65d, - 0xf7f7f75, 0x80f11375, - 0xf7942c7, 0x80f050db, 0xf73060f, 0x80ef8e90, 0xf6cc94e, 0x80eecc93, - 0xf668c83, 0x80ee0ae4, - 0xf604faf, 0x80ed4984, 0xf5a12d1, 0x80ec8872, 0xf53d5ea, 0x80ebc7ae, - 0xf4d98f9, 0x80eb0739, - 0xf475bff, 0x80ea4712, 0xf411efb, 0x80e9873a, 0xf3ae1ee, 0x80e8c7b0, - 0xf34a4d8, 0x80e80874, - 0xf2e67b8, 0x80e74987, 0xf282a8f, 0x80e68ae8, 0xf21ed5d, 0x80e5cc98, - 0xf1bb021, 0x80e50e96, - 0xf1572dc, 0x80e450e2, 0xf0f358e, 0x80e3937d, 0xf08f836, 0x80e2d666, - 0xf02bad5, 0x80e2199e, - 0xefc7d6b, 0x80e15d24, 0xef63ff7, 0x80e0a0f8, 0xef0027b, 0x80dfe51b, - 0xee9c4f5, 0x80df298c, - 0xee38766, 0x80de6e4c, 0xedd49ce, 0x80ddb35a, 0xed70c2c, 0x80dcf8b7, - 0xed0ce82, 0x80dc3e62, - 0xeca90ce, 0x80db845b, 0xec45311, 0x80dacaa3, 0xebe154b, 0x80da1139, - 0xeb7d77c, 0x80d9581e, - 0xeb199a4, 0x80d89f51, 0xeab5bc3, 0x80d7e6d3, 0xea51dd8, 0x80d72ea3, - 0xe9edfe5, 0x80d676c1, - 0xe98a1e9, 0x80d5bf2e, 0xe9263e3, 0x80d507e9, 0xe8c25d5, 0x80d450f3, - 0xe85e7be, 0x80d39a4b, - 0xe7fa99e, 0x80d2e3f2, 0xe796b74, 0x80d22de7, 0xe732d42, 0x80d1782a, - 0xe6cef07, 0x80d0c2bc, - 0xe66b0c3, 0x80d00d9d, 0xe607277, 0x80cf58cc, 0xe5a3421, 0x80cea449, - 0xe53f5c2, 0x80cdf015, - 0xe4db75b, 0x80cd3c2f, 0xe4778eb, 0x80cc8898, 0xe413a72, 0x80cbd54f, - 0xe3afbf0, 0x80cb2255, - 0xe34bd66, 0x80ca6fa9, 0xe2e7ed2, 0x80c9bd4c, 0xe284036, 0x80c90b3d, - 0xe220191, 0x80c8597c, - 0xe1bc2e4, 0x80c7a80a, 0xe15842e, 0x80c6f6e7, 0xe0f456f, 0x80c64612, - 0xe0906a7, 0x80c5958b, - 0xe02c7d7, 0x80c4e553, 0xdfc88fe, 0x80c4356a, 0xdf64a1c, 0x80c385cf, - 0xdf00b32, 0x80c2d682, - 0xde9cc40, 0x80c22784, 0xde38d44, 0x80c178d4, 0xddd4e40, 0x80c0ca73, - 0xdd70f34, 0x80c01c60, - 0xdd0d01f, 0x80bf6e9c, 0xdca9102, 0x80bec127, 0xdc451dc, 0x80be13ff, - 0xdbe12ad, 0x80bd6727, - 0xdb7d376, 0x80bcba9d, 0xdb19437, 0x80bc0e61, 0xdab54ef, 0x80bb6274, - 0xda5159f, 0x80bab6d5, - 0xd9ed646, 0x80ba0b85, 0xd9896e5, 0x80b96083, 0xd92577b, 0x80b8b5d0, - 0xd8c1809, 0x80b80b6c, - 0xd85d88f, 0x80b76156, 0xd7f990c, 0x80b6b78e, 0xd795982, 0x80b60e15, - 0xd7319ee, 0x80b564ea, - 0xd6cda53, 0x80b4bc0e, 0xd669aaf, 0x80b41381, 0xd605b03, 0x80b36b42, - 0xd5a1b4f, 0x80b2c351, - 0xd53db92, 0x80b21baf, 0xd4d9bcd, 0x80b1745c, 0xd475c00, 0x80b0cd57, - 0xd411c2b, 0x80b026a1, - 0xd3adc4e, 0x80af8039, 0xd349c68, 0x80aeda20, 0xd2e5c7b, 0x80ae3455, - 0xd281c85, 0x80ad8ed9, - 0xd21dc87, 0x80ace9ab, 0xd1b9c81, 0x80ac44cc, 0xd155c73, 0x80aba03b, - 0xd0f1c5d, 0x80aafbf9, - 0xd08dc3f, 0x80aa5806, 0xd029c18, 0x80a9b461, 0xcfc5bea, 0x80a9110b, - 0xcf61bb4, 0x80a86e03, - 0xcefdb76, 0x80a7cb49, 0xce99b2f, 0x80a728df, 0xce35ae1, 0x80a686c2, - 0xcdd1a8b, 0x80a5e4f5, - 0xcd6da2d, 0x80a54376, 0xcd099c7, 0x80a4a245, 0xcca5959, 0x80a40163, - 0xcc418e3, 0x80a360d0, - 0xcbdd865, 0x80a2c08b, 0xcb797e0, 0x80a22095, 0xcb15752, 0x80a180ed, - 0xcab16bd, 0x80a0e194, - 0xca4d620, 0x80a04289, 0xc9e957b, 0x809fa3cd, 0xc9854cf, 0x809f0560, - 0xc92141a, 0x809e6741, - 0xc8bd35e, 0x809dc971, 0xc85929a, 0x809d2bef, 0xc7f51cf, 0x809c8ebc, - 0xc7910fb, 0x809bf1d7, - 0xc72d020, 0x809b5541, 0xc6c8f3e, 0x809ab8fa, 0xc664e53, 0x809a1d01, - 0xc600d61, 0x80998157, - 0xc59cc68, 0x8098e5fb, 0xc538b66, 0x80984aee, 0xc4d4a5d, 0x8097b030, - 0xc47094d, 0x809715c0, - 0xc40c835, 0x80967b9f, 0xc3a8715, 0x8095e1cc, 0xc3445ee, 0x80954848, - 0xc2e04c0, 0x8094af13, - 0xc27c389, 0x8094162c, 0xc21824c, 0x80937d93, 0xc1b4107, 0x8092e54a, - 0xc14ffba, 0x80924d4f, - 0xc0ebe66, 0x8091b5a2, 0xc087d0a, 0x80911e44, 0xc023ba7, 0x80908735, - 0xbfbfa3d, 0x808ff074, - 0xbf5b8cb, 0x808f5a02, 0xbef7752, 0x808ec3df, 0xbe935d2, 0x808e2e0a, - 0xbe2f44a, 0x808d9884, - 0xbdcb2bb, 0x808d034c, 0xbd67124, 0x808c6e63, 0xbd02f87, 0x808bd9c9, - 0xbc9ede2, 0x808b457d, - 0xbc3ac35, 0x808ab180, 0xbbd6a82, 0x808a1dd2, 0xbb728c7, 0x80898a72, - 0xbb0e705, 0x8088f761, - 0xbaaa53b, 0x8088649e, 0xba4636b, 0x8087d22a, 0xb9e2193, 0x80874005, - 0xb97dfb5, 0x8086ae2e, - 0xb919dcf, 0x80861ca6, 0xb8b5be1, 0x80858b6c, 0xb8519ed, 0x8084fa82, - 0xb7ed7f2, 0x808469e5, - 0xb7895f0, 0x8083d998, 0xb7253e6, 0x80834999, 0xb6c11d5, 0x8082b9e9, - 0xb65cfbe, 0x80822a87, - 0xb5f8d9f, 0x80819b74, 0xb594b7a, 0x80810cb0, 0xb53094d, 0x80807e3a, - 0xb4cc719, 0x807ff013, - 0xb4684df, 0x807f623b, 0xb40429d, 0x807ed4b1, 0xb3a0055, 0x807e4776, - 0xb33be05, 0x807dba89, - 0xb2d7baf, 0x807d2dec, 0xb273952, 0x807ca19c, 0xb20f6ee, 0x807c159c, - 0xb1ab483, 0x807b89ea, - 0xb147211, 0x807afe87, 0xb0e2f98, 0x807a7373, 0xb07ed19, 0x8079e8ad, - 0xb01aa92, 0x80795e36, - 0xafb6805, 0x8078d40d, 0xaf52571, 0x80784a33, 0xaeee2d7, 0x8077c0a8, - 0xae8a036, 0x8077376c, - 0xae25d8d, 0x8076ae7e, 0xadc1adf, 0x807625df, 0xad5d829, 0x80759d8e, - 0xacf956d, 0x8075158c, - 0xac952aa, 0x80748dd9, 0xac30fe1, 0x80740675, 0xabccd11, 0x80737f5f, - 0xab68a3a, 0x8072f898, - 0xab0475c, 0x8072721f, 0xaaa0478, 0x8071ebf6, 0xaa3c18e, 0x8071661a, - 0xa9d7e9d, 0x8070e08e, - 0xa973ba5, 0x80705b50, 0xa90f8a7, 0x806fd661, 0xa8ab5a2, 0x806f51c1, - 0xa847297, 0x806ecd6f, - 0xa7e2f85, 0x806e496c, 0xa77ec6d, 0x806dc5b8, 0xa71a94f, 0x806d4253, - 0xa6b662a, 0x806cbf3c, - 0xa6522fe, 0x806c3c74, 0xa5edfcc, 0x806bb9fa, 0xa589c94, 0x806b37cf, - 0xa525955, 0x806ab5f3, - 0xa4c1610, 0x806a3466, 0xa45d2c5, 0x8069b327, 0xa3f8f73, 0x80693237, - 0xa394c1b, 0x8068b196, - 0xa3308bd, 0x80683143, 0xa2cc558, 0x8067b13f, 0xa2681ed, 0x8067318a, - 0xa203e7c, 0x8066b224, - 0xa19fb04, 0x8066330c, 0xa13b787, 0x8065b443, 0xa0d7403, 0x806535c9, - 0xa073079, 0x8064b79d, - 0xa00ece8, 0x806439c0, 0x9faa952, 0x8063bc32, 0x9f465b5, 0x80633ef3, - 0x9ee2213, 0x8062c202, - 0x9e7de6a, 0x80624560, 0x9e19abb, 0x8061c90c, 0x9db5706, 0x80614d08, - 0x9d5134b, 0x8060d152, - 0x9cecf89, 0x806055eb, 0x9c88bc2, 0x805fdad2, 0x9c247f5, 0x805f6009, - 0x9bc0421, 0x805ee58e, - 0x9b5c048, 0x805e6b62, 0x9af7c69, 0x805df184, 0x9a93884, 0x805d77f5, - 0x9a2f498, 0x805cfeb5, - 0x99cb0a7, 0x805c85c4, 0x9966cb0, 0x805c0d21, 0x99028b3, 0x805b94ce, - 0x989e4b0, 0x805b1cc8, - 0x983a0a7, 0x805aa512, 0x97d5c99, 0x805a2daa, 0x9771884, 0x8059b692, - 0x970d46a, 0x80593fc7, - 0x96a9049, 0x8058c94c, 0x9644c23, 0x8058531f, 0x95e07f8, 0x8057dd41, - 0x957c3c6, 0x805767b2, - 0x9517f8f, 0x8056f272, 0x94b3b52, 0x80567d80, 0x944f70f, 0x805608dd, - 0x93eb2c6, 0x80559489, - 0x9386e78, 0x80552084, 0x9322a24, 0x8054accd, 0x92be5ca, 0x80543965, - 0x925a16b, 0x8053c64c, - 0x91f5d06, 0x80535381, 0x919189c, 0x8052e106, 0x912d42c, 0x80526ed9, - 0x90c8fb6, 0x8051fcfb, - 0x9064b3a, 0x80518b6b, 0x90006ba, 0x80511a2b, 0x8f9c233, 0x8050a939, - 0x8f37da7, 0x80503896, - 0x8ed3916, 0x804fc841, 0x8e6f47f, 0x804f583c, 0x8e0afe2, 0x804ee885, - 0x8da6b40, 0x804e791d, - 0x8d42699, 0x804e0a04, 0x8cde1ec, 0x804d9b39, 0x8c79d3a, 0x804d2cbd, - 0x8c15882, 0x804cbe90, - 0x8bb13c5, 0x804c50b2, 0x8b4cf02, 0x804be323, 0x8ae8a3a, 0x804b75e2, - 0x8a8456d, 0x804b08f0, - 0x8a2009a, 0x804a9c4d, 0x89bbbc3, 0x804a2ff9, 0x89576e5, 0x8049c3f3, - 0x88f3203, 0x8049583d, - 0x888ed1b, 0x8048ecd5, 0x882a82e, 0x804881bb, 0x87c633c, 0x804816f1, - 0x8761e44, 0x8047ac75, - 0x86fd947, 0x80474248, 0x8699445, 0x8046d86a, 0x8634f3e, 0x80466edb, - 0x85d0a32, 0x8046059b, - 0x856c520, 0x80459ca9, 0x850800a, 0x80453406, 0x84a3aee, 0x8044cbb2, - 0x843f5cd, 0x804463ad, - 0x83db0a7, 0x8043fbf6, 0x8376b7c, 0x8043948e, 0x831264c, 0x80432d75, - 0x82ae117, 0x8042c6ab, - 0x8249bdd, 0x80426030, 0x81e569d, 0x8041fa03, 0x8181159, 0x80419425, - 0x811cc10, 0x80412e96, - 0x80b86c2, 0x8040c956, 0x805416e, 0x80406465, 0x7fefc16, 0x803fffc2, - 0x7f8b6b9, 0x803f9b6f, - 0x7f27157, 0x803f376a, 0x7ec2bf0, 0x803ed3b3, 0x7e5e685, 0x803e704c, - 0x7dfa114, 0x803e0d34, - 0x7d95b9e, 0x803daa6a, 0x7d31624, 0x803d47ef, 0x7ccd0a5, 0x803ce5c3, - 0x7c68b21, 0x803c83e5, - 0x7c04598, 0x803c2257, 0x7ba000b, 0x803bc117, 0x7b3ba78, 0x803b6026, - 0x7ad74e1, 0x803aff84, - 0x7a72f45, 0x803a9f31, 0x7a0e9a5, 0x803a3f2d, 0x79aa400, 0x8039df77, - 0x7945e56, 0x80398010, - 0x78e18a7, 0x803920f8, 0x787d2f4, 0x8038c22f, 0x7818d3c, 0x803863b5, - 0x77b4780, 0x80380589, - 0x77501be, 0x8037a7ac, 0x76ebbf9, 0x80374a1f, 0x768762e, 0x8036ece0, - 0x762305f, 0x80368fef, - 0x75bea8c, 0x8036334e, 0x755a4b4, 0x8035d6fb, 0x74f5ed7, 0x80357af8, - 0x74918f6, 0x80351f43, - 0x742d311, 0x8034c3dd, 0x73c8d27, 0x803468c5, 0x7364738, 0x80340dfd, - 0x7300145, 0x8033b383, - 0x729bb4e, 0x80335959, 0x7237552, 0x8032ff7d, 0x71d2f52, 0x8032a5ef, - 0x716e94e, 0x80324cb1, - 0x710a345, 0x8031f3c2, 0x70a5d37, 0x80319b21, 0x7041726, 0x803142cf, - 0x6fdd110, 0x8030eacd, - 0x6f78af6, 0x80309318, 0x6f144d7, 0x80303bb3, 0x6eafeb4, 0x802fe49d, - 0x6e4b88d, 0x802f8dd5, - 0x6de7262, 0x802f375d, 0x6d82c32, 0x802ee133, 0x6d1e5fe, 0x802e8b58, - 0x6cb9fc6, 0x802e35cb, - 0x6c5598a, 0x802de08e, 0x6bf1349, 0x802d8ba0, 0x6b8cd05, 0x802d3700, - 0x6b286bc, 0x802ce2af, - 0x6ac406f, 0x802c8ead, 0x6a5fa1e, 0x802c3afa, 0x69fb3c9, 0x802be796, - 0x6996d70, 0x802b9480, - 0x6932713, 0x802b41ba, 0x68ce0b2, 0x802aef42, 0x6869a4c, 0x802a9d19, - 0x68053e3, 0x802a4b3f, - 0x67a0d76, 0x8029f9b4, 0x673c704, 0x8029a878, 0x66d808f, 0x8029578b, - 0x6673a16, 0x802906ec, - 0x660f398, 0x8028b69c, 0x65aad17, 0x8028669b, 0x6546692, 0x802816e9, - 0x64e2009, 0x8027c786, - 0x647d97c, 0x80277872, 0x64192eb, 0x802729ad, 0x63b4c57, 0x8026db36, - 0x63505be, 0x80268d0e, - 0x62ebf22, 0x80263f36, 0x6287882, 0x8025f1ac, 0x62231de, 0x8025a471, - 0x61beb36, 0x80255784, - 0x615a48b, 0x80250ae7, 0x60f5ddc, 0x8024be99, 0x6091729, 0x80247299, - 0x602d072, 0x802426e8, - 0x5fc89b8, 0x8023db86, 0x5f642fa, 0x80239073, 0x5effc38, 0x802345af, - 0x5e9b572, 0x8022fb3a, - 0x5e36ea9, 0x8022b114, 0x5dd27dd, 0x8022673c, 0x5d6e10c, 0x80221db3, - 0x5d09a38, 0x8021d47a, - 0x5ca5361, 0x80218b8f, 0x5c40c86, 0x802142f3, 0x5bdc5a7, 0x8020faa6, - 0x5b77ec5, 0x8020b2a7, - 0x5b137df, 0x80206af8, 0x5aaf0f6, 0x80202397, 0x5a4aa09, 0x801fdc86, - 0x59e6319, 0x801f95c3, - 0x5981c26, 0x801f4f4f, 0x591d52f, 0x801f092a, 0x58b8e34, 0x801ec354, - 0x5854736, 0x801e7dcd, - 0x57f0035, 0x801e3895, 0x578b930, 0x801df3ab, 0x5727228, 0x801daf11, - 0x56c2b1c, 0x801d6ac5, - 0x565e40d, 0x801d26c8, 0x55f9cfb, 0x801ce31a, 0x55955e6, 0x801c9fbb, - 0x5530ecd, 0x801c5cab, - 0x54cc7b1, 0x801c19ea, 0x5468092, 0x801bd777, 0x540396f, 0x801b9554, - 0x539f249, 0x801b537f, - 0x533ab20, 0x801b11fa, 0x52d63f4, 0x801ad0c3, 0x5271cc4, 0x801a8fdb, - 0x520d592, 0x801a4f42, - 0x51a8e5c, 0x801a0ef8, 0x5144723, 0x8019cefd, 0x50dffe7, 0x80198f50, - 0x507b8a8, 0x80194ff3, - 0x5017165, 0x801910e4, 0x4fb2a20, 0x8018d225, 0x4f4e2d8, 0x801893b4, - 0x4ee9b8c, 0x80185592, - 0x4e8543e, 0x801817bf, 0x4e20cec, 0x8017da3b, 0x4dbc597, 0x80179d06, - 0x4d57e40, 0x80176020, - 0x4cf36e5, 0x80172388, 0x4c8ef88, 0x8016e740, 0x4c2a827, 0x8016ab46, - 0x4bc60c4, 0x80166f9c, - 0x4b6195d, 0x80163440, 0x4afd1f4, 0x8015f933, 0x4a98a88, 0x8015be75, - 0x4a34319, 0x80158406, - 0x49cfba7, 0x801549e6, 0x496b432, 0x80151015, 0x4906cbb, 0x8014d693, - 0x48a2540, 0x80149d5f, - 0x483ddc3, 0x8014647b, 0x47d9643, 0x80142be5, 0x4774ec1, 0x8013f39e, - 0x471073b, 0x8013bba7, - 0x46abfb3, 0x801383fe, 0x4647828, 0x80134ca4, 0x45e309a, 0x80131599, - 0x457e90a, 0x8012dedd, - 0x451a177, 0x8012a86f, 0x44b59e1, 0x80127251, 0x4451249, 0x80123c82, - 0x43ecaae, 0x80120701, - 0x4388310, 0x8011d1d0, 0x4323b70, 0x80119ced, 0x42bf3cd, 0x80116859, - 0x425ac28, 0x80113414, - 0x41f6480, 0x8011001f, 0x4191cd5, 0x8010cc78, 0x412d528, 0x8010991f, - 0x40c8d79, 0x80106616, - 0x40645c7, 0x8010335c, 0x3fffe12, 0x801000f1, 0x3f9b65b, 0x800fced4, - 0x3f36ea2, 0x800f9d07, - 0x3ed26e6, 0x800f6b88, 0x3e6df28, 0x800f3a59, 0x3e09767, 0x800f0978, - 0x3da4fa4, 0x800ed8e6, - 0x3d407df, 0x800ea8a3, 0x3cdc017, 0x800e78af, 0x3c7784d, 0x800e490a, - 0x3c13080, 0x800e19b4, - 0x3bae8b2, 0x800deaad, 0x3b4a0e0, 0x800dbbf5, 0x3ae590d, 0x800d8d8b, - 0x3a81137, 0x800d5f71, - 0x3a1c960, 0x800d31a5, 0x39b8185, 0x800d0429, 0x39539a9, 0x800cd6fb, - 0x38ef1ca, 0x800caa1c, - 0x388a9ea, 0x800c7d8c, 0x3826207, 0x800c514c, 0x37c1a22, 0x800c255a, - 0x375d23a, 0x800bf9b7, - 0x36f8a51, 0x800bce63, 0x3694265, 0x800ba35d, 0x362fa78, 0x800b78a7, - 0x35cb288, 0x800b4e40, - 0x3566a96, 0x800b2427, 0x35022a2, 0x800afa5e, 0x349daac, 0x800ad0e3, - 0x34392b4, 0x800aa7b8, - 0x33d4abb, 0x800a7edb, 0x33702bf, 0x800a564e, 0x330bac1, 0x800a2e0f, - 0x32a72c1, 0x800a061f, - 0x3242abf, 0x8009de7e, 0x31de2bb, 0x8009b72c, 0x3179ab5, 0x80099029, - 0x31152ae, 0x80096975, - 0x30b0aa4, 0x80094310, 0x304c299, 0x80091cf9, 0x2fe7a8c, 0x8008f732, - 0x2f8327d, 0x8008d1ba, - 0x2f1ea6c, 0x8008ac90, 0x2eba259, 0x800887b6, 0x2e55a44, 0x8008632a, - 0x2df122e, 0x80083eed, - 0x2d8ca16, 0x80081b00, 0x2d281fc, 0x8007f761, 0x2cc39e1, 0x8007d411, - 0x2c5f1c3, 0x8007b110, - 0x2bfa9a4, 0x80078e5e, 0x2b96184, 0x80076bfb, 0x2b31961, 0x800749e7, - 0x2acd13d, 0x80072822, - 0x2a68917, 0x800706ac, 0x2a040f0, 0x8006e585, 0x299f8c7, 0x8006c4ac, - 0x293b09c, 0x8006a423, - 0x28d6870, 0x800683e8, 0x2872043, 0x800663fd, 0x280d813, 0x80064460, - 0x27a8fe2, 0x80062513, - 0x27447b0, 0x80060614, 0x26dff7c, 0x8005e764, 0x267b747, 0x8005c904, - 0x2616f10, 0x8005aaf2, - 0x25b26d7, 0x80058d2f, 0x254de9e, 0x80056fbb, 0x24e9662, 0x80055296, - 0x2484e26, 0x800535c0, - 0x24205e8, 0x80051939, 0x23bbda8, 0x8004fd00, 0x2357567, 0x8004e117, - 0x22f2d25, 0x8004c57d, - 0x228e4e2, 0x8004aa32, 0x2229c9d, 0x80048f35, 0x21c5457, 0x80047488, - 0x2160c0f, 0x80045a29, - 0x20fc3c6, 0x8004401a, 0x2097b7c, 0x80042659, 0x2033331, 0x80040ce7, - 0x1fceae4, 0x8003f3c5, - 0x1f6a297, 0x8003daf1, 0x1f05a48, 0x8003c26c, 0x1ea11f7, 0x8003aa36, - 0x1e3c9a6, 0x8003924f, - 0x1dd8154, 0x80037ab7, 0x1d73900, 0x8003636e, 0x1d0f0ab, 0x80034c74, - 0x1caa855, 0x800335c9, - 0x1c45ffe, 0x80031f6d, 0x1be17a6, 0x80030960, 0x1b7cf4d, 0x8002f3a1, - 0x1b186f3, 0x8002de32, - 0x1ab3e97, 0x8002c912, 0x1a4f63b, 0x8002b440, 0x19eaddd, 0x80029fbe, - 0x198657f, 0x80028b8a, - 0x1921d20, 0x800277a6, 0x18bd4bf, 0x80026410, 0x1858c5e, 0x800250c9, - 0x17f43fc, 0x80023dd2, - 0x178fb99, 0x80022b29, 0x172b335, 0x800218cf, 0x16c6ad0, 0x800206c4, - 0x166226a, 0x8001f508, - 0x15fda03, 0x8001e39b, 0x159919c, 0x8001d27d, 0x1534934, 0x8001c1ae, - 0x14d00ca, 0x8001b12e, - 0x146b860, 0x8001a0fd, 0x1406ff6, 0x8001911b, 0x13a278a, 0x80018187, - 0x133df1e, 0x80017243, - 0x12d96b1, 0x8001634e, 0x1274e43, 0x800154a7, 0x12105d5, 0x80014650, - 0x11abd66, 0x80013847, - 0x11474f6, 0x80012a8e, 0x10e2c85, 0x80011d23, 0x107e414, 0x80011008, - 0x1019ba2, 0x8001033b, - 0xfb5330, 0x8000f6bd, 0xf50abd, 0x8000ea8e, 0xeec249, 0x8000deaf, 0xe879d5, - 0x8000d31e, - 0xe23160, 0x8000c7dc, 0xdbe8eb, 0x8000bce9, 0xd5a075, 0x8000b245, 0xcf57ff, - 0x8000a7f0, - 0xc90f88, 0x80009dea, 0xc2c711, 0x80009433, 0xbc7e99, 0x80008aca, 0xb63621, - 0x800081b1, - 0xafeda8, 0x800078e7, 0xa9a52f, 0x8000706c, 0xa35cb5, 0x8000683f, 0x9d143b, - 0x80006062, - 0x96cbc1, 0x800058d4, 0x908346, 0x80005194, 0x8a3acb, 0x80004aa4, 0x83f250, - 0x80004402, - 0x7da9d4, 0x80003daf, 0x776159, 0x800037ac, 0x7118dc, 0x800031f7, 0x6ad060, - 0x80002c91, - 0x6487e3, 0x8000277a, 0x5e3f66, 0x800022b3, 0x57f6e9, 0x80001e3a, 0x51ae6b, - 0x80001a10, - 0x4b65ee, 0x80001635, 0x451d70, 0x800012a9, 0x3ed4f2, 0x80000f6c, 0x388c74, - 0x80000c7e, - 0x3243f5, 0x800009df, 0x2bfb77, 0x8000078e, 0x25b2f8, 0x8000058d, 0x1f6a7a, - 0x800003db, - 0x1921fb, 0x80000278, 0x12d97c, 0x80000163, 0xc90fe, 0x8000009e, 0x6487f, - 0x80000027, - -}; - -/** -* \par -* cosFactor tables are generated using the formula :
cos_factors[n] = 2 * cos((2n+1)*pi/(4*N))
-* \par -* C command to generate the table -*
    
-* for(i = 0; i< N; i++)    
-* {    
-*   cos_factors[i]= 2 * cos((2*i+1)*c/2);    
-* } 
-* \par -* where N is the number of factors to generate and c is pi/(2*N) -* \par -* Then converted to q31 format by multiplying with 2^31 and saturated if required. -*/ - - -static const q31_t cos_factorsQ31_128[128] = { - 0x7fff6216, 0x7ffa72d1, 0x7ff09478, 0x7fe1c76b, 0x7fce0c3e, 0x7fb563b3, - 0x7f97cebd, 0x7f754e80, - 0x7f4de451, 0x7f2191b4, 0x7ef05860, 0x7eba3a39, 0x7e7f3957, 0x7e3f57ff, - 0x7dfa98a8, 0x7db0fdf8, - 0x7d628ac6, 0x7d0f4218, 0x7cb72724, 0x7c5a3d50, 0x7bf88830, 0x7b920b89, - 0x7b26cb4f, 0x7ab6cba4, - 0x7a4210d8, 0x79c89f6e, 0x794a7c12, 0x78c7aba2, 0x78403329, 0x77b417df, - 0x77235f2d, 0x768e0ea6, - 0x75f42c0b, 0x7555bd4c, 0x74b2c884, 0x740b53fb, 0x735f6626, 0x72af05a7, - 0x71fa3949, 0x71410805, - 0x708378ff, 0x6fc19385, 0x6efb5f12, 0x6e30e34a, 0x6d6227fa, 0x6c8f351c, - 0x6bb812d1, 0x6adcc964, - 0x69fd614a, 0x6919e320, 0x683257ab, 0x6746c7d8, 0x66573cbb, 0x6563bf92, - 0x646c59bf, 0x637114cc, - 0x6271fa69, 0x616f146c, 0x60686ccf, 0x5f5e0db3, 0x5e50015d, 0x5d3e5237, - 0x5c290acc, 0x5b1035cf, - 0x59f3de12, 0x58d40e8c, 0x57b0d256, 0x568a34a9, 0x556040e2, 0x5433027d, - 0x53028518, 0x51ced46e, - 0x5097fc5e, 0x4f5e08e3, 0x4e210617, 0x4ce10034, 0x4b9e0390, 0x4a581c9e, - 0x490f57ee, 0x47c3c22f, - 0x46756828, 0x452456bd, 0x43d09aed, 0x427a41d0, 0x4121589b, 0x3fc5ec98, - 0x3e680b2c, 0x3d07c1d6, - 0x3ba51e29, 0x3a402dd2, 0x38d8fe93, 0x376f9e46, 0x36041ad9, 0x34968250, - 0x3326e2c3, 0x31b54a5e, - 0x3041c761, 0x2ecc681e, 0x2d553afc, 0x2bdc4e6f, 0x2a61b101, 0x28e5714b, - 0x27679df4, 0x25e845b6, - 0x24677758, 0x22e541af, 0x2161b3a0, 0x1fdcdc1b, 0x1e56ca1e, 0x1ccf8cb3, - 0x1b4732ef, 0x19bdcbf3, - 0x183366e9, 0x16a81305, 0x151bdf86, 0x138edbb1, 0x120116d5, 0x1072a048, - 0xee38766, 0xd53db92, - 0xbc3ac35, 0xa3308bd, 0x8a2009a, 0x710a345, 0x57f0035, 0x3ed26e6, 0x25b26d7, - 0xc90f88, -}; - -static const q31_t cos_factorsQ31_512[512] = { - 0x7ffff621, 0x7fffa72c, 0x7fff0943, 0x7ffe1c65, 0x7ffce093, 0x7ffb55ce, - 0x7ff97c18, 0x7ff75370, - 0x7ff4dbd9, 0x7ff21553, 0x7feeffe1, 0x7feb9b85, 0x7fe7e841, 0x7fe3e616, - 0x7fdf9508, 0x7fdaf519, - 0x7fd6064c, 0x7fd0c8a3, 0x7fcb3c23, 0x7fc560cf, 0x7fbf36aa, 0x7fb8bdb8, - 0x7fb1f5fc, 0x7faadf7c, - 0x7fa37a3c, 0x7f9bc640, 0x7f93c38c, 0x7f8b7227, 0x7f82d214, 0x7f79e35a, - 0x7f70a5fe, 0x7f671a05, - 0x7f5d3f75, 0x7f531655, 0x7f489eaa, 0x7f3dd87c, 0x7f32c3d1, 0x7f2760af, - 0x7f1baf1e, 0x7f0faf25, - 0x7f0360cb, 0x7ef6c418, 0x7ee9d914, 0x7edc9fc6, 0x7ecf1837, 0x7ec14270, - 0x7eb31e78, 0x7ea4ac58, - 0x7e95ec1a, 0x7e86ddc6, 0x7e778166, 0x7e67d703, 0x7e57dea7, 0x7e47985b, - 0x7e37042a, 0x7e26221f, - 0x7e14f242, 0x7e0374a0, 0x7df1a942, 0x7ddf9034, 0x7dcd2981, 0x7dba7534, - 0x7da77359, 0x7d9423fc, - 0x7d808728, 0x7d6c9ce9, 0x7d58654d, 0x7d43e05e, 0x7d2f0e2b, 0x7d19eebf, - 0x7d048228, 0x7ceec873, - 0x7cd8c1ae, 0x7cc26de5, 0x7cabcd28, 0x7c94df83, 0x7c7da505, 0x7c661dbc, - 0x7c4e49b7, 0x7c362904, - 0x7c1dbbb3, 0x7c0501d2, 0x7bebfb70, 0x7bd2a89e, 0x7bb9096b, 0x7b9f1de6, - 0x7b84e61f, 0x7b6a6227, - 0x7b4f920e, 0x7b3475e5, 0x7b190dbc, 0x7afd59a4, 0x7ae159ae, 0x7ac50dec, - 0x7aa8766f, 0x7a8b9348, - 0x7a6e648a, 0x7a50ea47, 0x7a332490, 0x7a151378, 0x79f6b711, 0x79d80f6f, - 0x79b91ca4, 0x7999dec4, - 0x797a55e0, 0x795a820e, 0x793a6361, 0x7919f9ec, 0x78f945c3, 0x78d846fb, - 0x78b6fda8, 0x789569df, - 0x78738bb3, 0x7851633b, 0x782ef08b, 0x780c33b8, 0x77e92cd9, 0x77c5dc01, - 0x77a24148, 0x777e5cc3, - 0x775a2e89, 0x7735b6af, 0x7710f54c, 0x76ebea77, 0x76c69647, 0x76a0f8d2, - 0x767b1231, 0x7654e279, - 0x762e69c4, 0x7607a828, 0x75e09dbd, 0x75b94a9c, 0x7591aedd, 0x7569ca99, - 0x75419de7, 0x751928e0, - 0x74f06b9e, 0x74c7663a, 0x749e18cd, 0x74748371, 0x744aa63f, 0x74208150, - 0x73f614c0, 0x73cb60a8, - 0x73a06522, 0x73752249, 0x73499838, 0x731dc70a, 0x72f1aed9, 0x72c54fc1, - 0x7298a9dd, 0x726bbd48, - 0x723e8a20, 0x7211107e, 0x71e35080, 0x71b54a41, 0x7186fdde, 0x71586b74, - 0x7129931f, 0x70fa74fc, - 0x70cb1128, 0x709b67c0, 0x706b78e3, 0x703b44ad, 0x700acb3c, 0x6fda0cae, - 0x6fa90921, 0x6f77c0b3, - 0x6f463383, 0x6f1461b0, 0x6ee24b57, 0x6eaff099, 0x6e7d5193, 0x6e4a6e66, - 0x6e174730, 0x6de3dc11, - 0x6db02d29, 0x6d7c3a98, 0x6d48047e, 0x6d138afb, 0x6cdece2f, 0x6ca9ce3b, - 0x6c748b3f, 0x6c3f055d, - 0x6c093cb6, 0x6bd3316a, 0x6b9ce39b, 0x6b66536b, 0x6b2f80fb, 0x6af86c6c, - 0x6ac115e2, 0x6a897d7d, - 0x6a51a361, 0x6a1987b0, 0x69e12a8c, 0x69a88c19, 0x696fac78, 0x69368bce, - 0x68fd2a3d, 0x68c387e9, - 0x6889a4f6, 0x684f8186, 0x68151dbe, 0x67da79c3, 0x679f95b7, 0x676471c0, - 0x67290e02, 0x66ed6aa1, - 0x66b187c3, 0x6675658c, 0x66390422, 0x65fc63a9, 0x65bf8447, 0x65826622, - 0x6545095f, 0x65076e25, - 0x64c99498, 0x648b7ce0, 0x644d2722, 0x640e9386, 0x63cfc231, 0x6390b34a, - 0x635166f9, 0x6311dd64, - 0x62d216b3, 0x6292130c, 0x6251d298, 0x6211557e, 0x61d09be5, 0x618fa5f7, - 0x614e73da, 0x610d05b7, - 0x60cb5bb7, 0x60897601, 0x604754bf, 0x6004f819, 0x5fc26038, 0x5f7f8d46, - 0x5f3c7f6b, 0x5ef936d1, - 0x5eb5b3a2, 0x5e71f606, 0x5e2dfe29, 0x5de9cc33, 0x5da5604f, 0x5d60baa7, - 0x5d1bdb65, 0x5cd6c2b5, - 0x5c9170bf, 0x5c4be5b0, 0x5c0621b2, 0x5bc024f0, 0x5b79ef96, 0x5b3381ce, - 0x5aecdbc5, 0x5aa5fda5, - 0x5a5ee79a, 0x5a1799d1, 0x59d01475, 0x598857b2, 0x594063b5, 0x58f838a9, - 0x58afd6bd, 0x58673e1b, - 0x581e6ef1, 0x57d5696d, 0x578c2dba, 0x5742bc06, 0x56f9147e, 0x56af3750, - 0x566524aa, 0x561adcb9, - 0x55d05faa, 0x5585adad, 0x553ac6ee, 0x54efab9c, 0x54a45be6, 0x5458d7f9, - 0x540d2005, 0x53c13439, - 0x537514c2, 0x5328c1d0, 0x52dc3b92, 0x528f8238, 0x524295f0, 0x51f576ea, - 0x51a82555, 0x515aa162, - 0x510ceb40, 0x50bf031f, 0x5070e92f, 0x50229da1, 0x4fd420a4, 0x4f857269, - 0x4f369320, 0x4ee782fb, - 0x4e984229, 0x4e48d0dd, 0x4df92f46, 0x4da95d96, 0x4d595bfe, 0x4d092ab0, - 0x4cb8c9dd, 0x4c6839b7, - 0x4c177a6e, 0x4bc68c36, 0x4b756f40, 0x4b2423be, 0x4ad2a9e2, 0x4a8101de, - 0x4a2f2be6, 0x49dd282a, - 0x498af6df, 0x49389836, 0x48e60c62, 0x48935397, 0x48406e08, 0x47ed5be6, - 0x479a1d67, 0x4746b2bc, - 0x46f31c1a, 0x469f59b4, 0x464b6bbe, 0x45f7526b, 0x45a30df0, 0x454e9e80, - 0x44fa0450, 0x44a53f93, - 0x4450507e, 0x43fb3746, 0x43a5f41e, 0x4350873c, 0x42faf0d4, 0x42a5311b, - 0x424f4845, 0x41f93689, - 0x41a2fc1a, 0x414c992f, 0x40f60dfb, 0x409f5ab6, 0x40487f94, 0x3ff17cca, - 0x3f9a5290, 0x3f430119, - 0x3eeb889c, 0x3e93e950, 0x3e3c2369, 0x3de4371f, 0x3d8c24a8, 0x3d33ec39, - 0x3cdb8e09, 0x3c830a50, - 0x3c2a6142, 0x3bd19318, 0x3b78a007, 0x3b1f8848, 0x3ac64c0f, 0x3a6ceb96, - 0x3a136712, 0x39b9bebc, - 0x395ff2c9, 0x39060373, 0x38abf0ef, 0x3851bb77, 0x37f76341, 0x379ce885, - 0x37424b7b, 0x36e78c5b, - 0x368cab5c, 0x3631a8b8, 0x35d684a6, 0x357b3f5d, 0x351fd918, 0x34c4520d, - 0x3468aa76, 0x340ce28b, - 0x33b0fa84, 0x3354f29b, 0x32f8cb07, 0x329c8402, 0x32401dc6, 0x31e39889, - 0x3186f487, 0x312a31f8, - 0x30cd5115, 0x30705217, 0x30133539, 0x2fb5fab2, 0x2f58a2be, 0x2efb2d95, - 0x2e9d9b70, 0x2e3fec8b, - 0x2de2211e, 0x2d843964, 0x2d263596, 0x2cc815ee, 0x2c69daa6, 0x2c0b83fa, - 0x2bad1221, 0x2b4e8558, - 0x2aefddd8, 0x2a911bdc, 0x2a323f9e, 0x29d34958, 0x29743946, 0x29150fa1, - 0x28b5cca5, 0x2856708d, - 0x27f6fb92, 0x27976df1, 0x2737c7e3, 0x26d809a5, 0x26783370, 0x26184581, - 0x25b84012, 0x2558235f, - 0x24f7efa2, 0x2497a517, 0x243743fa, 0x23d6cc87, 0x23763ef7, 0x23159b88, - 0x22b4e274, 0x225413f8, - 0x21f3304f, 0x219237b5, 0x21312a65, 0x20d0089c, 0x206ed295, 0x200d888d, - 0x1fac2abf, 0x1f4ab968, - 0x1ee934c3, 0x1e879d0d, 0x1e25f282, 0x1dc4355e, 0x1d6265dd, 0x1d00843d, - 0x1c9e90b8, 0x1c3c8b8c, - 0x1bda74f6, 0x1b784d30, 0x1b161479, 0x1ab3cb0d, 0x1a517128, 0x19ef0707, - 0x198c8ce7, 0x192a0304, - 0x18c7699b, 0x1864c0ea, 0x1802092c, 0x179f429f, 0x173c6d80, 0x16d98a0c, - 0x1676987f, 0x16139918, - 0x15b08c12, 0x154d71aa, 0x14ea4a1f, 0x148715ae, 0x1423d492, 0x13c0870a, - 0x135d2d53, 0x12f9c7aa, - 0x1296564d, 0x1232d979, 0x11cf516a, 0x116bbe60, 0x11082096, 0x10a4784b, - 0x1040c5bb, 0xfdd0926, - 0xf7942c7, 0xf1572dc, 0xeb199a4, 0xe4db75b, 0xde9cc40, 0xd85d88f, 0xd21dc87, - 0xcbdd865, - 0xc59cc68, 0xbf5b8cb, 0xb919dcf, 0xb2d7baf, 0xac952aa, 0xa6522fe, 0xa00ece8, - 0x99cb0a7, - 0x9386e78, 0x8d42699, 0x86fd947, 0x80b86c2, 0x7a72f45, 0x742d311, 0x6de7262, - 0x67a0d76, - 0x615a48b, 0x5b137df, 0x54cc7b1, 0x4e8543e, 0x483ddc3, 0x41f6480, 0x3bae8b2, - 0x3566a96, - 0x2f1ea6c, 0x28d6870, 0x228e4e2, 0x1c45ffe, 0x15fda03, 0xfb5330, 0x96cbc1, - 0x3243f5, -}; - -static const q31_t cos_factorsQ31_2048[2048] = { - 0x7fffff62, 0x7ffffa73, 0x7ffff094, 0x7fffe1c6, 0x7fffce09, 0x7fffb55c, - 0x7fff97c1, 0x7fff7536, - 0x7fff4dbb, 0x7fff2151, 0x7ffeeff8, 0x7ffeb9b0, 0x7ffe7e79, 0x7ffe3e52, - 0x7ffdf93c, 0x7ffdaf37, - 0x7ffd6042, 0x7ffd0c5f, 0x7ffcb38c, 0x7ffc55ca, 0x7ffbf319, 0x7ffb8b78, - 0x7ffb1ee9, 0x7ffaad6a, - 0x7ffa36fc, 0x7ff9bba0, 0x7ff93b54, 0x7ff8b619, 0x7ff82bef, 0x7ff79cd6, - 0x7ff708ce, 0x7ff66fd7, - 0x7ff5d1f1, 0x7ff52f1d, 0x7ff48759, 0x7ff3daa6, 0x7ff32905, 0x7ff27275, - 0x7ff1b6f6, 0x7ff0f688, - 0x7ff0312c, 0x7fef66e1, 0x7fee97a7, 0x7fedc37e, 0x7fecea67, 0x7fec0c62, - 0x7feb296d, 0x7fea418b, - 0x7fe954ba, 0x7fe862fa, 0x7fe76c4c, 0x7fe670b0, 0x7fe57025, 0x7fe46aac, - 0x7fe36045, 0x7fe250ef, - 0x7fe13cac, 0x7fe0237a, 0x7fdf055a, 0x7fdde24d, 0x7fdcba51, 0x7fdb8d67, - 0x7fda5b8f, 0x7fd924ca, - 0x7fd7e917, 0x7fd6a875, 0x7fd562e7, 0x7fd4186a, 0x7fd2c900, 0x7fd174a8, - 0x7fd01b63, 0x7fcebd31, - 0x7fcd5a11, 0x7fcbf203, 0x7fca8508, 0x7fc91320, 0x7fc79c4b, 0x7fc62089, - 0x7fc49fda, 0x7fc31a3d, - 0x7fc18fb4, 0x7fc0003e, 0x7fbe6bdb, 0x7fbcd28b, 0x7fbb344e, 0x7fb99125, - 0x7fb7e90f, 0x7fb63c0d, - 0x7fb48a1e, 0x7fb2d343, 0x7fb1177b, 0x7faf56c7, 0x7fad9127, 0x7fabc69b, - 0x7fa9f723, 0x7fa822bf, - 0x7fa6496e, 0x7fa46b32, 0x7fa2880b, 0x7fa09ff7, 0x7f9eb2f8, 0x7f9cc10d, - 0x7f9aca37, 0x7f98ce76, - 0x7f96cdc9, 0x7f94c831, 0x7f92bdad, 0x7f90ae3f, 0x7f8e99e6, 0x7f8c80a1, - 0x7f8a6272, 0x7f883f58, - 0x7f861753, 0x7f83ea64, 0x7f81b88a, 0x7f7f81c6, 0x7f7d4617, 0x7f7b057e, - 0x7f78bffb, 0x7f76758e, - 0x7f742637, 0x7f71d1f6, 0x7f6f78cb, 0x7f6d1ab6, 0x7f6ab7b8, 0x7f684fd0, - 0x7f65e2ff, 0x7f637144, - 0x7f60faa0, 0x7f5e7f13, 0x7f5bfe9d, 0x7f59793e, 0x7f56eef5, 0x7f545fc5, - 0x7f51cbab, 0x7f4f32a9, - 0x7f4c94be, 0x7f49f1eb, 0x7f474a30, 0x7f449d8c, 0x7f41ec01, 0x7f3f358d, - 0x7f3c7a31, 0x7f39b9ee, - 0x7f36f4c3, 0x7f342ab1, 0x7f315bb7, 0x7f2e87d6, 0x7f2baf0d, 0x7f28d15d, - 0x7f25eec7, 0x7f230749, - 0x7f201ae5, 0x7f1d299a, 0x7f1a3368, 0x7f173850, 0x7f143852, 0x7f11336d, - 0x7f0e29a3, 0x7f0b1af2, - 0x7f08075c, 0x7f04eedf, 0x7f01d17d, 0x7efeaf36, 0x7efb8809, 0x7ef85bf7, - 0x7ef52b00, 0x7ef1f524, - 0x7eeeba62, 0x7eeb7abc, 0x7ee83632, 0x7ee4ecc3, 0x7ee19e6f, 0x7ede4b38, - 0x7edaf31c, 0x7ed7961c, - 0x7ed43438, 0x7ed0cd70, 0x7ecd61c5, 0x7ec9f137, 0x7ec67bc5, 0x7ec3016f, - 0x7ebf8237, 0x7ebbfe1c, - 0x7eb8751e, 0x7eb4e73d, 0x7eb1547a, 0x7eadbcd4, 0x7eaa204c, 0x7ea67ee2, - 0x7ea2d896, 0x7e9f2d68, - 0x7e9b7d58, 0x7e97c867, 0x7e940e94, 0x7e904fe0, 0x7e8c8c4b, 0x7e88c3d5, - 0x7e84f67e, 0x7e812447, - 0x7e7d4d2f, 0x7e797136, 0x7e75905d, 0x7e71aaa4, 0x7e6dc00c, 0x7e69d093, - 0x7e65dc3b, 0x7e61e303, - 0x7e5de4ec, 0x7e59e1f5, 0x7e55da20, 0x7e51cd6c, 0x7e4dbbd9, 0x7e49a567, - 0x7e458a17, 0x7e4169e9, - 0x7e3d44dd, 0x7e391af3, 0x7e34ec2b, 0x7e30b885, 0x7e2c8002, 0x7e2842a2, - 0x7e240064, 0x7e1fb94a, - 0x7e1b6d53, 0x7e171c7f, 0x7e12c6ce, 0x7e0e6c42, 0x7e0a0cd9, 0x7e05a894, - 0x7e013f74, 0x7dfcd178, - 0x7df85ea0, 0x7df3e6ee, 0x7def6a60, 0x7deae8f7, 0x7de662b3, 0x7de1d795, - 0x7ddd479d, 0x7dd8b2ca, - 0x7dd4191d, 0x7dcf7a96, 0x7dcad736, 0x7dc62efc, 0x7dc181e8, 0x7dbccffc, - 0x7db81936, 0x7db35d98, - 0x7dae9d21, 0x7da9d7d2, 0x7da50dab, 0x7da03eab, 0x7d9b6ad3, 0x7d969224, - 0x7d91b49e, 0x7d8cd240, - 0x7d87eb0a, 0x7d82fefe, 0x7d7e0e1c, 0x7d791862, 0x7d741dd2, 0x7d6f1e6c, - 0x7d6a1a31, 0x7d65111f, - 0x7d600338, 0x7d5af07b, 0x7d55d8e9, 0x7d50bc82, 0x7d4b9b46, 0x7d467536, - 0x7d414a51, 0x7d3c1a98, - 0x7d36e60b, 0x7d31acaa, 0x7d2c6e76, 0x7d272b6e, 0x7d21e393, 0x7d1c96e5, - 0x7d174564, 0x7d11ef11, - 0x7d0c93eb, 0x7d0733f3, 0x7d01cf29, 0x7cfc658d, 0x7cf6f720, 0x7cf183e1, - 0x7cec0bd1, 0x7ce68ef0, - 0x7ce10d3f, 0x7cdb86bd, 0x7cd5fb6a, 0x7cd06b48, 0x7ccad656, 0x7cc53c94, - 0x7cbf9e03, 0x7cb9faa2, - 0x7cb45272, 0x7caea574, 0x7ca8f3a7, 0x7ca33d0c, 0x7c9d81a3, 0x7c97c16b, - 0x7c91fc66, 0x7c8c3294, - 0x7c8663f4, 0x7c809088, 0x7c7ab84e, 0x7c74db48, 0x7c6ef976, 0x7c6912d7, - 0x7c63276d, 0x7c5d3737, - 0x7c574236, 0x7c514869, 0x7c4b49d2, 0x7c45466f, 0x7c3f3e42, 0x7c39314b, - 0x7c331f8a, 0x7c2d08ff, - 0x7c26edab, 0x7c20cd8d, 0x7c1aa8a6, 0x7c147ef6, 0x7c0e507e, 0x7c081d3d, - 0x7c01e534, 0x7bfba863, - 0x7bf566cb, 0x7bef206b, 0x7be8d544, 0x7be28556, 0x7bdc30a1, 0x7bd5d726, - 0x7bcf78e5, 0x7bc915dd, - 0x7bc2ae10, 0x7bbc417e, 0x7bb5d026, 0x7baf5a09, 0x7ba8df28, 0x7ba25f82, - 0x7b9bdb18, 0x7b9551ea, - 0x7b8ec3f8, 0x7b883143, 0x7b8199ca, 0x7b7afd8f, 0x7b745c91, 0x7b6db6d0, - 0x7b670c4d, 0x7b605d09, - 0x7b59a902, 0x7b52f03a, 0x7b4c32b1, 0x7b457068, 0x7b3ea95d, 0x7b37dd92, - 0x7b310d07, 0x7b2a37bc, - 0x7b235db2, 0x7b1c7ee8, 0x7b159b5f, 0x7b0eb318, 0x7b07c612, 0x7b00d44d, - 0x7af9ddcb, 0x7af2e28b, - 0x7aebe28d, 0x7ae4ddd2, 0x7addd45b, 0x7ad6c626, 0x7acfb336, 0x7ac89b89, - 0x7ac17f20, 0x7aba5dfc, - 0x7ab3381d, 0x7aac0d82, 0x7aa4de2d, 0x7a9daa1d, 0x7a967153, 0x7a8f33d0, - 0x7a87f192, 0x7a80aa9c, - 0x7a795eec, 0x7a720e84, 0x7a6ab963, 0x7a635f8a, 0x7a5c00f9, 0x7a549db0, - 0x7a4d35b0, 0x7a45c8f9, - 0x7a3e578b, 0x7a36e166, 0x7a2f668c, 0x7a27e6fb, 0x7a2062b5, 0x7a18d9b9, - 0x7a114c09, 0x7a09b9a4, - 0x7a02228a, 0x79fa86bc, 0x79f2e63a, 0x79eb4105, 0x79e3971c, 0x79dbe880, - 0x79d43532, 0x79cc7d31, - 0x79c4c07e, 0x79bcff19, 0x79b53903, 0x79ad6e3c, 0x79a59ec3, 0x799dca9a, - 0x7995f1c1, 0x798e1438, - 0x798631ff, 0x797e4b16, 0x79765f7f, 0x796e6f39, 0x79667a44, 0x795e80a1, - 0x79568250, 0x794e7f52, - 0x794677a6, 0x793e6b4e, 0x79365a49, 0x792e4497, 0x79262a3a, 0x791e0b31, - 0x7915e77c, 0x790dbf1d, - 0x79059212, 0x78fd605d, 0x78f529fe, 0x78eceef6, 0x78e4af44, 0x78dc6ae8, - 0x78d421e4, 0x78cbd437, - 0x78c381e2, 0x78bb2ae5, 0x78b2cf41, 0x78aa6ef5, 0x78a20a03, 0x7899a06a, - 0x7891322a, 0x7888bf45, - 0x788047ba, 0x7877cb89, 0x786f4ab4, 0x7866c53a, 0x785e3b1c, 0x7855ac5a, - 0x784d18f4, 0x784480ea, - 0x783be43e, 0x783342ef, 0x782a9cfe, 0x7821f26b, 0x78194336, 0x78108f60, - 0x7807d6e9, 0x77ff19d1, - 0x77f65819, 0x77ed91c0, 0x77e4c6c9, 0x77dbf732, 0x77d322fc, 0x77ca4a27, - 0x77c16cb4, 0x77b88aa3, - 0x77afa3f5, 0x77a6b8a9, 0x779dc8c0, 0x7794d43b, 0x778bdb19, 0x7782dd5c, - 0x7779db03, 0x7770d40f, - 0x7767c880, 0x775eb857, 0x7755a394, 0x774c8a36, 0x77436c40, 0x773a49b0, - 0x77312287, 0x7727f6c6, - 0x771ec66e, 0x7715917d, 0x770c57f5, 0x770319d6, 0x76f9d721, 0x76f08fd5, - 0x76e743f4, 0x76ddf37c, - 0x76d49e70, 0x76cb44cf, 0x76c1e699, 0x76b883d0, 0x76af1c72, 0x76a5b082, - 0x769c3ffe, 0x7692cae8, - 0x7689513f, 0x767fd304, 0x76765038, 0x766cc8db, 0x76633ced, 0x7659ac6f, - 0x76501760, 0x76467dc2, - 0x763cdf94, 0x76333cd8, 0x7629958c, 0x761fe9b3, 0x7616394c, 0x760c8457, - 0x7602cad5, 0x75f90cc7, - 0x75ef4a2c, 0x75e58305, 0x75dbb753, 0x75d1e715, 0x75c8124d, 0x75be38fa, - 0x75b45b1d, 0x75aa78b6, - 0x75a091c6, 0x7596a64d, 0x758cb64c, 0x7582c1c2, 0x7578c8b0, 0x756ecb18, - 0x7564c8f8, 0x755ac251, - 0x7550b725, 0x7546a772, 0x753c933a, 0x75327a7d, 0x75285d3b, 0x751e3b75, - 0x7514152b, 0x7509ea5d, - 0x74ffbb0d, 0x74f58739, 0x74eb4ee3, 0x74e1120c, 0x74d6d0b2, 0x74cc8ad8, - 0x74c2407d, 0x74b7f1a1, - 0x74ad9e46, 0x74a3466b, 0x7498ea11, 0x748e8938, 0x748423e0, 0x7479ba0b, - 0x746f4bb8, 0x7464d8e8, - 0x745a619b, 0x744fe5d2, 0x7445658d, 0x743ae0cc, 0x74305790, 0x7425c9da, - 0x741b37a9, 0x7410a0fe, - 0x740605d9, 0x73fb663c, 0x73f0c226, 0x73e61997, 0x73db6c91, 0x73d0bb13, - 0x73c6051f, 0x73bb4ab3, - 0x73b08bd1, 0x73a5c87a, 0x739b00ad, 0x7390346b, 0x738563b5, 0x737a8e8a, - 0x736fb4ec, 0x7364d6da, - 0x7359f456, 0x734f0d5f, 0x734421f6, 0x7339321b, 0x732e3dcf, 0x73234512, - 0x731847e5, 0x730d4648, - 0x7302403c, 0x72f735c0, 0x72ec26d6, 0x72e1137d, 0x72d5fbb7, 0x72cadf83, - 0x72bfbee3, 0x72b499d6, - 0x72a9705c, 0x729e4277, 0x72931027, 0x7287d96c, 0x727c9e47, 0x72715eb8, - 0x72661abf, 0x725ad25d, - 0x724f8593, 0x72443460, 0x7238dec5, 0x722d84c4, 0x7222265b, 0x7216c38c, - 0x720b5c57, 0x71fff0bc, - 0x71f480bc, 0x71e90c57, 0x71dd938f, 0x71d21662, 0x71c694d2, 0x71bb0edf, - 0x71af848a, 0x71a3f5d2, - 0x719862b9, 0x718ccb3f, 0x71812f65, 0x71758f29, 0x7169ea8f, 0x715e4194, - 0x7152943b, 0x7146e284, - 0x713b2c6e, 0x712f71fb, 0x7123b32b, 0x7117effe, 0x710c2875, 0x71005c90, - 0x70f48c50, 0x70e8b7b5, - 0x70dcdec0, 0x70d10171, 0x70c51fc8, 0x70b939c7, 0x70ad4f6d, 0x70a160ba, - 0x70956db1, 0x70897650, - 0x707d7a98, 0x70717a8a, 0x70657626, 0x70596d6d, 0x704d6060, 0x70414efd, - 0x70353947, 0x70291f3e, - 0x701d00e1, 0x7010de32, 0x7004b731, 0x6ff88bde, 0x6fec5c3b, 0x6fe02846, - 0x6fd3f001, 0x6fc7b36d, - 0x6fbb728a, 0x6faf2d57, 0x6fa2e3d7, 0x6f969608, 0x6f8a43ed, 0x6f7ded84, - 0x6f7192cf, 0x6f6533ce, - 0x6f58d082, 0x6f4c68eb, 0x6f3ffd09, 0x6f338cde, 0x6f271868, 0x6f1a9faa, - 0x6f0e22a3, 0x6f01a155, - 0x6ef51bbe, 0x6ee891e1, 0x6edc03bc, 0x6ecf7152, 0x6ec2daa2, 0x6eb63fad, - 0x6ea9a073, 0x6e9cfcf5, - 0x6e905534, 0x6e83a92f, 0x6e76f8e7, 0x6e6a445d, 0x6e5d8b91, 0x6e50ce84, - 0x6e440d37, 0x6e3747a9, - 0x6e2a7ddb, 0x6e1dafce, 0x6e10dd82, 0x6e0406f8, 0x6df72c30, 0x6dea4d2b, - 0x6ddd69e9, 0x6dd0826a, - 0x6dc396b0, 0x6db6a6ba, 0x6da9b28a, 0x6d9cba1f, 0x6d8fbd7a, 0x6d82bc9d, - 0x6d75b786, 0x6d68ae37, - 0x6d5ba0b0, 0x6d4e8ef2, 0x6d4178fd, 0x6d345ed1, 0x6d274070, 0x6d1a1dda, - 0x6d0cf70f, 0x6cffcc0f, - 0x6cf29cdc, 0x6ce56975, 0x6cd831dc, 0x6ccaf610, 0x6cbdb613, 0x6cb071e4, - 0x6ca32985, 0x6c95dcf6, - 0x6c888c36, 0x6c7b3748, 0x6c6dde2b, 0x6c6080e0, 0x6c531f67, 0x6c45b9c1, - 0x6c384fef, 0x6c2ae1f0, - 0x6c1d6fc6, 0x6c0ff971, 0x6c027ef1, 0x6bf50047, 0x6be77d74, 0x6bd9f677, - 0x6bcc6b53, 0x6bbedc06, - 0x6bb14892, 0x6ba3b0f7, 0x6b961536, 0x6b88754f, 0x6b7ad142, 0x6b6d2911, - 0x6b5f7cbc, 0x6b51cc42, - 0x6b4417a6, 0x6b365ee7, 0x6b28a206, 0x6b1ae103, 0x6b0d1bdf, 0x6aff529a, - 0x6af18536, 0x6ae3b3b2, - 0x6ad5de0f, 0x6ac8044e, 0x6aba266e, 0x6aac4472, 0x6a9e5e58, 0x6a907423, - 0x6a8285d1, 0x6a749365, - 0x6a669cdd, 0x6a58a23c, 0x6a4aa381, 0x6a3ca0ad, 0x6a2e99c0, 0x6a208ebb, - 0x6a127f9f, 0x6a046c6c, - 0x69f65523, 0x69e839c4, 0x69da1a50, 0x69cbf6c7, 0x69bdcf29, 0x69afa378, - 0x69a173b5, 0x69933fde, - 0x698507f6, 0x6976cbfc, 0x69688bf1, 0x695a47d6, 0x694bffab, 0x693db371, - 0x692f6328, 0x69210ed1, - 0x6912b66c, 0x690459fb, 0x68f5f97d, 0x68e794f3, 0x68d92c5d, 0x68cabfbd, - 0x68bc4f13, 0x68adda5f, - 0x689f61a1, 0x6890e4dc, 0x6882640e, 0x6873df38, 0x6865565c, 0x6856c979, - 0x68483891, 0x6839a3a4, - 0x682b0ab1, 0x681c6dbb, 0x680dccc1, 0x67ff27c4, 0x67f07ec5, 0x67e1d1c4, - 0x67d320c1, 0x67c46bbe, - 0x67b5b2bb, 0x67a6f5b8, 0x679834b6, 0x67896fb6, 0x677aa6b8, 0x676bd9bd, - 0x675d08c4, 0x674e33d0, - 0x673f5ae0, 0x67307df5, 0x67219d10, 0x6712b831, 0x6703cf58, 0x66f4e287, - 0x66e5f1be, 0x66d6fcfd, - 0x66c80445, 0x66b90797, 0x66aa06f3, 0x669b0259, 0x668bf9cb, 0x667ced49, - 0x666ddcd3, 0x665ec86b, - 0x664fb010, 0x664093c3, 0x66317385, 0x66224f56, 0x66132738, 0x6603fb2a, - 0x65f4cb2d, 0x65e59742, - 0x65d65f69, 0x65c723a3, 0x65b7e3f1, 0x65a8a052, 0x659958c9, 0x658a0d54, - 0x657abdf6, 0x656b6aae, - 0x655c137d, 0x654cb863, 0x653d5962, 0x652df679, 0x651e8faa, 0x650f24f5, - 0x64ffb65b, 0x64f043dc, - 0x64e0cd78, 0x64d15331, 0x64c1d507, 0x64b252fa, 0x64a2cd0c, 0x6493433c, - 0x6483b58c, 0x647423fb, - 0x64648e8c, 0x6454f53d, 0x64455810, 0x6435b706, 0x6426121e, 0x6416695a, - 0x6406bcba, 0x63f70c3f, - 0x63e757ea, 0x63d79fba, 0x63c7e3b1, 0x63b823cf, 0x63a86015, 0x63989884, - 0x6388cd1b, 0x6378fddc, - 0x63692ac7, 0x635953dd, 0x6349791f, 0x63399a8d, 0x6329b827, 0x6319d1ef, - 0x6309e7e4, 0x62f9fa09, - 0x62ea085c, 0x62da12df, 0x62ca1992, 0x62ba1c77, 0x62aa1b8d, 0x629a16d5, - 0x628a0e50, 0x627a01fe, - 0x6269f1e1, 0x6259ddf8, 0x6249c645, 0x6239aac7, 0x62298b81, 0x62196871, - 0x62094199, 0x61f916f9, - 0x61e8e893, 0x61d8b666, 0x61c88074, 0x61b846bc, 0x61a80940, 0x6197c800, - 0x618782fd, 0x61773a37, - 0x6166edb0, 0x61569d67, 0x6146495d, 0x6135f193, 0x6125960a, 0x611536c2, - 0x6104d3bc, 0x60f46cf9, - 0x60e40278, 0x60d3943b, 0x60c32243, 0x60b2ac8f, 0x60a23322, 0x6091b5fa, - 0x60813519, 0x6070b080, - 0x6060282f, 0x604f9c27, 0x603f0c69, 0x602e78f4, 0x601de1ca, 0x600d46ec, - 0x5ffca859, 0x5fec0613, - 0x5fdb601b, 0x5fcab670, 0x5fba0914, 0x5fa95807, 0x5f98a34a, 0x5f87eade, - 0x5f772ec2, 0x5f666ef9, - 0x5f55ab82, 0x5f44e45e, 0x5f34198e, 0x5f234b12, 0x5f1278eb, 0x5f01a31a, - 0x5ef0c99f, 0x5edfec7b, - 0x5ecf0baf, 0x5ebe273b, 0x5ead3f1f, 0x5e9c535e, 0x5e8b63f7, 0x5e7a70ea, - 0x5e697a39, 0x5e587fe5, - 0x5e4781ed, 0x5e368053, 0x5e257b17, 0x5e147239, 0x5e0365bb, 0x5df2559e, - 0x5de141e1, 0x5dd02a85, - 0x5dbf0f8c, 0x5dadf0f5, 0x5d9ccec2, 0x5d8ba8f3, 0x5d7a7f88, 0x5d695283, - 0x5d5821e4, 0x5d46edac, - 0x5d35b5db, 0x5d247a72, 0x5d133b72, 0x5d01f8dc, 0x5cf0b2af, 0x5cdf68ed, - 0x5cce1b97, 0x5cbccaac, - 0x5cab762f, 0x5c9a1e1e, 0x5c88c27c, 0x5c776348, 0x5c660084, 0x5c549a30, - 0x5c43304d, 0x5c31c2db, - 0x5c2051db, 0x5c0edd4e, 0x5bfd6534, 0x5bebe98e, 0x5bda6a5d, 0x5bc8e7a2, - 0x5bb7615d, 0x5ba5d78e, - 0x5b944a37, 0x5b82b958, 0x5b7124f2, 0x5b5f8d06, 0x5b4df193, 0x5b3c529c, - 0x5b2ab020, 0x5b190a20, - 0x5b07609d, 0x5af5b398, 0x5ae40311, 0x5ad24f09, 0x5ac09781, 0x5aaedc78, - 0x5a9d1df1, 0x5a8b5bec, - 0x5a799669, 0x5a67cd69, 0x5a5600ec, 0x5a4430f5, 0x5a325d82, 0x5a208695, - 0x5a0eac2e, 0x59fcce4f, - 0x59eaecf8, 0x59d90829, 0x59c71fe3, 0x59b53427, 0x59a344f6, 0x59915250, - 0x597f5c36, 0x596d62a9, - 0x595b65aa, 0x59496538, 0x59376155, 0x59255a02, 0x59134f3e, 0x5901410c, - 0x58ef2f6b, 0x58dd1a5d, - 0x58cb01e1, 0x58b8e5f9, 0x58a6c6a5, 0x5894a3e7, 0x58827dbe, 0x5870542c, - 0x585e2730, 0x584bf6cd, - 0x5839c302, 0x58278bd1, 0x58155139, 0x5803133c, 0x57f0d1da, 0x57de8d15, - 0x57cc44ec, 0x57b9f960, - 0x57a7aa73, 0x57955825, 0x57830276, 0x5770a968, 0x575e4cfa, 0x574bed2f, - 0x57398a05, 0x5727237f, - 0x5714b99d, 0x57024c5f, 0x56efdbc7, 0x56dd67d4, 0x56caf088, 0x56b875e4, - 0x56a5f7e7, 0x56937694, - 0x5680f1ea, 0x566e69ea, 0x565bde95, 0x56494fec, 0x5636bdef, 0x5624289f, - 0x56118ffe, 0x55fef40a, - 0x55ec54c6, 0x55d9b232, 0x55c70c4f, 0x55b4631d, 0x55a1b69d, 0x558f06d0, - 0x557c53b6, 0x55699d51, - 0x5556e3a1, 0x554426a7, 0x55316663, 0x551ea2d6, 0x550bdc01, 0x54f911e5, - 0x54e64482, 0x54d373d9, - 0x54c09feb, 0x54adc8b8, 0x549aee42, 0x54881089, 0x54752f8d, 0x54624b50, - 0x544f63d2, 0x543c7914, - 0x54298b17, 0x541699db, 0x5403a561, 0x53f0adaa, 0x53ddb2b6, 0x53cab486, - 0x53b7b31c, 0x53a4ae77, - 0x5391a699, 0x537e9b82, 0x536b8d33, 0x53587bad, 0x534566f0, 0x53324efd, - 0x531f33d5, 0x530c1579, - 0x52f8f3e9, 0x52e5cf27, 0x52d2a732, 0x52bf7c0b, 0x52ac4db4, 0x52991c2d, - 0x5285e777, 0x5272af92, - 0x525f7480, 0x524c3640, 0x5238f4d4, 0x5225b03d, 0x5212687b, 0x51ff1d8f, - 0x51ebcf7a, 0x51d87e3c, - 0x51c529d7, 0x51b1d24a, 0x519e7797, 0x518b19bf, 0x5177b8c2, 0x516454a0, - 0x5150ed5c, 0x513d82f4, - 0x512a156b, 0x5116a4c1, 0x510330f7, 0x50efba0d, 0x50dc4005, 0x50c8c2de, - 0x50b5429a, 0x50a1bf39, - 0x508e38bd, 0x507aaf25, 0x50672273, 0x505392a8, 0x503fffc4, 0x502c69c8, - 0x5018d0b4, 0x5005348a, - 0x4ff1954b, 0x4fddf2f6, 0x4fca4d8d, 0x4fb6a510, 0x4fa2f981, 0x4f8f4ae0, - 0x4f7b992d, 0x4f67e46a, - 0x4f542c98, 0x4f4071b6, 0x4f2cb3c7, 0x4f18f2c9, 0x4f052ec0, 0x4ef167aa, - 0x4edd9d89, 0x4ec9d05e, - 0x4eb60029, 0x4ea22ceb, 0x4e8e56a5, 0x4e7a7d58, 0x4e66a105, 0x4e52c1ab, - 0x4e3edf4d, 0x4e2af9ea, - 0x4e171184, 0x4e03261b, 0x4def37b0, 0x4ddb4644, 0x4dc751d8, 0x4db35a6c, - 0x4d9f6001, 0x4d8b6298, - 0x4d776231, 0x4d635ece, 0x4d4f5870, 0x4d3b4f16, 0x4d2742c2, 0x4d133374, - 0x4cff212e, 0x4ceb0bf0, - 0x4cd6f3bb, 0x4cc2d88f, 0x4caeba6e, 0x4c9a9958, 0x4c86754e, 0x4c724e50, - 0x4c5e2460, 0x4c49f77f, - 0x4c35c7ac, 0x4c2194e9, 0x4c0d5f37, 0x4bf92697, 0x4be4eb08, 0x4bd0ac8d, - 0x4bbc6b25, 0x4ba826d1, - 0x4b93df93, 0x4b7f956b, 0x4b6b485a, 0x4b56f861, 0x4b42a580, 0x4b2e4fb8, - 0x4b19f70a, 0x4b059b77, - 0x4af13d00, 0x4adcdba5, 0x4ac87767, 0x4ab41046, 0x4a9fa645, 0x4a8b3963, - 0x4a76c9a2, 0x4a625701, - 0x4a4de182, 0x4a396926, 0x4a24edee, 0x4a106fda, 0x49fbeeea, 0x49e76b21, - 0x49d2e47e, 0x49be5b02, - 0x49a9ceaf, 0x49953f84, 0x4980ad84, 0x496c18ae, 0x49578103, 0x4942e684, - 0x492e4933, 0x4919a90f, - 0x4905061a, 0x48f06054, 0x48dbb7be, 0x48c70c59, 0x48b25e25, 0x489dad25, - 0x4888f957, 0x487442be, - 0x485f8959, 0x484acd2a, 0x48360e32, 0x48214c71, 0x480c87e8, 0x47f7c099, - 0x47e2f682, 0x47ce29a7, - 0x47b95a06, 0x47a487a2, 0x478fb27b, 0x477ada91, 0x4765ffe6, 0x4751227a, - 0x473c424e, 0x47275f63, - 0x471279ba, 0x46fd9154, 0x46e8a631, 0x46d3b852, 0x46bec7b8, 0x46a9d464, - 0x4694de56, 0x467fe590, - 0x466aea12, 0x4655ebdd, 0x4640eaf2, 0x462be751, 0x4616e0fc, 0x4601d7f3, - 0x45eccc37, 0x45d7bdc9, - 0x45c2acaa, 0x45ad98da, 0x4598825a, 0x4583692c, 0x456e4d4f, 0x45592ec6, - 0x45440d90, 0x452ee9ae, - 0x4519c321, 0x450499eb, 0x44ef6e0b, 0x44da3f83, 0x44c50e53, 0x44afda7d, - 0x449aa400, 0x44856adf, - 0x44702f19, 0x445af0b0, 0x4445afa4, 0x44306bf6, 0x441b25a8, 0x4405dcb9, - 0x43f0912b, 0x43db42fe, - 0x43c5f234, 0x43b09ecc, 0x439b48c9, 0x4385f02a, 0x437094f1, 0x435b371f, - 0x4345d6b3, 0x433073b0, - 0x431b0e15, 0x4305a5e5, 0x42f03b1e, 0x42dacdc3, 0x42c55dd4, 0x42afeb53, - 0x429a763f, 0x4284fe99, - 0x426f8463, 0x425a079e, 0x42448849, 0x422f0667, 0x421981f7, 0x4203fafb, - 0x41ee7174, 0x41d8e561, - 0x41c356c5, 0x41adc5a0, 0x419831f3, 0x41829bbe, 0x416d0302, 0x415767c1, - 0x4141c9fb, 0x412c29b1, - 0x411686e4, 0x4100e194, 0x40eb39c3, 0x40d58f71, 0x40bfe29f, 0x40aa334e, - 0x4094817f, 0x407ecd32, - 0x40691669, 0x40535d24, 0x403da165, 0x4027e32b, 0x40122278, 0x3ffc5f4d, - 0x3fe699aa, 0x3fd0d191, - 0x3fbb0702, 0x3fa539fd, 0x3f8f6a85, 0x3f799899, 0x3f63c43b, 0x3f4ded6b, - 0x3f38142a, 0x3f22387a, - 0x3f0c5a5a, 0x3ef679cc, 0x3ee096d1, 0x3ecab169, 0x3eb4c995, 0x3e9edf57, - 0x3e88f2ae, 0x3e73039d, - 0x3e5d1222, 0x3e471e41, 0x3e3127f9, 0x3e1b2f4a, 0x3e053437, 0x3def36c0, - 0x3dd936e6, 0x3dc334a9, - 0x3dad300b, 0x3d97290b, 0x3d811fac, 0x3d6b13ee, 0x3d5505d2, 0x3d3ef559, - 0x3d28e282, 0x3d12cd51, - 0x3cfcb5c4, 0x3ce69bde, 0x3cd07f9f, 0x3cba6107, 0x3ca44018, 0x3c8e1cd3, - 0x3c77f737, 0x3c61cf48, - 0x3c4ba504, 0x3c35786d, 0x3c1f4983, 0x3c091849, 0x3bf2e4be, 0x3bdcaee3, - 0x3bc676b9, 0x3bb03c42, - 0x3b99ff7d, 0x3b83c06c, 0x3b6d7f10, 0x3b573b69, 0x3b40f579, 0x3b2aad3f, - 0x3b1462be, 0x3afe15f6, - 0x3ae7c6e7, 0x3ad17593, 0x3abb21fb, 0x3aa4cc1e, 0x3a8e7400, 0x3a78199f, - 0x3a61bcfd, 0x3a4b5e1b, - 0x3a34fcf9, 0x3a1e9999, 0x3a0833fc, 0x39f1cc21, 0x39db620b, 0x39c4f5ba, - 0x39ae872f, 0x3998166a, - 0x3981a36d, 0x396b2e38, 0x3954b6cd, 0x393e3d2c, 0x3927c155, 0x3911434b, - 0x38fac30e, 0x38e4409e, - 0x38cdbbfc, 0x38b7352a, 0x38a0ac29, 0x388a20f8, 0x38739399, 0x385d040d, - 0x38467255, 0x382fde72, - 0x38194864, 0x3802b02c, 0x37ec15cb, 0x37d57943, 0x37beda93, 0x37a839be, - 0x379196c3, 0x377af1a3, - 0x37644a60, 0x374da0fa, 0x3736f573, 0x372047ca, 0x37099802, 0x36f2e61a, - 0x36dc3214, 0x36c57bf0, - 0x36aec3b0, 0x36980954, 0x36814cde, 0x366a8e4d, 0x3653cda3, 0x363d0ae2, - 0x36264609, 0x360f7f19, - 0x35f8b614, 0x35e1eafa, 0x35cb1dcc, 0x35b44e8c, 0x359d7d39, 0x3586a9d5, - 0x356fd461, 0x3558fcde, - 0x3542234c, 0x352b47ad, 0x35146a00, 0x34fd8a48, 0x34e6a885, 0x34cfc4b7, - 0x34b8dee1, 0x34a1f702, - 0x348b0d1c, 0x3474212f, 0x345d333c, 0x34464345, 0x342f5149, 0x34185d4b, - 0x3401674a, 0x33ea6f48, - 0x33d37546, 0x33bc7944, 0x33a57b44, 0x338e7b46, 0x3377794b, 0x33607554, - 0x33496f62, 0x33326776, - 0x331b5d91, 0x330451b3, 0x32ed43de, 0x32d63412, 0x32bf2250, 0x32a80e99, - 0x3290f8ef, 0x3279e151, - 0x3262c7c1, 0x324bac40, 0x32348ecf, 0x321d6f6e, 0x32064e1e, 0x31ef2ae1, - 0x31d805b7, 0x31c0dea1, - 0x31a9b5a0, 0x31928ab4, 0x317b5de0, 0x31642f23, 0x314cfe7f, 0x3135cbf4, - 0x311e9783, 0x3107612e, - 0x30f028f4, 0x30d8eed8, 0x30c1b2da, 0x30aa74fa, 0x3093353a, 0x307bf39b, - 0x3064b01d, 0x304d6ac1, - 0x30362389, 0x301eda75, 0x30078f86, 0x2ff042bd, 0x2fd8f41b, 0x2fc1a3a0, - 0x2faa514f, 0x2f92fd26, - 0x2f7ba729, 0x2f644f56, 0x2f4cf5b0, 0x2f359a37, 0x2f1e3ced, 0x2f06ddd1, - 0x2eef7ce5, 0x2ed81a29, - 0x2ec0b5a0, 0x2ea94f49, 0x2e91e725, 0x2e7a7d36, 0x2e63117c, 0x2e4ba3f8, - 0x2e3434ac, 0x2e1cc397, - 0x2e0550bb, 0x2deddc19, 0x2dd665b2, 0x2dbeed86, 0x2da77397, 0x2d8ff7e5, - 0x2d787a72, 0x2d60fb3e, - 0x2d497a4a, 0x2d31f797, 0x2d1a7325, 0x2d02ecf7, 0x2ceb650d, 0x2cd3db67, - 0x2cbc5006, 0x2ca4c2ed, - 0x2c8d341a, 0x2c75a390, 0x2c5e114f, 0x2c467d58, 0x2c2ee7ad, 0x2c17504d, - 0x2bffb73a, 0x2be81c74, - 0x2bd07ffe, 0x2bb8e1d7, 0x2ba14200, 0x2b89a07b, 0x2b71fd48, 0x2b5a5868, - 0x2b42b1dd, 0x2b2b09a6, - 0x2b135fc6, 0x2afbb43c, 0x2ae4070a, 0x2acc5831, 0x2ab4a7b1, 0x2a9cf58c, - 0x2a8541c3, 0x2a6d8c55, - 0x2a55d545, 0x2a3e1c93, 0x2a266240, 0x2a0ea64d, 0x29f6e8bb, 0x29df298b, - 0x29c768be, 0x29afa654, - 0x2997e24f, 0x29801caf, 0x29685576, 0x29508ca4, 0x2938c23a, 0x2920f63a, - 0x290928a3, 0x28f15978, - 0x28d988b8, 0x28c1b666, 0x28a9e281, 0x28920d0a, 0x287a3604, 0x28625d6d, - 0x284a8349, 0x2832a796, - 0x281aca57, 0x2802eb8c, 0x27eb0b36, 0x27d32956, 0x27bb45ed, 0x27a360fc, - 0x278b7a84, 0x27739285, - 0x275ba901, 0x2743bdf9, 0x272bd16d, 0x2713e35f, 0x26fbf3ce, 0x26e402bd, - 0x26cc102d, 0x26b41c1d, - 0x269c268f, 0x26842f84, 0x266c36fe, 0x26543cfb, 0x263c417f, 0x26244489, - 0x260c461b, 0x25f44635, - 0x25dc44d9, 0x25c44207, 0x25ac3dc0, 0x25943806, 0x257c30d8, 0x25642839, - 0x254c1e28, 0x253412a8, - 0x251c05b8, 0x2503f75a, 0x24ebe78f, 0x24d3d657, 0x24bbc3b4, 0x24a3afa6, - 0x248b9a2f, 0x2473834f, - 0x245b6b07, 0x24435158, 0x242b3644, 0x241319ca, 0x23fafbec, 0x23e2dcac, - 0x23cabc09, 0x23b29a05, - 0x239a76a0, 0x238251dd, 0x236a2bba, 0x2352043b, 0x2339db5e, 0x2321b126, - 0x23098593, 0x22f158a7, - 0x22d92a61, 0x22c0fac4, 0x22a8c9cf, 0x22909785, 0x227863e5, 0x22602ef1, - 0x2247f8aa, 0x222fc111, - 0x22178826, 0x21ff4dea, 0x21e71260, 0x21ced586, 0x21b6975f, 0x219e57eb, - 0x2186172b, 0x216dd521, - 0x215591cc, 0x213d4d2f, 0x21250749, 0x210cc01d, 0x20f477aa, 0x20dc2df2, - 0x20c3e2f5, 0x20ab96b5, - 0x20934933, 0x207afa6f, 0x2062aa6b, 0x204a5927, 0x203206a4, 0x2019b2e4, - 0x20015de7, 0x1fe907ae, - 0x1fd0b03a, 0x1fb8578b, 0x1f9ffda4, 0x1f87a285, 0x1f6f462f, 0x1f56e8a2, - 0x1f3e89e0, 0x1f2629ea, - 0x1f0dc8c0, 0x1ef56664, 0x1edd02d6, 0x1ec49e17, 0x1eac3829, 0x1e93d10c, - 0x1e7b68c2, 0x1e62ff4a, - 0x1e4a94a7, 0x1e3228d9, 0x1e19bbe0, 0x1e014dbf, 0x1de8de75, 0x1dd06e04, - 0x1db7fc6d, 0x1d9f89b1, - 0x1d8715d0, 0x1d6ea0cc, 0x1d562aa6, 0x1d3db35e, 0x1d253af5, 0x1d0cc16c, - 0x1cf446c5, 0x1cdbcb00, - 0x1cc34e1f, 0x1caad021, 0x1c925109, 0x1c79d0d6, 0x1c614f8b, 0x1c48cd27, - 0x1c3049ac, 0x1c17c51b, - 0x1bff3f75, 0x1be6b8ba, 0x1bce30ec, 0x1bb5a80c, 0x1b9d1e1a, 0x1b849317, - 0x1b6c0705, 0x1b5379e5, - 0x1b3aebb6, 0x1b225c7b, 0x1b09cc34, 0x1af13ae3, 0x1ad8a887, 0x1ac01522, - 0x1aa780b6, 0x1a8eeb42, - 0x1a7654c8, 0x1a5dbd49, 0x1a4524c6, 0x1a2c8b3f, 0x1a13f0b6, 0x19fb552c, - 0x19e2b8a2, 0x19ca1b17, - 0x19b17c8f, 0x1998dd09, 0x19803c86, 0x19679b07, 0x194ef88e, 0x1936551b, - 0x191db0af, 0x19050b4b, - 0x18ec64f0, 0x18d3bda0, 0x18bb155a, 0x18a26c20, 0x1889c1f3, 0x187116d4, - 0x18586ac3, 0x183fbdc3, - 0x18270fd3, 0x180e60f4, 0x17f5b129, 0x17dd0070, 0x17c44ecd, 0x17ab9c3e, - 0x1792e8c6, 0x177a3466, - 0x17617f1d, 0x1748c8ee, 0x173011d9, 0x171759df, 0x16fea102, 0x16e5e741, - 0x16cd2c9f, 0x16b4711b, - 0x169bb4b7, 0x1682f774, 0x166a3953, 0x16517a55, 0x1638ba7a, 0x161ff9c4, - 0x16073834, 0x15ee75cb, - 0x15d5b288, 0x15bcee6f, 0x15a4297f, 0x158b63b9, 0x15729d1f, 0x1559d5b1, - 0x15410d70, 0x1528445d, - 0x150f7a7a, 0x14f6afc7, 0x14dde445, 0x14c517f4, 0x14ac4ad7, 0x14937cee, - 0x147aae3a, 0x1461debc, - 0x14490e74, 0x14303d65, 0x14176b8e, 0x13fe98f1, 0x13e5c58e, 0x13ccf167, - 0x13b41c7d, 0x139b46d0, - 0x13827062, 0x13699933, 0x1350c144, 0x1337e897, 0x131f0f2c, 0x13063505, - 0x12ed5a21, 0x12d47e83, - 0x12bba22b, 0x12a2c51b, 0x1289e752, 0x127108d2, 0x1258299c, 0x123f49b2, - 0x12266913, 0x120d87c1, - 0x11f4a5bd, 0x11dbc307, 0x11c2dfa2, 0x11a9fb8d, 0x119116c9, 0x11783159, - 0x115f4b3c, 0x11466473, - 0x112d7d00, 0x111494e4, 0x10fbac1e, 0x10e2c2b2, 0x10c9d89e, 0x10b0ede5, - 0x10980287, 0x107f1686, - 0x106629e1, 0x104d3c9b, 0x10344eb4, 0x101b602d, 0x10027107, 0xfe98143, - 0xfd090e1, 0xfb79fe4, - 0xf9eae4c, 0xf85bc19, 0xf6cc94e, 0xf53d5ea, 0xf3ae1ee, 0xf21ed5d, 0xf08f836, - 0xef0027b, - 0xed70c2c, 0xebe154b, 0xea51dd8, 0xe8c25d5, 0xe732d42, 0xe5a3421, 0xe413a72, - 0xe284036, - 0xe0f456f, 0xdf64a1c, 0xddd4e40, 0xdc451dc, 0xdab54ef, 0xd92577b, 0xd795982, - 0xd605b03, - 0xd475c00, 0xd2e5c7b, 0xd155c73, 0xcfc5bea, 0xce35ae1, 0xcca5959, 0xcb15752, - 0xc9854cf, - 0xc7f51cf, 0xc664e53, 0xc4d4a5d, 0xc3445ee, 0xc1b4107, 0xc023ba7, 0xbe935d2, - 0xbd02f87, - 0xbb728c7, 0xb9e2193, 0xb8519ed, 0xb6c11d5, 0xb53094d, 0xb3a0055, 0xb20f6ee, - 0xb07ed19, - 0xaeee2d7, 0xad5d829, 0xabccd11, 0xaa3c18e, 0xa8ab5a2, 0xa71a94f, 0xa589c94, - 0xa3f8f73, - 0xa2681ed, 0xa0d7403, 0x9f465b5, 0x9db5706, 0x9c247f5, 0x9a93884, 0x99028b3, - 0x9771884, - 0x95e07f8, 0x944f70f, 0x92be5ca, 0x912d42c, 0x8f9c233, 0x8e0afe2, 0x8c79d3a, - 0x8ae8a3a, - 0x89576e5, 0x87c633c, 0x8634f3e, 0x84a3aee, 0x831264c, 0x8181159, 0x7fefc16, - 0x7e5e685, - 0x7ccd0a5, 0x7b3ba78, 0x79aa400, 0x7818d3c, 0x768762e, 0x74f5ed7, 0x7364738, - 0x71d2f52, - 0x7041726, 0x6eafeb4, 0x6d1e5fe, 0x6b8cd05, 0x69fb3c9, 0x6869a4c, 0x66d808f, - 0x6546692, - 0x63b4c57, 0x62231de, 0x6091729, 0x5effc38, 0x5d6e10c, 0x5bdc5a7, 0x5a4aa09, - 0x58b8e34, - 0x5727228, 0x55955e6, 0x540396f, 0x5271cc4, 0x50dffe7, 0x4f4e2d8, 0x4dbc597, - 0x4c2a827, - 0x4a98a88, 0x4906cbb, 0x4774ec1, 0x45e309a, 0x4451249, 0x42bf3cd, 0x412d528, - 0x3f9b65b, - 0x3e09767, 0x3c7784d, 0x3ae590d, 0x39539a9, 0x37c1a22, 0x362fa78, 0x349daac, - 0x330bac1, - 0x3179ab5, 0x2fe7a8c, 0x2e55a44, 0x2cc39e1, 0x2b31961, 0x299f8c7, 0x280d813, - 0x267b747, - 0x24e9662, 0x2357567, 0x21c5457, 0x2033331, 0x1ea11f7, 0x1d0f0ab, 0x1b7cf4d, - 0x19eaddd, - 0x1858c5e, 0x16c6ad0, 0x1534934, 0x13a278a, 0x12105d5, 0x107e414, 0xeec249, - 0xd5a075, - 0xbc7e99, 0xa35cb5, 0x8a3acb, 0x7118dc, 0x57f6e9, 0x3ed4f2, 0x25b2f8, - 0xc90fe, - -}; - -static const q31_t cos_factorsQ31_8192[8192] = { - 0x7ffffff6, 0x7fffffa7, 0x7fffff09, 0x7ffffe1c, 0x7ffffce1, 0x7ffffb56, - 0x7ffff97c, 0x7ffff753, - 0x7ffff4dc, 0x7ffff215, 0x7fffef00, 0x7fffeb9b, 0x7fffe7e8, 0x7fffe3e5, - 0x7fffdf94, 0x7fffdaf3, - 0x7fffd604, 0x7fffd0c6, 0x7fffcb39, 0x7fffc55c, 0x7fffbf31, 0x7fffb8b7, - 0x7fffb1ee, 0x7fffaad6, - 0x7fffa36f, 0x7fff9bb9, 0x7fff93b4, 0x7fff8b61, 0x7fff82be, 0x7fff79cc, - 0x7fff708b, 0x7fff66fc, - 0x7fff5d1d, 0x7fff52ef, 0x7fff4873, 0x7fff3da8, 0x7fff328d, 0x7fff2724, - 0x7fff1b6b, 0x7fff0f64, - 0x7fff030e, 0x7ffef669, 0x7ffee975, 0x7ffedc31, 0x7ffece9f, 0x7ffec0be, - 0x7ffeb28e, 0x7ffea40f, - 0x7ffe9542, 0x7ffe8625, 0x7ffe76b9, 0x7ffe66fe, 0x7ffe56f5, 0x7ffe469c, - 0x7ffe35f4, 0x7ffe24fe, - 0x7ffe13b8, 0x7ffe0224, 0x7ffdf040, 0x7ffdde0e, 0x7ffdcb8d, 0x7ffdb8bc, - 0x7ffda59d, 0x7ffd922f, - 0x7ffd7e72, 0x7ffd6a66, 0x7ffd560b, 0x7ffd4161, 0x7ffd2c68, 0x7ffd1720, - 0x7ffd0189, 0x7ffceba4, - 0x7ffcd56f, 0x7ffcbeeb, 0x7ffca819, 0x7ffc90f7, 0x7ffc7987, 0x7ffc61c7, - 0x7ffc49b9, 0x7ffc315b, - 0x7ffc18af, 0x7ffbffb4, 0x7ffbe66a, 0x7ffbccd0, 0x7ffbb2e8, 0x7ffb98b1, - 0x7ffb7e2b, 0x7ffb6356, - 0x7ffb4833, 0x7ffb2cc0, 0x7ffb10fe, 0x7ffaf4ed, 0x7ffad88e, 0x7ffabbdf, - 0x7ffa9ee2, 0x7ffa8195, - 0x7ffa63fa, 0x7ffa460f, 0x7ffa27d6, 0x7ffa094e, 0x7ff9ea76, 0x7ff9cb50, - 0x7ff9abdb, 0x7ff98c17, - 0x7ff96c04, 0x7ff94ba2, 0x7ff92af1, 0x7ff909f2, 0x7ff8e8a3, 0x7ff8c705, - 0x7ff8a519, 0x7ff882dd, - 0x7ff86053, 0x7ff83d79, 0x7ff81a51, 0x7ff7f6da, 0x7ff7d313, 0x7ff7aefe, - 0x7ff78a9a, 0x7ff765e7, - 0x7ff740e5, 0x7ff71b94, 0x7ff6f5f4, 0x7ff6d005, 0x7ff6a9c8, 0x7ff6833b, - 0x7ff65c5f, 0x7ff63535, - 0x7ff60dbb, 0x7ff5e5f3, 0x7ff5bddc, 0x7ff59576, 0x7ff56cc0, 0x7ff543bc, - 0x7ff51a69, 0x7ff4f0c7, - 0x7ff4c6d6, 0x7ff49c96, 0x7ff47208, 0x7ff4472a, 0x7ff41bfd, 0x7ff3f082, - 0x7ff3c4b7, 0x7ff3989e, - 0x7ff36c36, 0x7ff33f7e, 0x7ff31278, 0x7ff2e523, 0x7ff2b77f, 0x7ff2898c, - 0x7ff25b4a, 0x7ff22cb9, - 0x7ff1fdd9, 0x7ff1ceab, 0x7ff19f2d, 0x7ff16f61, 0x7ff13f45, 0x7ff10edb, - 0x7ff0de22, 0x7ff0ad19, - 0x7ff07bc2, 0x7ff04a1c, 0x7ff01827, 0x7fefe5e4, 0x7fefb351, 0x7fef806f, - 0x7fef4d3e, 0x7fef19bf, - 0x7feee5f0, 0x7feeb1d3, 0x7fee7d67, 0x7fee48ac, 0x7fee13a1, 0x7fedde48, - 0x7feda8a0, 0x7fed72aa, - 0x7fed3c64, 0x7fed05cf, 0x7fecceec, 0x7fec97b9, 0x7fec6038, 0x7fec2867, - 0x7febf048, 0x7febb7da, - 0x7feb7f1d, 0x7feb4611, 0x7feb0cb6, 0x7fead30c, 0x7fea9914, 0x7fea5ecc, - 0x7fea2436, 0x7fe9e950, - 0x7fe9ae1c, 0x7fe97299, 0x7fe936c7, 0x7fe8faa6, 0x7fe8be36, 0x7fe88177, - 0x7fe84469, 0x7fe8070d, - 0x7fe7c961, 0x7fe78b67, 0x7fe74d1e, 0x7fe70e85, 0x7fe6cf9e, 0x7fe69068, - 0x7fe650e3, 0x7fe61110, - 0x7fe5d0ed, 0x7fe5907b, 0x7fe54fbb, 0x7fe50eac, 0x7fe4cd4d, 0x7fe48ba0, - 0x7fe449a4, 0x7fe40759, - 0x7fe3c4bf, 0x7fe381d7, 0x7fe33e9f, 0x7fe2fb19, 0x7fe2b743, 0x7fe2731f, - 0x7fe22eac, 0x7fe1e9ea, - 0x7fe1a4d9, 0x7fe15f79, 0x7fe119cb, 0x7fe0d3cd, 0x7fe08d81, 0x7fe046e5, - 0x7fdffffb, 0x7fdfb8c2, - 0x7fdf713a, 0x7fdf2963, 0x7fdee13e, 0x7fde98c9, 0x7fde5006, 0x7fde06f3, - 0x7fddbd92, 0x7fdd73e2, - 0x7fdd29e3, 0x7fdcdf95, 0x7fdc94f9, 0x7fdc4a0d, 0x7fdbfed3, 0x7fdbb349, - 0x7fdb6771, 0x7fdb1b4a, - 0x7fdaced4, 0x7fda820f, 0x7fda34fc, 0x7fd9e799, 0x7fd999e8, 0x7fd94be8, - 0x7fd8fd98, 0x7fd8aefa, - 0x7fd8600e, 0x7fd810d2, 0x7fd7c147, 0x7fd7716e, 0x7fd72146, 0x7fd6d0cf, - 0x7fd68009, 0x7fd62ef4, - 0x7fd5dd90, 0x7fd58bdd, 0x7fd539dc, 0x7fd4e78c, 0x7fd494ed, 0x7fd441ff, - 0x7fd3eec2, 0x7fd39b36, - 0x7fd3475c, 0x7fd2f332, 0x7fd29eba, 0x7fd249f3, 0x7fd1f4dd, 0x7fd19f78, - 0x7fd149c5, 0x7fd0f3c2, - 0x7fd09d71, 0x7fd046d1, 0x7fcfefe2, 0x7fcf98a4, 0x7fcf4117, 0x7fcee93c, - 0x7fce9112, 0x7fce3898, - 0x7fcddfd0, 0x7fcd86b9, 0x7fcd2d54, 0x7fccd39f, 0x7fcc799c, 0x7fcc1f4a, - 0x7fcbc4a9, 0x7fcb69b9, - 0x7fcb0e7a, 0x7fcab2ed, 0x7fca5710, 0x7fc9fae5, 0x7fc99e6b, 0x7fc941a2, - 0x7fc8e48b, 0x7fc88724, - 0x7fc8296f, 0x7fc7cb6b, 0x7fc76d18, 0x7fc70e76, 0x7fc6af86, 0x7fc65046, - 0x7fc5f0b8, 0x7fc590db, - 0x7fc530af, 0x7fc4d035, 0x7fc46f6b, 0x7fc40e53, 0x7fc3acec, 0x7fc34b36, - 0x7fc2e931, 0x7fc286de, - 0x7fc2243b, 0x7fc1c14a, 0x7fc15e0a, 0x7fc0fa7b, 0x7fc0969e, 0x7fc03271, - 0x7fbfcdf6, 0x7fbf692c, - 0x7fbf0414, 0x7fbe9eac, 0x7fbe38f6, 0x7fbdd2f0, 0x7fbd6c9c, 0x7fbd05fa, - 0x7fbc9f08, 0x7fbc37c8, - 0x7fbbd039, 0x7fbb685b, 0x7fbb002e, 0x7fba97b2, 0x7fba2ee8, 0x7fb9c5cf, - 0x7fb95c67, 0x7fb8f2b0, - 0x7fb888ab, 0x7fb81e57, 0x7fb7b3b4, 0x7fb748c2, 0x7fb6dd81, 0x7fb671f2, - 0x7fb60614, 0x7fb599e7, - 0x7fb52d6b, 0x7fb4c0a1, 0x7fb45387, 0x7fb3e61f, 0x7fb37869, 0x7fb30a63, - 0x7fb29c0f, 0x7fb22d6c, - 0x7fb1be7a, 0x7fb14f39, 0x7fb0dfaa, 0x7fb06fcb, 0x7fafff9e, 0x7faf8f23, - 0x7faf1e58, 0x7faead3f, - 0x7fae3bd7, 0x7fadca20, 0x7fad581b, 0x7face5c6, 0x7fac7323, 0x7fac0031, - 0x7fab8cf1, 0x7fab1962, - 0x7faaa584, 0x7faa3157, 0x7fa9bcdb, 0x7fa94811, 0x7fa8d2f8, 0x7fa85d90, - 0x7fa7e7d9, 0x7fa771d4, - 0x7fa6fb80, 0x7fa684dd, 0x7fa60dec, 0x7fa596ac, 0x7fa51f1d, 0x7fa4a73f, - 0x7fa42f12, 0x7fa3b697, - 0x7fa33dcd, 0x7fa2c4b5, 0x7fa24b4d, 0x7fa1d197, 0x7fa15792, 0x7fa0dd3f, - 0x7fa0629c, 0x7f9fe7ab, - 0x7f9f6c6b, 0x7f9ef0dd, 0x7f9e7500, 0x7f9df8d4, 0x7f9d7c59, 0x7f9cff90, - 0x7f9c8278, 0x7f9c0511, - 0x7f9b875b, 0x7f9b0957, 0x7f9a8b04, 0x7f9a0c62, 0x7f998d72, 0x7f990e33, - 0x7f988ea5, 0x7f980ec8, - 0x7f978e9d, 0x7f970e23, 0x7f968d5b, 0x7f960c43, 0x7f958add, 0x7f950929, - 0x7f948725, 0x7f9404d3, - 0x7f938232, 0x7f92ff43, 0x7f927c04, 0x7f91f878, 0x7f91749c, 0x7f90f072, - 0x7f906bf9, 0x7f8fe731, - 0x7f8f621b, 0x7f8edcb6, 0x7f8e5702, 0x7f8dd0ff, 0x7f8d4aae, 0x7f8cc40f, - 0x7f8c3d20, 0x7f8bb5e3, - 0x7f8b2e57, 0x7f8aa67d, 0x7f8a1e54, 0x7f8995dc, 0x7f890d15, 0x7f888400, - 0x7f87fa9c, 0x7f8770ea, - 0x7f86e6e9, 0x7f865c99, 0x7f85d1fa, 0x7f85470d, 0x7f84bbd1, 0x7f843047, - 0x7f83a46e, 0x7f831846, - 0x7f828bcf, 0x7f81ff0a, 0x7f8171f6, 0x7f80e494, 0x7f8056e3, 0x7f7fc8e3, - 0x7f7f3a95, 0x7f7eabf8, - 0x7f7e1d0c, 0x7f7d8dd2, 0x7f7cfe49, 0x7f7c6e71, 0x7f7bde4b, 0x7f7b4dd6, - 0x7f7abd13, 0x7f7a2c01, - 0x7f799aa0, 0x7f7908f0, 0x7f7876f2, 0x7f77e4a6, 0x7f77520a, 0x7f76bf21, - 0x7f762be8, 0x7f759861, - 0x7f75048b, 0x7f747067, 0x7f73dbf4, 0x7f734732, 0x7f72b222, 0x7f721cc3, - 0x7f718715, 0x7f70f119, - 0x7f705ace, 0x7f6fc435, 0x7f6f2d4d, 0x7f6e9617, 0x7f6dfe91, 0x7f6d66be, - 0x7f6cce9b, 0x7f6c362a, - 0x7f6b9d6b, 0x7f6b045d, 0x7f6a6b00, 0x7f69d154, 0x7f69375a, 0x7f689d12, - 0x7f68027b, 0x7f676795, - 0x7f66cc61, 0x7f6630de, 0x7f65950c, 0x7f64f8ec, 0x7f645c7d, 0x7f63bfc0, - 0x7f6322b4, 0x7f62855a, - 0x7f61e7b1, 0x7f6149b9, 0x7f60ab73, 0x7f600cdf, 0x7f5f6dfb, 0x7f5ecec9, - 0x7f5e2f49, 0x7f5d8f7a, - 0x7f5cef5c, 0x7f5c4ef0, 0x7f5bae36, 0x7f5b0d2c, 0x7f5a6bd5, 0x7f59ca2e, - 0x7f592839, 0x7f5885f6, - 0x7f57e364, 0x7f574083, 0x7f569d54, 0x7f55f9d6, 0x7f55560a, 0x7f54b1ef, - 0x7f540d86, 0x7f5368ce, - 0x7f52c3c8, 0x7f521e73, 0x7f5178cf, 0x7f50d2dd, 0x7f502c9d, 0x7f4f860e, - 0x7f4edf30, 0x7f4e3804, - 0x7f4d9089, 0x7f4ce8c0, 0x7f4c40a8, 0x7f4b9842, 0x7f4aef8d, 0x7f4a468a, - 0x7f499d38, 0x7f48f398, - 0x7f4849a9, 0x7f479f6c, 0x7f46f4e0, 0x7f464a06, 0x7f459edd, 0x7f44f365, - 0x7f44479f, 0x7f439b8b, - 0x7f42ef28, 0x7f424277, 0x7f419577, 0x7f40e828, 0x7f403a8b, 0x7f3f8ca0, - 0x7f3ede66, 0x7f3e2fde, - 0x7f3d8107, 0x7f3cd1e2, 0x7f3c226e, 0x7f3b72ab, 0x7f3ac29b, 0x7f3a123b, - 0x7f39618e, 0x7f38b091, - 0x7f37ff47, 0x7f374dad, 0x7f369bc6, 0x7f35e990, 0x7f35370b, 0x7f348438, - 0x7f33d116, 0x7f331da6, - 0x7f3269e8, 0x7f31b5db, 0x7f31017f, 0x7f304cd6, 0x7f2f97dd, 0x7f2ee296, - 0x7f2e2d01, 0x7f2d771e, - 0x7f2cc0eb, 0x7f2c0a6b, 0x7f2b539c, 0x7f2a9c7e, 0x7f29e512, 0x7f292d58, - 0x7f28754f, 0x7f27bcf8, - 0x7f270452, 0x7f264b5e, 0x7f25921c, 0x7f24d88b, 0x7f241eab, 0x7f23647e, - 0x7f22aa01, 0x7f21ef37, - 0x7f21341e, 0x7f2078b6, 0x7f1fbd00, 0x7f1f00fc, 0x7f1e44a9, 0x7f1d8808, - 0x7f1ccb18, 0x7f1c0dda, - 0x7f1b504e, 0x7f1a9273, 0x7f19d44a, 0x7f1915d2, 0x7f18570c, 0x7f1797f8, - 0x7f16d895, 0x7f1618e4, - 0x7f1558e4, 0x7f149896, 0x7f13d7fa, 0x7f13170f, 0x7f1255d6, 0x7f11944f, - 0x7f10d279, 0x7f101054, - 0x7f0f4de2, 0x7f0e8b21, 0x7f0dc811, 0x7f0d04b3, 0x7f0c4107, 0x7f0b7d0d, - 0x7f0ab8c4, 0x7f09f42d, - 0x7f092f47, 0x7f086a13, 0x7f07a491, 0x7f06dec0, 0x7f0618a1, 0x7f055233, - 0x7f048b78, 0x7f03c46d, - 0x7f02fd15, 0x7f02356e, 0x7f016d79, 0x7f00a535, 0x7effdca4, 0x7eff13c3, - 0x7efe4a95, 0x7efd8118, - 0x7efcb74d, 0x7efbed33, 0x7efb22cb, 0x7efa5815, 0x7ef98d11, 0x7ef8c1be, - 0x7ef7f61d, 0x7ef72a2d, - 0x7ef65def, 0x7ef59163, 0x7ef4c489, 0x7ef3f760, 0x7ef329e9, 0x7ef25c24, - 0x7ef18e10, 0x7ef0bfae, - 0x7eeff0fe, 0x7eef21ff, 0x7eee52b2, 0x7eed8317, 0x7eecb32d, 0x7eebe2f6, - 0x7eeb1270, 0x7eea419b, - 0x7ee97079, 0x7ee89f08, 0x7ee7cd49, 0x7ee6fb3b, 0x7ee628df, 0x7ee55635, - 0x7ee4833d, 0x7ee3aff6, - 0x7ee2dc61, 0x7ee2087e, 0x7ee1344d, 0x7ee05fcd, 0x7edf8aff, 0x7edeb5e3, - 0x7edde079, 0x7edd0ac0, - 0x7edc34b9, 0x7edb5e64, 0x7eda87c0, 0x7ed9b0ce, 0x7ed8d98e, 0x7ed80200, - 0x7ed72a24, 0x7ed651f9, - 0x7ed57980, 0x7ed4a0b9, 0x7ed3c7a3, 0x7ed2ee40, 0x7ed2148e, 0x7ed13a8e, - 0x7ed0603f, 0x7ecf85a3, - 0x7eceaab8, 0x7ecdcf7f, 0x7eccf3f8, 0x7ecc1822, 0x7ecb3bff, 0x7eca5f8d, - 0x7ec982cd, 0x7ec8a5bf, - 0x7ec7c862, 0x7ec6eab7, 0x7ec60cbe, 0x7ec52e77, 0x7ec44fe2, 0x7ec370fe, - 0x7ec291cd, 0x7ec1b24d, - 0x7ec0d27f, 0x7ebff263, 0x7ebf11f8, 0x7ebe313f, 0x7ebd5039, 0x7ebc6ee4, - 0x7ebb8d40, 0x7ebaab4f, - 0x7eb9c910, 0x7eb8e682, 0x7eb803a6, 0x7eb7207c, 0x7eb63d04, 0x7eb5593d, - 0x7eb47529, 0x7eb390c6, - 0x7eb2ac15, 0x7eb1c716, 0x7eb0e1c9, 0x7eaffc2e, 0x7eaf1645, 0x7eae300d, - 0x7ead4987, 0x7eac62b3, - 0x7eab7b91, 0x7eaa9421, 0x7ea9ac63, 0x7ea8c457, 0x7ea7dbfc, 0x7ea6f353, - 0x7ea60a5d, 0x7ea52118, - 0x7ea43785, 0x7ea34da4, 0x7ea26374, 0x7ea178f7, 0x7ea08e2b, 0x7e9fa312, - 0x7e9eb7aa, 0x7e9dcbf4, - 0x7e9cdff0, 0x7e9bf39e, 0x7e9b06fe, 0x7e9a1a10, 0x7e992cd4, 0x7e983f49, - 0x7e975171, 0x7e96634a, - 0x7e9574d6, 0x7e948613, 0x7e939702, 0x7e92a7a3, 0x7e91b7f6, 0x7e90c7fb, - 0x7e8fd7b2, 0x7e8ee71b, - 0x7e8df636, 0x7e8d0502, 0x7e8c1381, 0x7e8b21b1, 0x7e8a2f94, 0x7e893d28, - 0x7e884a6f, 0x7e875767, - 0x7e866411, 0x7e85706d, 0x7e847c7c, 0x7e83883c, 0x7e8293ae, 0x7e819ed2, - 0x7e80a9a8, 0x7e7fb430, - 0x7e7ebe6a, 0x7e7dc856, 0x7e7cd1f4, 0x7e7bdb44, 0x7e7ae446, 0x7e79ecf9, - 0x7e78f55f, 0x7e77fd77, - 0x7e770541, 0x7e760cbd, 0x7e7513ea, 0x7e741aca, 0x7e73215c, 0x7e7227a0, - 0x7e712d96, 0x7e70333d, - 0x7e6f3897, 0x7e6e3da3, 0x7e6d4261, 0x7e6c46d1, 0x7e6b4af2, 0x7e6a4ec6, - 0x7e69524c, 0x7e685584, - 0x7e67586e, 0x7e665b0a, 0x7e655d58, 0x7e645f58, 0x7e63610a, 0x7e62626e, - 0x7e616384, 0x7e60644c, - 0x7e5f64c7, 0x7e5e64f3, 0x7e5d64d1, 0x7e5c6461, 0x7e5b63a4, 0x7e5a6298, - 0x7e59613f, 0x7e585f97, - 0x7e575da2, 0x7e565b5f, 0x7e5558ce, 0x7e5455ef, 0x7e5352c1, 0x7e524f46, - 0x7e514b7e, 0x7e504767, - 0x7e4f4302, 0x7e4e3e4f, 0x7e4d394f, 0x7e4c3400, 0x7e4b2e64, 0x7e4a287a, - 0x7e492241, 0x7e481bbb, - 0x7e4714e7, 0x7e460dc5, 0x7e450656, 0x7e43fe98, 0x7e42f68c, 0x7e41ee33, - 0x7e40e58c, 0x7e3fdc97, - 0x7e3ed353, 0x7e3dc9c3, 0x7e3cbfe4, 0x7e3bb5b7, 0x7e3aab3c, 0x7e39a074, - 0x7e38955e, 0x7e3789fa, - 0x7e367e48, 0x7e357248, 0x7e3465fa, 0x7e33595e, 0x7e324c75, 0x7e313f3e, - 0x7e3031b9, 0x7e2f23e6, - 0x7e2e15c5, 0x7e2d0756, 0x7e2bf89a, 0x7e2ae990, 0x7e29da38, 0x7e28ca92, - 0x7e27ba9e, 0x7e26aa5d, - 0x7e2599cd, 0x7e2488f0, 0x7e2377c5, 0x7e22664c, 0x7e215486, 0x7e204271, - 0x7e1f300f, 0x7e1e1d5f, - 0x7e1d0a61, 0x7e1bf716, 0x7e1ae37c, 0x7e19cf95, 0x7e18bb60, 0x7e17a6dd, - 0x7e16920d, 0x7e157cee, - 0x7e146782, 0x7e1351c9, 0x7e123bc1, 0x7e11256c, 0x7e100ec8, 0x7e0ef7d7, - 0x7e0de099, 0x7e0cc90c, - 0x7e0bb132, 0x7e0a990a, 0x7e098095, 0x7e0867d1, 0x7e074ec0, 0x7e063561, - 0x7e051bb4, 0x7e0401ba, - 0x7e02e772, 0x7e01ccdc, 0x7e00b1f9, 0x7dff96c7, 0x7dfe7b48, 0x7dfd5f7b, - 0x7dfc4361, 0x7dfb26f9, - 0x7dfa0a43, 0x7df8ed3f, 0x7df7cfee, 0x7df6b24f, 0x7df59462, 0x7df47628, - 0x7df357a0, 0x7df238ca, - 0x7df119a7, 0x7deffa35, 0x7deeda77, 0x7dedba6a, 0x7dec9a10, 0x7deb7968, - 0x7dea5872, 0x7de9372f, - 0x7de8159e, 0x7de6f3c0, 0x7de5d193, 0x7de4af1a, 0x7de38c52, 0x7de2693d, - 0x7de145da, 0x7de02229, - 0x7ddefe2b, 0x7dddd9e0, 0x7ddcb546, 0x7ddb905f, 0x7dda6b2a, 0x7dd945a8, - 0x7dd81fd8, 0x7dd6f9ba, - 0x7dd5d34f, 0x7dd4ac96, 0x7dd38590, 0x7dd25e3c, 0x7dd1369a, 0x7dd00eab, - 0x7dcee66e, 0x7dcdbde3, - 0x7dcc950b, 0x7dcb6be6, 0x7dca4272, 0x7dc918b1, 0x7dc7eea3, 0x7dc6c447, - 0x7dc5999d, 0x7dc46ea6, - 0x7dc34361, 0x7dc217cf, 0x7dc0ebef, 0x7dbfbfc1, 0x7dbe9346, 0x7dbd667d, - 0x7dbc3967, 0x7dbb0c03, - 0x7db9de52, 0x7db8b053, 0x7db78207, 0x7db6536d, 0x7db52485, 0x7db3f550, - 0x7db2c5cd, 0x7db195fd, - 0x7db065df, 0x7daf3574, 0x7dae04bb, 0x7dacd3b5, 0x7daba261, 0x7daa70c0, - 0x7da93ed1, 0x7da80c95, - 0x7da6da0b, 0x7da5a733, 0x7da4740e, 0x7da3409c, 0x7da20cdc, 0x7da0d8cf, - 0x7d9fa474, 0x7d9e6fcb, - 0x7d9d3ad6, 0x7d9c0592, 0x7d9ad001, 0x7d999a23, 0x7d9863f7, 0x7d972d7e, - 0x7d95f6b7, 0x7d94bfa3, - 0x7d938841, 0x7d925092, 0x7d911896, 0x7d8fe04c, 0x7d8ea7b4, 0x7d8d6ecf, - 0x7d8c359d, 0x7d8afc1d, - 0x7d89c250, 0x7d888835, 0x7d874dcd, 0x7d861317, 0x7d84d814, 0x7d839cc4, - 0x7d826126, 0x7d81253a, - 0x7d7fe902, 0x7d7eac7c, 0x7d7d6fa8, 0x7d7c3287, 0x7d7af519, 0x7d79b75d, - 0x7d787954, 0x7d773afd, - 0x7d75fc59, 0x7d74bd68, 0x7d737e29, 0x7d723e9d, 0x7d70fec4, 0x7d6fbe9d, - 0x7d6e7e29, 0x7d6d3d67, - 0x7d6bfc58, 0x7d6abafc, 0x7d697952, 0x7d68375b, 0x7d66f517, 0x7d65b285, - 0x7d646fa6, 0x7d632c79, - 0x7d61e8ff, 0x7d60a538, 0x7d5f6124, 0x7d5e1cc2, 0x7d5cd813, 0x7d5b9316, - 0x7d5a4dcc, 0x7d590835, - 0x7d57c251, 0x7d567c1f, 0x7d5535a0, 0x7d53eed3, 0x7d52a7ba, 0x7d516053, - 0x7d50189e, 0x7d4ed09d, - 0x7d4d884e, 0x7d4c3fb1, 0x7d4af6c8, 0x7d49ad91, 0x7d48640d, 0x7d471a3c, - 0x7d45d01d, 0x7d4485b1, - 0x7d433af8, 0x7d41eff1, 0x7d40a49e, 0x7d3f58fd, 0x7d3e0d0e, 0x7d3cc0d3, - 0x7d3b744a, 0x7d3a2774, - 0x7d38da51, 0x7d378ce0, 0x7d363f23, 0x7d34f118, 0x7d33a2bf, 0x7d32541a, - 0x7d310527, 0x7d2fb5e7, - 0x7d2e665a, 0x7d2d1680, 0x7d2bc659, 0x7d2a75e4, 0x7d292522, 0x7d27d413, - 0x7d2682b6, 0x7d25310d, - 0x7d23df16, 0x7d228cd2, 0x7d213a41, 0x7d1fe762, 0x7d1e9437, 0x7d1d40be, - 0x7d1becf8, 0x7d1a98e5, - 0x7d194485, 0x7d17efd8, 0x7d169add, 0x7d154595, 0x7d13f001, 0x7d129a1f, - 0x7d1143ef, 0x7d0fed73, - 0x7d0e96aa, 0x7d0d3f93, 0x7d0be82f, 0x7d0a907e, 0x7d093880, 0x7d07e035, - 0x7d06879d, 0x7d052eb8, - 0x7d03d585, 0x7d027c05, 0x7d012239, 0x7cffc81f, 0x7cfe6db8, 0x7cfd1304, - 0x7cfbb803, 0x7cfa5cb4, - 0x7cf90119, 0x7cf7a531, 0x7cf648fb, 0x7cf4ec79, 0x7cf38fa9, 0x7cf2328c, - 0x7cf0d522, 0x7cef776b, - 0x7cee1967, 0x7cecbb16, 0x7ceb5c78, 0x7ce9fd8d, 0x7ce89e55, 0x7ce73ed0, - 0x7ce5defd, 0x7ce47ede, - 0x7ce31e72, 0x7ce1bdb8, 0x7ce05cb2, 0x7cdefb5e, 0x7cdd99be, 0x7cdc37d0, - 0x7cdad596, 0x7cd9730e, - 0x7cd8103a, 0x7cd6ad18, 0x7cd549aa, 0x7cd3e5ee, 0x7cd281e5, 0x7cd11d90, - 0x7ccfb8ed, 0x7cce53fe, - 0x7ccceec1, 0x7ccb8937, 0x7cca2361, 0x7cc8bd3d, 0x7cc756cd, 0x7cc5f010, - 0x7cc48905, 0x7cc321ae, - 0x7cc1ba09, 0x7cc05218, 0x7cbee9da, 0x7cbd814f, 0x7cbc1877, 0x7cbaaf51, - 0x7cb945df, 0x7cb7dc20, - 0x7cb67215, 0x7cb507bc, 0x7cb39d16, 0x7cb23223, 0x7cb0c6e4, 0x7caf5b57, - 0x7cadef7e, 0x7cac8358, - 0x7cab16e4, 0x7ca9aa24, 0x7ca83d17, 0x7ca6cfbd, 0x7ca56216, 0x7ca3f423, - 0x7ca285e2, 0x7ca11755, - 0x7c9fa87a, 0x7c9e3953, 0x7c9cc9df, 0x7c9b5a1e, 0x7c99ea10, 0x7c9879b6, - 0x7c97090e, 0x7c95981a, - 0x7c9426d8, 0x7c92b54a, 0x7c91436f, 0x7c8fd148, 0x7c8e5ed3, 0x7c8cec12, - 0x7c8b7903, 0x7c8a05a8, - 0x7c889200, 0x7c871e0c, 0x7c85a9ca, 0x7c84353c, 0x7c82c060, 0x7c814b39, - 0x7c7fd5c4, 0x7c7e6002, - 0x7c7ce9f4, 0x7c7b7399, 0x7c79fcf1, 0x7c7885fc, 0x7c770eba, 0x7c75972c, - 0x7c741f51, 0x7c72a729, - 0x7c712eb5, 0x7c6fb5f3, 0x7c6e3ce5, 0x7c6cc38a, 0x7c6b49e3, 0x7c69cfee, - 0x7c6855ad, 0x7c66db1f, - 0x7c656045, 0x7c63e51e, 0x7c6269aa, 0x7c60ede9, 0x7c5f71db, 0x7c5df581, - 0x7c5c78da, 0x7c5afbe6, - 0x7c597ea6, 0x7c580119, 0x7c56833f, 0x7c550519, 0x7c5386a6, 0x7c5207e6, - 0x7c5088d9, 0x7c4f0980, - 0x7c4d89da, 0x7c4c09e8, 0x7c4a89a8, 0x7c49091c, 0x7c478844, 0x7c46071f, - 0x7c4485ad, 0x7c4303ee, - 0x7c4181e3, 0x7c3fff8b, 0x7c3e7ce7, 0x7c3cf9f5, 0x7c3b76b8, 0x7c39f32d, - 0x7c386f56, 0x7c36eb33, - 0x7c3566c2, 0x7c33e205, 0x7c325cfc, 0x7c30d7a6, 0x7c2f5203, 0x7c2dcc14, - 0x7c2c45d8, 0x7c2abf4f, - 0x7c29387a, 0x7c27b158, 0x7c2629ea, 0x7c24a22f, 0x7c231a28, 0x7c2191d4, - 0x7c200933, 0x7c1e8046, - 0x7c1cf70c, 0x7c1b6d86, 0x7c19e3b3, 0x7c185994, 0x7c16cf28, 0x7c15446f, - 0x7c13b96a, 0x7c122e19, - 0x7c10a27b, 0x7c0f1690, 0x7c0d8a59, 0x7c0bfdd5, 0x7c0a7105, 0x7c08e3e8, - 0x7c07567f, 0x7c05c8c9, - 0x7c043ac7, 0x7c02ac78, 0x7c011ddd, 0x7bff8ef5, 0x7bfdffc1, 0x7bfc7041, - 0x7bfae073, 0x7bf9505a, - 0x7bf7bff4, 0x7bf62f41, 0x7bf49e42, 0x7bf30cf6, 0x7bf17b5e, 0x7befe97a, - 0x7bee5749, 0x7becc4cc, - 0x7beb3202, 0x7be99eec, 0x7be80b89, 0x7be677da, 0x7be4e3df, 0x7be34f97, - 0x7be1bb02, 0x7be02621, - 0x7bde90f4, 0x7bdcfb7b, 0x7bdb65b5, 0x7bd9cfa2, 0x7bd83944, 0x7bd6a298, - 0x7bd50ba1, 0x7bd3745d, - 0x7bd1dccc, 0x7bd044f0, 0x7bceacc7, 0x7bcd1451, 0x7bcb7b8f, 0x7bc9e281, - 0x7bc84927, 0x7bc6af80, - 0x7bc5158c, 0x7bc37b4d, 0x7bc1e0c1, 0x7bc045e9, 0x7bbeaac4, 0x7bbd0f53, - 0x7bbb7396, 0x7bb9d78c, - 0x7bb83b36, 0x7bb69e94, 0x7bb501a5, 0x7bb3646a, 0x7bb1c6e3, 0x7bb02910, - 0x7bae8af0, 0x7bacec84, - 0x7bab4dcc, 0x7ba9aec7, 0x7ba80f76, 0x7ba66fd9, 0x7ba4cfef, 0x7ba32fba, - 0x7ba18f38, 0x7b9fee69, - 0x7b9e4d4f, 0x7b9cabe8, 0x7b9b0a35, 0x7b996836, 0x7b97c5ea, 0x7b962352, - 0x7b94806e, 0x7b92dd3e, - 0x7b9139c2, 0x7b8f95f9, 0x7b8df1e4, 0x7b8c4d83, 0x7b8aa8d6, 0x7b8903dc, - 0x7b875e96, 0x7b85b904, - 0x7b841326, 0x7b826cfc, 0x7b80c686, 0x7b7f1fc3, 0x7b7d78b4, 0x7b7bd159, - 0x7b7a29b2, 0x7b7881be, - 0x7b76d97f, 0x7b7530f3, 0x7b73881b, 0x7b71def7, 0x7b703587, 0x7b6e8bcb, - 0x7b6ce1c2, 0x7b6b376e, - 0x7b698ccd, 0x7b67e1e0, 0x7b6636a7, 0x7b648b22, 0x7b62df51, 0x7b613334, - 0x7b5f86ca, 0x7b5dda15, - 0x7b5c2d13, 0x7b5a7fc6, 0x7b58d22c, 0x7b572446, 0x7b557614, 0x7b53c796, - 0x7b5218cc, 0x7b5069b6, - 0x7b4eba53, 0x7b4d0aa5, 0x7b4b5aab, 0x7b49aa64, 0x7b47f9d2, 0x7b4648f3, - 0x7b4497c9, 0x7b42e652, - 0x7b413490, 0x7b3f8281, 0x7b3dd026, 0x7b3c1d80, 0x7b3a6a8d, 0x7b38b74e, - 0x7b3703c3, 0x7b354fed, - 0x7b339bca, 0x7b31e75b, 0x7b3032a0, 0x7b2e7d9a, 0x7b2cc847, 0x7b2b12a8, - 0x7b295cbe, 0x7b27a687, - 0x7b25f004, 0x7b243936, 0x7b22821b, 0x7b20cab5, 0x7b1f1302, 0x7b1d5b04, - 0x7b1ba2b9, 0x7b19ea23, - 0x7b183141, 0x7b167813, 0x7b14be99, 0x7b1304d3, 0x7b114ac1, 0x7b0f9063, - 0x7b0dd5b9, 0x7b0c1ac4, - 0x7b0a5f82, 0x7b08a3f5, 0x7b06e81b, 0x7b052bf6, 0x7b036f85, 0x7b01b2c8, - 0x7afff5bf, 0x7afe386a, - 0x7afc7aca, 0x7afabcdd, 0x7af8fea5, 0x7af74021, 0x7af58151, 0x7af3c235, - 0x7af202cd, 0x7af0431a, - 0x7aee831a, 0x7aecc2cf, 0x7aeb0238, 0x7ae94155, 0x7ae78026, 0x7ae5beac, - 0x7ae3fce6, 0x7ae23ad4, - 0x7ae07876, 0x7adeb5cc, 0x7adcf2d6, 0x7adb2f95, 0x7ad96c08, 0x7ad7a82f, - 0x7ad5e40a, 0x7ad41f9a, - 0x7ad25ade, 0x7ad095d6, 0x7aced082, 0x7acd0ae3, 0x7acb44f8, 0x7ac97ec1, - 0x7ac7b83e, 0x7ac5f170, - 0x7ac42a55, 0x7ac262ef, 0x7ac09b3e, 0x7abed341, 0x7abd0af7, 0x7abb4263, - 0x7ab97982, 0x7ab7b056, - 0x7ab5e6de, 0x7ab41d1b, 0x7ab2530b, 0x7ab088b0, 0x7aaebe0a, 0x7aacf318, - 0x7aab27da, 0x7aa95c50, - 0x7aa7907b, 0x7aa5c45a, 0x7aa3f7ed, 0x7aa22b35, 0x7aa05e31, 0x7a9e90e1, - 0x7a9cc346, 0x7a9af55f, - 0x7a99272d, 0x7a9758af, 0x7a9589e5, 0x7a93bad0, 0x7a91eb6f, 0x7a901bc2, - 0x7a8e4bca, 0x7a8c7b87, - 0x7a8aaaf7, 0x7a88da1c, 0x7a8708f6, 0x7a853784, 0x7a8365c6, 0x7a8193bd, - 0x7a7fc168, 0x7a7deec8, - 0x7a7c1bdc, 0x7a7a48a4, 0x7a787521, 0x7a76a153, 0x7a74cd38, 0x7a72f8d3, - 0x7a712422, 0x7a6f4f25, - 0x7a6d79dd, 0x7a6ba449, 0x7a69ce6a, 0x7a67f83f, 0x7a6621c9, 0x7a644b07, - 0x7a6273fa, 0x7a609ca1, - 0x7a5ec4fc, 0x7a5ced0d, 0x7a5b14d1, 0x7a593c4b, 0x7a576379, 0x7a558a5b, - 0x7a53b0f2, 0x7a51d73d, - 0x7a4ffd3d, 0x7a4e22f2, 0x7a4c485b, 0x7a4a6d78, 0x7a48924b, 0x7a46b6d1, - 0x7a44db0d, 0x7a42fefd, - 0x7a4122a1, 0x7a3f45fa, 0x7a3d6908, 0x7a3b8bca, 0x7a39ae41, 0x7a37d06d, - 0x7a35f24d, 0x7a3413e2, - 0x7a32352b, 0x7a305629, 0x7a2e76dc, 0x7a2c9743, 0x7a2ab75f, 0x7a28d72f, - 0x7a26f6b4, 0x7a2515ee, - 0x7a2334dd, 0x7a215380, 0x7a1f71d7, 0x7a1d8fe4, 0x7a1bada5, 0x7a19cb1b, - 0x7a17e845, 0x7a160524, - 0x7a1421b8, 0x7a123e01, 0x7a1059fe, 0x7a0e75b0, 0x7a0c9117, 0x7a0aac32, - 0x7a08c702, 0x7a06e187, - 0x7a04fbc1, 0x7a0315af, 0x7a012f52, 0x79ff48aa, 0x79fd61b6, 0x79fb7a77, - 0x79f992ed, 0x79f7ab18, - 0x79f5c2f8, 0x79f3da8c, 0x79f1f1d5, 0x79f008d3, 0x79ee1f86, 0x79ec35ed, - 0x79ea4c09, 0x79e861da, - 0x79e67760, 0x79e48c9b, 0x79e2a18a, 0x79e0b62e, 0x79deca87, 0x79dcde95, - 0x79daf258, 0x79d905d0, - 0x79d718fc, 0x79d52bdd, 0x79d33e73, 0x79d150be, 0x79cf62be, 0x79cd7473, - 0x79cb85dc, 0x79c996fb, - 0x79c7a7ce, 0x79c5b856, 0x79c3c893, 0x79c1d885, 0x79bfe82c, 0x79bdf788, - 0x79bc0698, 0x79ba155e, - 0x79b823d8, 0x79b63207, 0x79b43fec, 0x79b24d85, 0x79b05ad3, 0x79ae67d6, - 0x79ac748e, 0x79aa80fb, - 0x79a88d1d, 0x79a698f4, 0x79a4a480, 0x79a2afc1, 0x79a0bab6, 0x799ec561, - 0x799ccfc1, 0x799ad9d5, - 0x7998e39f, 0x7996ed1e, 0x7994f651, 0x7992ff3a, 0x799107d8, 0x798f102a, - 0x798d1832, 0x798b1fef, - 0x79892761, 0x79872e87, 0x79853563, 0x79833bf4, 0x7981423a, 0x797f4835, - 0x797d4de5, 0x797b534a, - 0x79795864, 0x79775d33, 0x797561b8, 0x797365f1, 0x797169df, 0x796f6d83, - 0x796d70dc, 0x796b73e9, - 0x796976ac, 0x79677924, 0x79657b51, 0x79637d33, 0x79617eca, 0x795f8017, - 0x795d8118, 0x795b81cf, - 0x7959823b, 0x7957825c, 0x79558232, 0x795381bd, 0x795180fe, 0x794f7ff3, - 0x794d7e9e, 0x794b7cfe, - 0x79497b13, 0x794778dd, 0x7945765d, 0x79437391, 0x7941707b, 0x793f6d1a, - 0x793d696f, 0x793b6578, - 0x79396137, 0x79375cab, 0x793557d4, 0x793352b2, 0x79314d46, 0x792f478f, - 0x792d418d, 0x792b3b40, - 0x792934a9, 0x79272dc7, 0x7925269a, 0x79231f22, 0x79211760, 0x791f0f53, - 0x791d06fb, 0x791afe59, - 0x7918f56c, 0x7916ec34, 0x7914e2b2, 0x7912d8e4, 0x7910cecc, 0x790ec46a, - 0x790cb9bd, 0x790aaec5, - 0x7908a382, 0x790697f5, 0x79048c1d, 0x79027ffa, 0x7900738d, 0x78fe66d5, - 0x78fc59d3, 0x78fa4c86, - 0x78f83eee, 0x78f6310c, 0x78f422df, 0x78f21467, 0x78f005a5, 0x78edf698, - 0x78ebe741, 0x78e9d79f, - 0x78e7c7b2, 0x78e5b77b, 0x78e3a6f9, 0x78e1962d, 0x78df8516, 0x78dd73b5, - 0x78db6209, 0x78d95012, - 0x78d73dd1, 0x78d52b46, 0x78d31870, 0x78d1054f, 0x78cef1e4, 0x78ccde2e, - 0x78caca2e, 0x78c8b5e3, - 0x78c6a14e, 0x78c48c6e, 0x78c27744, 0x78c061cf, 0x78be4c10, 0x78bc3606, - 0x78ba1fb2, 0x78b80913, - 0x78b5f22a, 0x78b3daf7, 0x78b1c379, 0x78afabb0, 0x78ad939d, 0x78ab7b40, - 0x78a96298, 0x78a749a6, - 0x78a53069, 0x78a316e2, 0x78a0fd11, 0x789ee2f5, 0x789cc88f, 0x789aadde, - 0x789892e3, 0x7896779d, - 0x78945c0d, 0x78924033, 0x7890240e, 0x788e07a0, 0x788beae6, 0x7889cde2, - 0x7887b094, 0x788592fc, - 0x78837519, 0x788156ec, 0x787f3875, 0x787d19b3, 0x787afaa7, 0x7878db50, - 0x7876bbb0, 0x78749bc5, - 0x78727b8f, 0x78705b10, 0x786e3a46, 0x786c1932, 0x7869f7d3, 0x7867d62a, - 0x7865b437, 0x786391fa, - 0x78616f72, 0x785f4ca1, 0x785d2984, 0x785b061e, 0x7858e26e, 0x7856be73, - 0x78549a2e, 0x7852759e, - 0x785050c5, 0x784e2ba1, 0x784c0633, 0x7849e07b, 0x7847ba79, 0x7845942c, - 0x78436d96, 0x784146b5, - 0x783f1f8a, 0x783cf815, 0x783ad055, 0x7838a84c, 0x78367ff8, 0x7834575a, - 0x78322e72, 0x78300540, - 0x782ddbc4, 0x782bb1fd, 0x782987ed, 0x78275d92, 0x782532ed, 0x782307fe, - 0x7820dcc5, 0x781eb142, - 0x781c8575, 0x781a595d, 0x78182cfc, 0x78160051, 0x7813d35b, 0x7811a61b, - 0x780f7892, 0x780d4abe, - 0x780b1ca0, 0x7808ee38, 0x7806bf86, 0x7804908a, 0x78026145, 0x780031b5, - 0x77fe01db, 0x77fbd1b6, - 0x77f9a148, 0x77f77090, 0x77f53f8e, 0x77f30e42, 0x77f0dcac, 0x77eeaacc, - 0x77ec78a2, 0x77ea462e, - 0x77e81370, 0x77e5e068, 0x77e3ad17, 0x77e1797b, 0x77df4595, 0x77dd1165, - 0x77dadcec, 0x77d8a828, - 0x77d6731a, 0x77d43dc3, 0x77d20822, 0x77cfd236, 0x77cd9c01, 0x77cb6582, - 0x77c92eb9, 0x77c6f7a6, - 0x77c4c04a, 0x77c288a3, 0x77c050b2, 0x77be1878, 0x77bbdff4, 0x77b9a726, - 0x77b76e0e, 0x77b534ac, - 0x77b2fb00, 0x77b0c10b, 0x77ae86cc, 0x77ac4c43, 0x77aa1170, 0x77a7d653, - 0x77a59aec, 0x77a35f3c, - 0x77a12342, 0x779ee6fe, 0x779caa70, 0x779a6d99, 0x77983077, 0x7795f30c, - 0x7793b557, 0x77917759, - 0x778f3910, 0x778cfa7e, 0x778abba2, 0x77887c7d, 0x77863d0d, 0x7783fd54, - 0x7781bd52, 0x777f7d05, - 0x777d3c6f, 0x777afb8f, 0x7778ba65, 0x777678f2, 0x77743735, 0x7771f52e, - 0x776fb2de, 0x776d7044, - 0x776b2d60, 0x7768ea33, 0x7766a6bc, 0x776462fb, 0x77621ef1, 0x775fda9d, - 0x775d95ff, 0x775b5118, - 0x77590be7, 0x7756c66c, 0x775480a8, 0x77523a9b, 0x774ff443, 0x774dada2, - 0x774b66b8, 0x77491f84, - 0x7746d806, 0x7744903f, 0x7742482e, 0x773fffd4, 0x773db730, 0x773b6e42, - 0x7739250b, 0x7736db8b, - 0x773491c0, 0x773247ad, 0x772ffd50, 0x772db2a9, 0x772b67b9, 0x77291c7f, - 0x7726d0fc, 0x7724852f, - 0x77223919, 0x771fecb9, 0x771da010, 0x771b531d, 0x771905e1, 0x7716b85b, - 0x77146a8c, 0x77121c74, - 0x770fce12, 0x770d7f66, 0x770b3072, 0x7708e133, 0x770691ab, 0x770441da, - 0x7701f1c0, 0x76ffa15c, - 0x76fd50ae, 0x76faffb8, 0x76f8ae78, 0x76f65cee, 0x76f40b1b, 0x76f1b8ff, - 0x76ef6699, 0x76ed13ea, - 0x76eac0f2, 0x76e86db0, 0x76e61a25, 0x76e3c650, 0x76e17233, 0x76df1dcb, - 0x76dcc91b, 0x76da7421, - 0x76d81ede, 0x76d5c952, 0x76d3737c, 0x76d11d5d, 0x76cec6f5, 0x76cc7043, - 0x76ca1948, 0x76c7c204, - 0x76c56a77, 0x76c312a0, 0x76c0ba80, 0x76be6217, 0x76bc0965, 0x76b9b069, - 0x76b75724, 0x76b4fd96, - 0x76b2a3bf, 0x76b0499e, 0x76adef34, 0x76ab9481, 0x76a93985, 0x76a6de40, - 0x76a482b1, 0x76a226da, - 0x769fcab9, 0x769d6e4f, 0x769b119b, 0x7698b49f, 0x76965759, 0x7693f9ca, - 0x76919bf3, 0x768f3dd2, - 0x768cdf67, 0x768a80b4, 0x768821b8, 0x7685c272, 0x768362e4, 0x7681030c, - 0x767ea2eb, 0x767c4281, - 0x7679e1ce, 0x767780d2, 0x76751f8d, 0x7672bdfe, 0x76705c27, 0x766dfa07, - 0x766b979d, 0x766934eb, - 0x7666d1ef, 0x76646eab, 0x76620b1d, 0x765fa747, 0x765d4327, 0x765adebe, - 0x76587a0d, 0x76561512, - 0x7653afce, 0x76514a42, 0x764ee46c, 0x764c7e4d, 0x764a17e6, 0x7647b135, - 0x76454a3c, 0x7642e2f9, - 0x76407b6e, 0x763e139a, 0x763bab7c, 0x76394316, 0x7636da67, 0x7634716f, - 0x7632082e, 0x762f9ea4, - 0x762d34d1, 0x762acab6, 0x76286051, 0x7625f5a3, 0x76238aad, 0x76211f6e, - 0x761eb3e6, 0x761c4815, - 0x7619dbfb, 0x76176f98, 0x761502ed, 0x761295f9, 0x761028bb, 0x760dbb35, - 0x760b4d67, 0x7608df4f, - 0x760670ee, 0x76040245, 0x76019353, 0x75ff2418, 0x75fcb495, 0x75fa44c8, - 0x75f7d4b3, 0x75f56455, - 0x75f2f3ae, 0x75f082bf, 0x75ee1187, 0x75eba006, 0x75e92e3c, 0x75e6bc2a, - 0x75e449ce, 0x75e1d72b, - 0x75df643e, 0x75dcf109, 0x75da7d8b, 0x75d809c4, 0x75d595b4, 0x75d3215c, - 0x75d0acbc, 0x75ce37d2, - 0x75cbc2a0, 0x75c94d25, 0x75c6d762, 0x75c46156, 0x75c1eb01, 0x75bf7464, - 0x75bcfd7e, 0x75ba864f, - 0x75b80ed8, 0x75b59718, 0x75b31f0f, 0x75b0a6be, 0x75ae2e25, 0x75abb542, - 0x75a93c18, 0x75a6c2a4, - 0x75a448e8, 0x75a1cee4, 0x759f5496, 0x759cda01, 0x759a5f22, 0x7597e3fc, - 0x7595688c, 0x7592ecd4, - 0x759070d4, 0x758df48b, 0x758b77fa, 0x7588fb20, 0x75867dfd, 0x75840093, - 0x758182df, 0x757f04e3, - 0x757c869f, 0x757a0812, 0x7577893d, 0x75750a1f, 0x75728ab9, 0x75700b0a, - 0x756d8b13, 0x756b0ad3, - 0x75688a4b, 0x7566097b, 0x75638862, 0x75610701, 0x755e8557, 0x755c0365, - 0x7559812b, 0x7556fea8, - 0x75547bdd, 0x7551f8c9, 0x754f756e, 0x754cf1c9, 0x754a6ddd, 0x7547e9a8, - 0x7545652a, 0x7542e065, - 0x75405b57, 0x753dd600, 0x753b5061, 0x7538ca7b, 0x7536444b, 0x7533bdd4, - 0x75313714, 0x752eb00c, - 0x752c28bb, 0x7529a122, 0x75271941, 0x75249118, 0x752208a7, 0x751f7fed, - 0x751cf6eb, 0x751a6da0, - 0x7517e40e, 0x75155a33, 0x7512d010, 0x751045a5, 0x750dbaf2, 0x750b2ff6, - 0x7508a4b2, 0x75061926, - 0x75038d52, 0x75010136, 0x74fe74d1, 0x74fbe825, 0x74f95b30, 0x74f6cdf3, - 0x74f4406d, 0x74f1b2a0, - 0x74ef248b, 0x74ec962d, 0x74ea0787, 0x74e7789a, 0x74e4e964, 0x74e259e6, - 0x74dfca20, 0x74dd3a11, - 0x74daa9bb, 0x74d8191d, 0x74d58836, 0x74d2f708, 0x74d06591, 0x74cdd3d2, - 0x74cb41cc, 0x74c8af7d, - 0x74c61ce6, 0x74c38a07, 0x74c0f6e0, 0x74be6372, 0x74bbcfbb, 0x74b93bbc, - 0x74b6a775, 0x74b412e6, - 0x74b17e0f, 0x74aee8f0, 0x74ac5389, 0x74a9bddb, 0x74a727e4, 0x74a491a5, - 0x74a1fb1e, 0x749f6450, - 0x749ccd39, 0x749a35db, 0x74979e34, 0x74950646, 0x74926e10, 0x748fd592, - 0x748d3ccb, 0x748aa3be, - 0x74880a68, 0x748570ca, 0x7482d6e4, 0x74803cb7, 0x747da242, 0x747b0784, - 0x74786c7f, 0x7475d132, - 0x7473359e, 0x747099c1, 0x746dfd9d, 0x746b6131, 0x7468c47c, 0x74662781, - 0x74638a3d, 0x7460ecb2, - 0x745e4ede, 0x745bb0c3, 0x74591261, 0x745673b6, 0x7453d4c4, 0x7451358a, - 0x744e9608, 0x744bf63e, - 0x7449562d, 0x7446b5d4, 0x74441533, 0x7441744b, 0x743ed31b, 0x743c31a3, - 0x74398fe3, 0x7436eddc, - 0x74344b8d, 0x7431a8f6, 0x742f0618, 0x742c62f2, 0x7429bf84, 0x74271bcf, - 0x742477d2, 0x7421d38e, - 0x741f2f01, 0x741c8a2d, 0x7419e512, 0x74173faf, 0x74149a04, 0x7411f412, - 0x740f4dd8, 0x740ca756, - 0x740a008d, 0x7407597d, 0x7404b224, 0x74020a85, 0x73ff629d, 0x73fcba6e, - 0x73fa11f8, 0x73f7693a, - 0x73f4c034, 0x73f216e7, 0x73ef6d53, 0x73ecc377, 0x73ea1953, 0x73e76ee8, - 0x73e4c435, 0x73e2193b, - 0x73df6df9, 0x73dcc270, 0x73da16a0, 0x73d76a88, 0x73d4be28, 0x73d21182, - 0x73cf6493, 0x73ccb75d, - 0x73ca09e0, 0x73c75c1c, 0x73c4ae10, 0x73c1ffbc, 0x73bf5121, 0x73bca23f, - 0x73b9f315, 0x73b743a4, - 0x73b493ec, 0x73b1e3ec, 0x73af33a5, 0x73ac8316, 0x73a9d240, 0x73a72123, - 0x73a46fbf, 0x73a1be13, - 0x739f0c20, 0x739c59e5, 0x7399a763, 0x7396f49a, 0x73944189, 0x73918e32, - 0x738eda93, 0x738c26ac, - 0x7389727f, 0x7386be0a, 0x7384094e, 0x7381544a, 0x737e9f00, 0x737be96e, - 0x73793395, 0x73767d74, - 0x7373c70d, 0x7371105e, 0x736e5968, 0x736ba22b, 0x7368eaa6, 0x736632db, - 0x73637ac8, 0x7360c26e, - 0x735e09cd, 0x735b50e4, 0x735897b5, 0x7355de3e, 0x73532481, 0x73506a7c, - 0x734db030, 0x734af59d, - 0x73483ac2, 0x73457fa1, 0x7342c438, 0x73400889, 0x733d4c92, 0x733a9054, - 0x7337d3d0, 0x73351704, - 0x733259f1, 0x732f9c97, 0x732cdef6, 0x732a210d, 0x732762de, 0x7324a468, - 0x7321e5ab, 0x731f26a7, - 0x731c675b, 0x7319a7c9, 0x7316e7f0, 0x731427cf, 0x73116768, 0x730ea6ba, - 0x730be5c5, 0x73092489, - 0x73066306, 0x7303a13b, 0x7300df2a, 0x72fe1cd2, 0x72fb5a34, 0x72f8974e, - 0x72f5d421, 0x72f310ad, - 0x72f04cf3, 0x72ed88f1, 0x72eac4a9, 0x72e8001a, 0x72e53b44, 0x72e27627, - 0x72dfb0c3, 0x72dceb18, - 0x72da2526, 0x72d75eee, 0x72d4986f, 0x72d1d1a9, 0x72cf0a9c, 0x72cc4348, - 0x72c97bad, 0x72c6b3cc, - 0x72c3eba4, 0x72c12335, 0x72be5a7f, 0x72bb9183, 0x72b8c83f, 0x72b5feb5, - 0x72b334e4, 0x72b06acd, - 0x72ada06f, 0x72aad5c9, 0x72a80ade, 0x72a53fab, 0x72a27432, 0x729fa872, - 0x729cdc6b, 0x729a101e, - 0x7297438a, 0x729476af, 0x7291a98e, 0x728edc26, 0x728c0e77, 0x72894082, - 0x72867245, 0x7283a3c3, - 0x7280d4f9, 0x727e05e9, 0x727b3693, 0x727866f6, 0x72759712, 0x7272c6e7, - 0x726ff676, 0x726d25bf, - 0x726a54c1, 0x7267837c, 0x7264b1f0, 0x7261e01e, 0x725f0e06, 0x725c3ba7, - 0x72596901, 0x72569615, - 0x7253c2e3, 0x7250ef6a, 0x724e1baa, 0x724b47a4, 0x72487357, 0x72459ec4, - 0x7242c9ea, 0x723ff4ca, - 0x723d1f63, 0x723a49b6, 0x723773c3, 0x72349d89, 0x7231c708, 0x722ef041, - 0x722c1934, 0x722941e0, - 0x72266a46, 0x72239266, 0x7220ba3f, 0x721de1d1, 0x721b091d, 0x72183023, - 0x721556e3, 0x72127d5c, - 0x720fa38e, 0x720cc97b, 0x7209ef21, 0x72071480, 0x7204399a, 0x72015e6d, - 0x71fe82f9, 0x71fba740, - 0x71f8cb40, 0x71f5eefa, 0x71f3126d, 0x71f0359a, 0x71ed5881, 0x71ea7b22, - 0x71e79d7c, 0x71e4bf90, - 0x71e1e15e, 0x71df02e5, 0x71dc2427, 0x71d94522, 0x71d665d6, 0x71d38645, - 0x71d0a66d, 0x71cdc650, - 0x71cae5ec, 0x71c80542, 0x71c52451, 0x71c2431b, 0x71bf619e, 0x71bc7fdb, - 0x71b99dd2, 0x71b6bb83, - 0x71b3d8ed, 0x71b0f612, 0x71ae12f0, 0x71ab2f89, 0x71a84bdb, 0x71a567e7, - 0x71a283ad, 0x719f9f2c, - 0x719cba66, 0x7199d55a, 0x7196f008, 0x71940a6f, 0x71912490, 0x718e3e6c, - 0x718b5801, 0x71887151, - 0x71858a5a, 0x7182a31d, 0x717fbb9a, 0x717cd3d2, 0x7179ebc3, 0x7177036e, - 0x71741ad3, 0x717131f3, - 0x716e48cc, 0x716b5f5f, 0x716875ad, 0x71658bb4, 0x7162a175, 0x715fb6f1, - 0x715ccc26, 0x7159e116, - 0x7156f5c0, 0x71540a24, 0x71511e42, 0x714e321a, 0x714b45ac, 0x714858f8, - 0x71456bfe, 0x71427ebf, - 0x713f9139, 0x713ca36e, 0x7139b55d, 0x7136c706, 0x7133d869, 0x7130e987, - 0x712dfa5e, 0x712b0af0, - 0x71281b3c, 0x71252b42, 0x71223b02, 0x711f4a7d, 0x711c59b2, 0x711968a1, - 0x7116774a, 0x711385ad, - 0x711093cb, 0x710da1a3, 0x710aaf35, 0x7107bc82, 0x7104c989, 0x7101d64a, - 0x70fee2c5, 0x70fbeefb, - 0x70f8faeb, 0x70f60695, 0x70f311fa, 0x70f01d19, 0x70ed27f2, 0x70ea3286, - 0x70e73cd4, 0x70e446dc, - 0x70e1509f, 0x70de5a1c, 0x70db6353, 0x70d86c45, 0x70d574f1, 0x70d27d58, - 0x70cf8579, 0x70cc8d54, - 0x70c994ea, 0x70c69c3a, 0x70c3a345, 0x70c0aa0a, 0x70bdb08a, 0x70bab6c4, - 0x70b7bcb8, 0x70b4c267, - 0x70b1c7d1, 0x70aeccf5, 0x70abd1d3, 0x70a8d66c, 0x70a5dac0, 0x70a2dece, - 0x709fe296, 0x709ce619, - 0x7099e957, 0x7096ec4f, 0x7093ef01, 0x7090f16e, 0x708df396, 0x708af579, - 0x7087f715, 0x7084f86d, - 0x7081f97f, 0x707efa4c, 0x707bfad3, 0x7078fb15, 0x7075fb11, 0x7072fac9, - 0x706ffa3a, 0x706cf967, - 0x7069f84e, 0x7066f6f0, 0x7063f54c, 0x7060f363, 0x705df135, 0x705aeec1, - 0x7057ec08, 0x7054e90a, - 0x7051e5c7, 0x704ee23e, 0x704bde70, 0x7048da5d, 0x7045d604, 0x7042d166, - 0x703fcc83, 0x703cc75b, - 0x7039c1ed, 0x7036bc3b, 0x7033b643, 0x7030b005, 0x702da983, 0x702aa2bb, - 0x70279baf, 0x7024945d, - 0x70218cc6, 0x701e84e9, 0x701b7cc8, 0x70187461, 0x70156bb5, 0x701262c4, - 0x700f598e, 0x700c5013, - 0x70094653, 0x70063c4e, 0x70033203, 0x70002774, 0x6ffd1c9f, 0x6ffa1185, - 0x6ff70626, 0x6ff3fa82, - 0x6ff0ee99, 0x6fede26b, 0x6fead5f8, 0x6fe7c940, 0x6fe4bc43, 0x6fe1af01, - 0x6fdea17a, 0x6fdb93ae, - 0x6fd8859d, 0x6fd57746, 0x6fd268ab, 0x6fcf59cb, 0x6fcc4aa6, 0x6fc93b3c, - 0x6fc62b8d, 0x6fc31b99, - 0x6fc00b60, 0x6fbcfae2, 0x6fb9ea20, 0x6fb6d918, 0x6fb3c7cb, 0x6fb0b63a, - 0x6fada464, 0x6faa9248, - 0x6fa77fe8, 0x6fa46d43, 0x6fa15a59, 0x6f9e472b, 0x6f9b33b7, 0x6f981fff, - 0x6f950c01, 0x6f91f7bf, - 0x6f8ee338, 0x6f8bce6c, 0x6f88b95c, 0x6f85a407, 0x6f828e6c, 0x6f7f788d, - 0x6f7c626a, 0x6f794c01, - 0x6f763554, 0x6f731e62, 0x6f70072b, 0x6f6cefb0, 0x6f69d7f0, 0x6f66bfeb, - 0x6f63a7a1, 0x6f608f13, - 0x6f5d7640, 0x6f5a5d28, 0x6f5743cb, 0x6f542a2a, 0x6f511044, 0x6f4df61a, - 0x6f4adbab, 0x6f47c0f7, - 0x6f44a5ff, 0x6f418ac2, 0x6f3e6f40, 0x6f3b537a, 0x6f38376f, 0x6f351b1f, - 0x6f31fe8b, 0x6f2ee1b2, - 0x6f2bc495, 0x6f28a733, 0x6f25898d, 0x6f226ba2, 0x6f1f4d72, 0x6f1c2efe, - 0x6f191045, 0x6f15f148, - 0x6f12d206, 0x6f0fb280, 0x6f0c92b6, 0x6f0972a6, 0x6f065253, 0x6f0331ba, - 0x6f0010de, 0x6efcefbd, - 0x6ef9ce57, 0x6ef6acad, 0x6ef38abe, 0x6ef0688b, 0x6eed4614, 0x6eea2358, - 0x6ee70058, 0x6ee3dd13, - 0x6ee0b98a, 0x6edd95bd, 0x6eda71ab, 0x6ed74d55, 0x6ed428ba, 0x6ed103db, - 0x6ecddeb8, 0x6ecab950, - 0x6ec793a4, 0x6ec46db4, 0x6ec1477f, 0x6ebe2106, 0x6ebafa49, 0x6eb7d347, - 0x6eb4ac02, 0x6eb18477, - 0x6eae5ca9, 0x6eab3496, 0x6ea80c3f, 0x6ea4e3a4, 0x6ea1bac4, 0x6e9e91a1, - 0x6e9b6839, 0x6e983e8d, - 0x6e95149c, 0x6e91ea67, 0x6e8ebfef, 0x6e8b9532, 0x6e886a30, 0x6e853eeb, - 0x6e821361, 0x6e7ee794, - 0x6e7bbb82, 0x6e788f2c, 0x6e756291, 0x6e7235b3, 0x6e6f0890, 0x6e6bdb2a, - 0x6e68ad7f, 0x6e657f90, - 0x6e62515d, 0x6e5f22e6, 0x6e5bf42b, 0x6e58c52c, 0x6e5595e9, 0x6e526662, - 0x6e4f3696, 0x6e4c0687, - 0x6e48d633, 0x6e45a59c, 0x6e4274c1, 0x6e3f43a1, 0x6e3c123e, 0x6e38e096, - 0x6e35aeab, 0x6e327c7b, - 0x6e2f4a08, 0x6e2c1750, 0x6e28e455, 0x6e25b115, 0x6e227d92, 0x6e1f49cb, - 0x6e1c15c0, 0x6e18e171, - 0x6e15acde, 0x6e127807, 0x6e0f42ec, 0x6e0c0d8e, 0x6e08d7eb, 0x6e05a205, - 0x6e026bda, 0x6dff356c, - 0x6dfbfeba, 0x6df8c7c4, 0x6df5908b, 0x6df2590d, 0x6def214c, 0x6debe947, - 0x6de8b0fe, 0x6de57871, - 0x6de23fa0, 0x6ddf068c, 0x6ddbcd34, 0x6dd89398, 0x6dd559b9, 0x6dd21f95, - 0x6dcee52e, 0x6dcbaa83, - 0x6dc86f95, 0x6dc53462, 0x6dc1f8ec, 0x6dbebd33, 0x6dbb8135, 0x6db844f4, - 0x6db5086f, 0x6db1cba7, - 0x6dae8e9b, 0x6dab514b, 0x6da813b8, 0x6da4d5e1, 0x6da197c6, 0x6d9e5968, - 0x6d9b1ac6, 0x6d97dbe0, - 0x6d949cb7, 0x6d915d4a, 0x6d8e1d9a, 0x6d8adda6, 0x6d879d6e, 0x6d845cf3, - 0x6d811c35, 0x6d7ddb33, - 0x6d7a99ed, 0x6d775864, 0x6d741697, 0x6d70d487, 0x6d6d9233, 0x6d6a4f9c, - 0x6d670cc1, 0x6d63c9a3, - 0x6d608641, 0x6d5d429c, 0x6d59feb3, 0x6d56ba87, 0x6d537617, 0x6d503164, - 0x6d4cec6e, 0x6d49a734, - 0x6d4661b7, 0x6d431bf6, 0x6d3fd5f2, 0x6d3c8fab, 0x6d394920, 0x6d360252, - 0x6d32bb40, 0x6d2f73eb, - 0x6d2c2c53, 0x6d28e477, 0x6d259c58, 0x6d2253f6, 0x6d1f0b50, 0x6d1bc267, - 0x6d18793b, 0x6d152fcc, - 0x6d11e619, 0x6d0e9c23, 0x6d0b51e9, 0x6d08076d, 0x6d04bcad, 0x6d0171aa, - 0x6cfe2663, 0x6cfadada, - 0x6cf78f0d, 0x6cf442fd, 0x6cf0f6aa, 0x6cedaa13, 0x6cea5d3a, 0x6ce7101d, - 0x6ce3c2bd, 0x6ce0751a, - 0x6cdd2733, 0x6cd9d90a, 0x6cd68a9d, 0x6cd33bed, 0x6ccfecfa, 0x6ccc9dc4, - 0x6cc94e4b, 0x6cc5fe8f, - 0x6cc2ae90, 0x6cbf5e4d, 0x6cbc0dc8, 0x6cb8bcff, 0x6cb56bf4, 0x6cb21aa5, - 0x6caec913, 0x6cab773e, - 0x6ca82527, 0x6ca4d2cc, 0x6ca1802e, 0x6c9e2d4d, 0x6c9ada29, 0x6c9786c2, - 0x6c943318, 0x6c90df2c, - 0x6c8d8afc, 0x6c8a3689, 0x6c86e1d3, 0x6c838cdb, 0x6c80379f, 0x6c7ce220, - 0x6c798c5f, 0x6c76365b, - 0x6c72e013, 0x6c6f8989, 0x6c6c32bc, 0x6c68dbac, 0x6c658459, 0x6c622cc4, - 0x6c5ed4eb, 0x6c5b7cd0, - 0x6c582472, 0x6c54cbd1, 0x6c5172ed, 0x6c4e19c6, 0x6c4ac05d, 0x6c4766b0, - 0x6c440cc1, 0x6c40b28f, - 0x6c3d581b, 0x6c39fd63, 0x6c36a269, 0x6c33472c, 0x6c2febad, 0x6c2c8fea, - 0x6c2933e5, 0x6c25d79d, - 0x6c227b13, 0x6c1f1e45, 0x6c1bc136, 0x6c1863e3, 0x6c15064e, 0x6c11a876, - 0x6c0e4a5b, 0x6c0aebfe, - 0x6c078d5e, 0x6c042e7b, 0x6c00cf56, 0x6bfd6fee, 0x6bfa1044, 0x6bf6b056, - 0x6bf35027, 0x6befefb5, - 0x6bec8f00, 0x6be92e08, 0x6be5ccce, 0x6be26b52, 0x6bdf0993, 0x6bdba791, - 0x6bd8454d, 0x6bd4e2c6, - 0x6bd17ffd, 0x6bce1cf1, 0x6bcab9a3, 0x6bc75613, 0x6bc3f23f, 0x6bc08e2a, - 0x6bbd29d2, 0x6bb9c537, - 0x6bb6605a, 0x6bb2fb3b, 0x6baf95d9, 0x6bac3034, 0x6ba8ca4e, 0x6ba56425, - 0x6ba1fdb9, 0x6b9e970b, - 0x6b9b301b, 0x6b97c8e8, 0x6b946173, 0x6b90f9bc, 0x6b8d91c2, 0x6b8a2986, - 0x6b86c107, 0x6b835846, - 0x6b7fef43, 0x6b7c85fe, 0x6b791c76, 0x6b75b2ac, 0x6b7248a0, 0x6b6ede51, - 0x6b6b73c0, 0x6b6808ed, - 0x6b649dd8, 0x6b613280, 0x6b5dc6e6, 0x6b5a5b0a, 0x6b56eeec, 0x6b53828b, - 0x6b5015e9, 0x6b4ca904, - 0x6b493bdd, 0x6b45ce73, 0x6b4260c8, 0x6b3ef2da, 0x6b3b84ab, 0x6b381639, - 0x6b34a785, 0x6b31388e, - 0x6b2dc956, 0x6b2a59dc, 0x6b26ea1f, 0x6b237a21, 0x6b2009e0, 0x6b1c995d, - 0x6b192898, 0x6b15b791, - 0x6b124648, 0x6b0ed4bd, 0x6b0b62f0, 0x6b07f0e1, 0x6b047e90, 0x6b010bfd, - 0x6afd9928, 0x6afa2610, - 0x6af6b2b7, 0x6af33f1c, 0x6aefcb3f, 0x6aec5720, 0x6ae8e2bf, 0x6ae56e1c, - 0x6ae1f937, 0x6ade8410, - 0x6adb0ea8, 0x6ad798fd, 0x6ad42311, 0x6ad0ace2, 0x6acd3672, 0x6ac9bfc0, - 0x6ac648cb, 0x6ac2d195, - 0x6abf5a1e, 0x6abbe264, 0x6ab86a68, 0x6ab4f22b, 0x6ab179ac, 0x6aae00eb, - 0x6aaa87e8, 0x6aa70ea4, - 0x6aa3951d, 0x6aa01b55, 0x6a9ca14b, 0x6a992700, 0x6a95ac72, 0x6a9231a3, - 0x6a8eb692, 0x6a8b3b3f, - 0x6a87bfab, 0x6a8443d5, 0x6a80c7bd, 0x6a7d4b64, 0x6a79cec8, 0x6a7651ec, - 0x6a72d4cd, 0x6a6f576d, - 0x6a6bd9cb, 0x6a685be8, 0x6a64ddc2, 0x6a615f5c, 0x6a5de0b3, 0x6a5a61c9, - 0x6a56e29e, 0x6a536331, - 0x6a4fe382, 0x6a4c6391, 0x6a48e360, 0x6a4562ec, 0x6a41e237, 0x6a3e6140, - 0x6a3ae008, 0x6a375e8f, - 0x6a33dcd4, 0x6a305ad7, 0x6a2cd899, 0x6a295619, 0x6a25d358, 0x6a225055, - 0x6a1ecd11, 0x6a1b498c, - 0x6a17c5c5, 0x6a1441bc, 0x6a10bd72, 0x6a0d38e7, 0x6a09b41a, 0x6a062f0c, - 0x6a02a9bc, 0x69ff242b, - 0x69fb9e59, 0x69f81845, 0x69f491f0, 0x69f10b5a, 0x69ed8482, 0x69e9fd69, - 0x69e6760f, 0x69e2ee73, - 0x69df6696, 0x69dbde77, 0x69d85618, 0x69d4cd77, 0x69d14494, 0x69cdbb71, - 0x69ca320c, 0x69c6a866, - 0x69c31e7f, 0x69bf9456, 0x69bc09ec, 0x69b87f41, 0x69b4f455, 0x69b16928, - 0x69adddb9, 0x69aa5209, - 0x69a6c618, 0x69a339e6, 0x699fad73, 0x699c20be, 0x699893c9, 0x69950692, - 0x6991791a, 0x698deb61, - 0x698a5d67, 0x6986cf2c, 0x698340af, 0x697fb1f2, 0x697c22f3, 0x697893b4, - 0x69750433, 0x69717472, - 0x696de46f, 0x696a542b, 0x6966c3a6, 0x696332e1, 0x695fa1da, 0x695c1092, - 0x69587f09, 0x6954ed40, - 0x69515b35, 0x694dc8e9, 0x694a365c, 0x6946a38f, 0x69431080, 0x693f7d31, - 0x693be9a0, 0x693855cf, - 0x6934c1bd, 0x69312d6a, 0x692d98d6, 0x692a0401, 0x69266eeb, 0x6922d995, - 0x691f43fd, 0x691bae25, - 0x6918180c, 0x691481b2, 0x6910eb17, 0x690d543b, 0x6909bd1f, 0x690625c2, - 0x69028e24, 0x68fef645, - 0x68fb5e25, 0x68f7c5c5, 0x68f42d24, 0x68f09442, 0x68ecfb20, 0x68e961bd, - 0x68e5c819, 0x68e22e34, - 0x68de940f, 0x68daf9a9, 0x68d75f02, 0x68d3c41b, 0x68d028f2, 0x68cc8d8a, - 0x68c8f1e0, 0x68c555f6, - 0x68c1b9cc, 0x68be1d61, 0x68ba80b5, 0x68b6e3c8, 0x68b3469b, 0x68afa92e, - 0x68ac0b7f, 0x68a86d91, - 0x68a4cf61, 0x68a130f1, 0x689d9241, 0x6899f350, 0x6896541f, 0x6892b4ad, - 0x688f14fa, 0x688b7507, - 0x6887d4d4, 0x68843460, 0x688093ab, 0x687cf2b6, 0x68795181, 0x6875b00b, - 0x68720e55, 0x686e6c5e, - 0x686aca27, 0x686727b0, 0x686384f8, 0x685fe200, 0x685c3ec7, 0x68589b4e, - 0x6854f795, 0x6851539b, - 0x684daf61, 0x684a0ae6, 0x6846662c, 0x6842c131, 0x683f1bf5, 0x683b7679, - 0x6837d0bd, 0x68342ac1, - 0x68308485, 0x682cde08, 0x6829374b, 0x6825904d, 0x6821e910, 0x681e4192, - 0x681a99d4, 0x6816f1d6, - 0x68134997, 0x680fa118, 0x680bf85a, 0x68084f5a, 0x6804a61b, 0x6800fc9c, - 0x67fd52dc, 0x67f9a8dd, - 0x67f5fe9d, 0x67f2541d, 0x67eea95d, 0x67eafe5d, 0x67e7531c, 0x67e3a79c, - 0x67dffbdc, 0x67dc4fdb, - 0x67d8a39a, 0x67d4f71a, 0x67d14a59, 0x67cd9d58, 0x67c9f017, 0x67c64297, - 0x67c294d6, 0x67bee6d5, - 0x67bb3894, 0x67b78a13, 0x67b3db53, 0x67b02c52, 0x67ac7d11, 0x67a8cd91, - 0x67a51dd0, 0x67a16dcf, - 0x679dbd8f, 0x679a0d0f, 0x67965c4e, 0x6792ab4e, 0x678efa0e, 0x678b488e, - 0x678796ce, 0x6783e4cf, - 0x6780328f, 0x677c8010, 0x6778cd50, 0x67751a51, 0x67716713, 0x676db394, - 0x6769ffd5, 0x67664bd7, - 0x67629799, 0x675ee31b, 0x675b2e5e, 0x67577960, 0x6753c423, 0x67500ea7, - 0x674c58ea, 0x6748a2ee, - 0x6744ecb2, 0x67413636, 0x673d7f7b, 0x6739c880, 0x67361145, 0x673259ca, - 0x672ea210, 0x672aea17, - 0x672731dd, 0x67237964, 0x671fc0ac, 0x671c07b4, 0x67184e7c, 0x67149504, - 0x6710db4d, 0x670d2157, - 0x67096721, 0x6705acab, 0x6701f1f6, 0x66fe3701, 0x66fa7bcd, 0x66f6c059, - 0x66f304a6, 0x66ef48b3, - 0x66eb8c80, 0x66e7d00f, 0x66e4135d, 0x66e0566c, 0x66dc993c, 0x66d8dbcd, - 0x66d51e1d, 0x66d1602f, - 0x66cda201, 0x66c9e393, 0x66c624e7, 0x66c265fa, 0x66bea6cf, 0x66bae764, - 0x66b727ba, 0x66b367d0, - 0x66afa7a7, 0x66abe73f, 0x66a82697, 0x66a465b0, 0x66a0a489, 0x669ce324, - 0x6699217f, 0x66955f9b, - 0x66919d77, 0x668ddb14, 0x668a1872, 0x66865591, 0x66829270, 0x667ecf11, - 0x667b0b72, 0x66774793, - 0x66738376, 0x666fbf19, 0x666bfa7d, 0x666835a2, 0x66647088, 0x6660ab2f, - 0x665ce596, 0x66591fbf, - 0x665559a8, 0x66519352, 0x664dccbd, 0x664a05e9, 0x66463ed6, 0x66427784, - 0x663eaff2, 0x663ae822, - 0x66372012, 0x663357c4, 0x662f8f36, 0x662bc66a, 0x6627fd5e, 0x66243413, - 0x66206a8a, 0x661ca0c1, - 0x6618d6b9, 0x66150c73, 0x661141ed, 0x660d7729, 0x6609ac25, 0x6605e0e3, - 0x66021561, 0x65fe49a1, - 0x65fa7da2, 0x65f6b164, 0x65f2e4e7, 0x65ef182b, 0x65eb4b30, 0x65e77df6, - 0x65e3b07e, 0x65dfe2c6, - 0x65dc14d0, 0x65d8469b, 0x65d47827, 0x65d0a975, 0x65ccda83, 0x65c90b53, - 0x65c53be4, 0x65c16c36, - 0x65bd9c49, 0x65b9cc1e, 0x65b5fbb4, 0x65b22b0b, 0x65ae5a23, 0x65aa88fd, - 0x65a6b798, 0x65a2e5f4, - 0x659f1412, 0x659b41f1, 0x65976f91, 0x65939cf3, 0x658fca15, 0x658bf6fa, - 0x6588239f, 0x65845006, - 0x65807c2f, 0x657ca818, 0x6578d3c4, 0x6574ff30, 0x65712a5e, 0x656d554d, - 0x65697ffe, 0x6565aa71, - 0x6561d4a4, 0x655dfe99, 0x655a2850, 0x655651c8, 0x65527b02, 0x654ea3fd, - 0x654accba, 0x6546f538, - 0x65431d77, 0x653f4579, 0x653b6d3b, 0x653794c0, 0x6533bc06, 0x652fe30d, - 0x652c09d6, 0x65283061, - 0x652456ad, 0x65207cbb, 0x651ca28a, 0x6518c81b, 0x6514ed6e, 0x65111283, - 0x650d3759, 0x65095bf0, - 0x6505804a, 0x6501a465, 0x64fdc841, 0x64f9ebe0, 0x64f60f40, 0x64f23262, - 0x64ee5546, 0x64ea77eb, - 0x64e69a52, 0x64e2bc7b, 0x64dede66, 0x64db0012, 0x64d72180, 0x64d342b0, - 0x64cf63a2, 0x64cb8456, - 0x64c7a4cb, 0x64c3c502, 0x64bfe4fc, 0x64bc04b6, 0x64b82433, 0x64b44372, - 0x64b06273, 0x64ac8135, - 0x64a89fba, 0x64a4be00, 0x64a0dc08, 0x649cf9d2, 0x6499175e, 0x649534ac, - 0x649151bc, 0x648d6e8e, - 0x64898b22, 0x6485a778, 0x6481c390, 0x647ddf6a, 0x6479fb06, 0x64761664, - 0x64723184, 0x646e4c66, - 0x646a670a, 0x64668170, 0x64629b98, 0x645eb582, 0x645acf2e, 0x6456e89d, - 0x645301cd, 0x644f1ac0, - 0x644b3375, 0x64474bec, 0x64436425, 0x643f7c20, 0x643b93dd, 0x6437ab5d, - 0x6433c29f, 0x642fd9a3, - 0x642bf069, 0x642806f1, 0x64241d3c, 0x64203348, 0x641c4917, 0x64185ea9, - 0x641473fc, 0x64108912, - 0x640c9dea, 0x6408b284, 0x6404c6e1, 0x6400db00, 0x63fceee1, 0x63f90285, - 0x63f515eb, 0x63f12913, - 0x63ed3bfd, 0x63e94eaa, 0x63e5611a, 0x63e1734b, 0x63dd853f, 0x63d996f6, - 0x63d5a86f, 0x63d1b9aa, - 0x63cdcaa8, 0x63c9db68, 0x63c5ebeb, 0x63c1fc30, 0x63be0c37, 0x63ba1c01, - 0x63b62b8e, 0x63b23add, - 0x63ae49ee, 0x63aa58c2, 0x63a66759, 0x63a275b2, 0x639e83cd, 0x639a91ac, - 0x63969f4c, 0x6392acaf, - 0x638eb9d5, 0x638ac6be, 0x6386d369, 0x6382dfd6, 0x637eec07, 0x637af7fa, - 0x637703af, 0x63730f27, - 0x636f1a62, 0x636b2560, 0x63673020, 0x63633aa3, 0x635f44e8, 0x635b4ef0, - 0x635758bb, 0x63536249, - 0x634f6b99, 0x634b74ad, 0x63477d82, 0x6343861b, 0x633f8e76, 0x633b9695, - 0x63379e76, 0x6333a619, - 0x632fad80, 0x632bb4a9, 0x6327bb96, 0x6323c245, 0x631fc8b7, 0x631bceeb, - 0x6317d4e3, 0x6313da9e, - 0x630fe01b, 0x630be55b, 0x6307ea5e, 0x6303ef25, 0x62fff3ae, 0x62fbf7fa, - 0x62f7fc08, 0x62f3ffda, - 0x62f0036f, 0x62ec06c7, 0x62e809e2, 0x62e40cbf, 0x62e00f60, 0x62dc11c4, - 0x62d813eb, 0x62d415d4, - 0x62d01781, 0x62cc18f1, 0x62c81a24, 0x62c41b1a, 0x62c01bd3, 0x62bc1c4f, - 0x62b81c8f, 0x62b41c91, - 0x62b01c57, 0x62ac1bdf, 0x62a81b2b, 0x62a41a3a, 0x62a0190c, 0x629c17a1, - 0x629815fa, 0x62941415, - 0x629011f4, 0x628c0f96, 0x62880cfb, 0x62840a23, 0x6280070f, 0x627c03be, - 0x62780030, 0x6273fc65, - 0x626ff85e, 0x626bf41a, 0x6267ef99, 0x6263eadc, 0x625fe5e1, 0x625be0ab, - 0x6257db37, 0x6253d587, - 0x624fcf9a, 0x624bc970, 0x6247c30a, 0x6243bc68, 0x623fb588, 0x623bae6c, - 0x6237a714, 0x62339f7e, - 0x622f97ad, 0x622b8f9e, 0x62278754, 0x62237ecc, 0x621f7608, 0x621b6d08, - 0x621763cb, 0x62135a51, - 0x620f509b, 0x620b46a9, 0x62073c7a, 0x6203320e, 0x61ff2766, 0x61fb1c82, - 0x61f71161, 0x61f30604, - 0x61eefa6b, 0x61eaee95, 0x61e6e282, 0x61e2d633, 0x61dec9a8, 0x61dabce0, - 0x61d6afdd, 0x61d2a29c, - 0x61ce9520, 0x61ca8767, 0x61c67971, 0x61c26b40, 0x61be5cd2, 0x61ba4e28, - 0x61b63f41, 0x61b2301e, - 0x61ae20bf, 0x61aa1124, 0x61a6014d, 0x61a1f139, 0x619de0e9, 0x6199d05d, - 0x6195bf94, 0x6191ae90, - 0x618d9d4f, 0x61898bd2, 0x61857a19, 0x61816824, 0x617d55f2, 0x61794385, - 0x617530db, 0x61711df5, - 0x616d0ad3, 0x6168f775, 0x6164e3db, 0x6160d005, 0x615cbbf3, 0x6158a7a4, - 0x6154931a, 0x61507e54, - 0x614c6951, 0x61485413, 0x61443e98, 0x614028e2, 0x613c12f0, 0x6137fcc1, - 0x6133e657, 0x612fcfb0, - 0x612bb8ce, 0x6127a1b0, 0x61238a56, 0x611f72c0, 0x611b5aee, 0x611742e0, - 0x61132a96, 0x610f1210, - 0x610af94f, 0x6106e051, 0x6102c718, 0x60feada3, 0x60fa93f2, 0x60f67a05, - 0x60f25fdd, 0x60ee4579, - 0x60ea2ad8, 0x60e60ffd, 0x60e1f4e5, 0x60ddd991, 0x60d9be02, 0x60d5a237, - 0x60d18631, 0x60cd69ee, - 0x60c94d70, 0x60c530b6, 0x60c113c1, 0x60bcf690, 0x60b8d923, 0x60b4bb7a, - 0x60b09d96, 0x60ac7f76, - 0x60a8611b, 0x60a44284, 0x60a023b1, 0x609c04a3, 0x6097e559, 0x6093c5d3, - 0x608fa612, 0x608b8616, - 0x608765dd, 0x6083456a, 0x607f24ba, 0x607b03d0, 0x6076e2a9, 0x6072c148, - 0x606e9faa, 0x606a7dd2, - 0x60665bbd, 0x6062396e, 0x605e16e2, 0x6059f41c, 0x6055d11a, 0x6051addc, - 0x604d8a63, 0x604966af, - 0x604542bf, 0x60411e94, 0x603cfa2e, 0x6038d58c, 0x6034b0af, 0x60308b97, - 0x602c6643, 0x602840b4, - 0x60241ae9, 0x601ff4e3, 0x601bcea2, 0x6017a826, 0x6013816e, 0x600f5a7b, - 0x600b334d, 0x60070be4, - 0x6002e43f, 0x5ffebc5f, 0x5ffa9444, 0x5ff66bee, 0x5ff2435d, 0x5fee1a90, - 0x5fe9f188, 0x5fe5c845, - 0x5fe19ec7, 0x5fdd750e, 0x5fd94b19, 0x5fd520ea, 0x5fd0f67f, 0x5fcccbd9, - 0x5fc8a0f8, 0x5fc475dc, - 0x5fc04a85, 0x5fbc1ef3, 0x5fb7f326, 0x5fb3c71e, 0x5faf9adb, 0x5fab6e5d, - 0x5fa741a3, 0x5fa314af, - 0x5f9ee780, 0x5f9aba16, 0x5f968c70, 0x5f925e90, 0x5f8e3075, 0x5f8a021f, - 0x5f85d38e, 0x5f81a4c2, - 0x5f7d75bb, 0x5f794679, 0x5f7516fd, 0x5f70e745, 0x5f6cb753, 0x5f688726, - 0x5f6456be, 0x5f60261b, - 0x5f5bf53d, 0x5f57c424, 0x5f5392d1, 0x5f4f6143, 0x5f4b2f7a, 0x5f46fd76, - 0x5f42cb37, 0x5f3e98be, - 0x5f3a660a, 0x5f36331b, 0x5f31fff1, 0x5f2dcc8d, 0x5f2998ee, 0x5f256515, - 0x5f213100, 0x5f1cfcb1, - 0x5f18c827, 0x5f149363, 0x5f105e64, 0x5f0c292a, 0x5f07f3b6, 0x5f03be07, - 0x5eff881d, 0x5efb51f9, - 0x5ef71b9b, 0x5ef2e501, 0x5eeeae2d, 0x5eea771f, 0x5ee63fd6, 0x5ee20853, - 0x5eddd094, 0x5ed9989c, - 0x5ed56069, 0x5ed127fb, 0x5eccef53, 0x5ec8b671, 0x5ec47d54, 0x5ec043fc, - 0x5ebc0a6a, 0x5eb7d09e, - 0x5eb39697, 0x5eaf5c56, 0x5eab21da, 0x5ea6e724, 0x5ea2ac34, 0x5e9e7109, - 0x5e9a35a4, 0x5e95fa05, - 0x5e91be2b, 0x5e8d8217, 0x5e8945c8, 0x5e85093f, 0x5e80cc7c, 0x5e7c8f7f, - 0x5e785247, 0x5e7414d5, - 0x5e6fd729, 0x5e6b9943, 0x5e675b22, 0x5e631cc7, 0x5e5ede32, 0x5e5a9f62, - 0x5e566059, 0x5e522115, - 0x5e4de197, 0x5e49a1df, 0x5e4561ed, 0x5e4121c0, 0x5e3ce15a, 0x5e38a0b9, - 0x5e345fde, 0x5e301ec9, - 0x5e2bdd7a, 0x5e279bf1, 0x5e235a2e, 0x5e1f1830, 0x5e1ad5f9, 0x5e169388, - 0x5e1250dc, 0x5e0e0df7, - 0x5e09cad7, 0x5e05877e, 0x5e0143ea, 0x5dfd001d, 0x5df8bc15, 0x5df477d4, - 0x5df03359, 0x5debeea3, - 0x5de7a9b4, 0x5de3648b, 0x5ddf1f28, 0x5ddad98b, 0x5dd693b4, 0x5dd24da3, - 0x5dce0759, 0x5dc9c0d4, - 0x5dc57a16, 0x5dc1331d, 0x5dbcebeb, 0x5db8a480, 0x5db45cda, 0x5db014fa, - 0x5dabcce1, 0x5da7848e, - 0x5da33c01, 0x5d9ef33b, 0x5d9aaa3a, 0x5d966100, 0x5d92178d, 0x5d8dcddf, - 0x5d8983f8, 0x5d8539d7, - 0x5d80ef7c, 0x5d7ca4e8, 0x5d785a1a, 0x5d740f12, 0x5d6fc3d1, 0x5d6b7856, - 0x5d672ca2, 0x5d62e0b4, - 0x5d5e948c, 0x5d5a482a, 0x5d55fb90, 0x5d51aebb, 0x5d4d61ad, 0x5d491465, - 0x5d44c6e4, 0x5d40792a, - 0x5d3c2b35, 0x5d37dd08, 0x5d338ea0, 0x5d2f4000, 0x5d2af125, 0x5d26a212, - 0x5d2252c5, 0x5d1e033e, - 0x5d19b37e, 0x5d156385, 0x5d111352, 0x5d0cc2e5, 0x5d087240, 0x5d042161, - 0x5cffd048, 0x5cfb7ef7, - 0x5cf72d6b, 0x5cf2dba7, 0x5cee89a9, 0x5cea3772, 0x5ce5e501, 0x5ce19258, - 0x5cdd3f75, 0x5cd8ec58, - 0x5cd49903, 0x5cd04574, 0x5ccbf1ab, 0x5cc79daa, 0x5cc3496f, 0x5cbef4fc, - 0x5cbaa04f, 0x5cb64b68, - 0x5cb1f649, 0x5cada0f0, 0x5ca94b5e, 0x5ca4f594, 0x5ca09f8f, 0x5c9c4952, - 0x5c97f2dc, 0x5c939c2c, - 0x5c8f4544, 0x5c8aee22, 0x5c8696c7, 0x5c823f34, 0x5c7de767, 0x5c798f61, - 0x5c753722, 0x5c70deaa, - 0x5c6c85f9, 0x5c682d0f, 0x5c63d3eb, 0x5c5f7a8f, 0x5c5b20fa, 0x5c56c72c, - 0x5c526d25, 0x5c4e12e5, - 0x5c49b86d, 0x5c455dbb, 0x5c4102d0, 0x5c3ca7ad, 0x5c384c50, 0x5c33f0bb, - 0x5c2f94ec, 0x5c2b38e5, - 0x5c26dca5, 0x5c22802c, 0x5c1e237b, 0x5c19c690, 0x5c15696d, 0x5c110c11, - 0x5c0cae7c, 0x5c0850ae, - 0x5c03f2a8, 0x5bff9469, 0x5bfb35f1, 0x5bf6d740, 0x5bf27857, 0x5bee1935, - 0x5be9b9da, 0x5be55a46, - 0x5be0fa7a, 0x5bdc9a75, 0x5bd83a37, 0x5bd3d9c1, 0x5bcf7912, 0x5bcb182b, - 0x5bc6b70b, 0x5bc255b2, - 0x5bbdf421, 0x5bb99257, 0x5bb53054, 0x5bb0ce19, 0x5bac6ba6, 0x5ba808f9, - 0x5ba3a615, 0x5b9f42f7, - 0x5b9adfa2, 0x5b967c13, 0x5b92184d, 0x5b8db44d, 0x5b895016, 0x5b84eba6, - 0x5b8086fd, 0x5b7c221c, - 0x5b77bd02, 0x5b7357b0, 0x5b6ef226, 0x5b6a8c63, 0x5b662668, 0x5b61c035, - 0x5b5d59c9, 0x5b58f324, - 0x5b548c48, 0x5b502533, 0x5b4bbde6, 0x5b475660, 0x5b42eea2, 0x5b3e86ac, - 0x5b3a1e7e, 0x5b35b617, - 0x5b314d78, 0x5b2ce4a1, 0x5b287b91, 0x5b241249, 0x5b1fa8c9, 0x5b1b3f11, - 0x5b16d521, 0x5b126af8, - 0x5b0e0098, 0x5b0995ff, 0x5b052b2e, 0x5b00c025, 0x5afc54e3, 0x5af7e96a, - 0x5af37db8, 0x5aef11cf, - 0x5aeaa5ad, 0x5ae63953, 0x5ae1ccc1, 0x5add5ff7, 0x5ad8f2f5, 0x5ad485bb, - 0x5ad01849, 0x5acbaa9f, - 0x5ac73cbd, 0x5ac2cea3, 0x5abe6050, 0x5ab9f1c6, 0x5ab58304, 0x5ab1140a, - 0x5aaca4d8, 0x5aa8356f, - 0x5aa3c5cd, 0x5a9f55f3, 0x5a9ae5e2, 0x5a967598, 0x5a920517, 0x5a8d945d, - 0x5a89236c, 0x5a84b243, - 0x5a8040e3, 0x5a7bcf4a, 0x5a775d7a, 0x5a72eb71, 0x5a6e7931, 0x5a6a06ba, - 0x5a65940a, 0x5a612123, - 0x5a5cae04, 0x5a583aad, 0x5a53c71e, 0x5a4f5358, 0x5a4adf5a, 0x5a466b24, - 0x5a41f6b7, 0x5a3d8212, - 0x5a390d35, 0x5a349821, 0x5a3022d5, 0x5a2bad51, 0x5a273796, 0x5a22c1a3, - 0x5a1e4b79, 0x5a19d517, - 0x5a155e7d, 0x5a10e7ac, 0x5a0c70a3, 0x5a07f963, 0x5a0381eb, 0x59ff0a3c, - 0x59fa9255, 0x59f61a36, - 0x59f1a1e0, 0x59ed2953, 0x59e8b08e, 0x59e43792, 0x59dfbe5e, 0x59db44f3, - 0x59d6cb50, 0x59d25176, - 0x59cdd765, 0x59c95d1c, 0x59c4e29c, 0x59c067e4, 0x59bbecf5, 0x59b771cf, - 0x59b2f671, 0x59ae7add, - 0x59a9ff10, 0x59a5830d, 0x59a106d2, 0x599c8a60, 0x59980db6, 0x599390d5, - 0x598f13bd, 0x598a966e, - 0x598618e8, 0x59819b2a, 0x597d1d35, 0x59789f09, 0x597420a6, 0x596fa20b, - 0x596b233a, 0x5966a431, - 0x596224f1, 0x595da57a, 0x595925cc, 0x5954a5e6, 0x595025ca, 0x594ba576, - 0x594724ec, 0x5942a42a, - 0x593e2331, 0x5939a202, 0x5935209b, 0x59309efd, 0x592c1d28, 0x59279b1c, - 0x592318d9, 0x591e9660, - 0x591a13af, 0x591590c7, 0x59110da8, 0x590c8a53, 0x590806c6, 0x59038302, - 0x58feff08, 0x58fa7ad7, - 0x58f5f66e, 0x58f171cf, 0x58ececf9, 0x58e867ed, 0x58e3e2a9, 0x58df5d2e, - 0x58dad77d, 0x58d65195, - 0x58d1cb76, 0x58cd4520, 0x58c8be94, 0x58c437d1, 0x58bfb0d7, 0x58bb29a6, - 0x58b6a23e, 0x58b21aa0, - 0x58ad92cb, 0x58a90ac0, 0x58a4827d, 0x589ffa04, 0x589b7155, 0x5896e86f, - 0x58925f52, 0x588dd5fe, - 0x58894c74, 0x5884c2b3, 0x588038bb, 0x587bae8d, 0x58772429, 0x5872998e, - 0x586e0ebc, 0x586983b4, - 0x5864f875, 0x58606d00, 0x585be154, 0x58575571, 0x5852c958, 0x584e3d09, - 0x5849b083, 0x584523c7, - 0x584096d4, 0x583c09ab, 0x58377c4c, 0x5832eeb6, 0x582e60e9, 0x5829d2e6, - 0x582544ad, 0x5820b63e, - 0x581c2798, 0x581798bb, 0x581309a9, 0x580e7a60, 0x5809eae1, 0x58055b2b, - 0x5800cb3f, 0x57fc3b1d, - 0x57f7aac5, 0x57f31a36, 0x57ee8971, 0x57e9f876, 0x57e56744, 0x57e0d5dd, - 0x57dc443f, 0x57d7b26b, - 0x57d32061, 0x57ce8e20, 0x57c9fbaa, 0x57c568fd, 0x57c0d61a, 0x57bc4301, - 0x57b7afb2, 0x57b31c2d, - 0x57ae8872, 0x57a9f480, 0x57a56059, 0x57a0cbfb, 0x579c3768, 0x5797a29e, - 0x57930d9e, 0x578e7869, - 0x5789e2fd, 0x57854d5b, 0x5780b784, 0x577c2176, 0x57778b32, 0x5772f4b9, - 0x576e5e09, 0x5769c724, - 0x57653009, 0x576098b7, 0x575c0130, 0x57576973, 0x5752d180, 0x574e3957, - 0x5749a0f9, 0x57450864, - 0x57406f9a, 0x573bd69a, 0x57373d64, 0x5732a3f8, 0x572e0a56, 0x5729707f, - 0x5724d672, 0x57203c2f, - 0x571ba1b7, 0x57170708, 0x57126c24, 0x570dd10a, 0x570935bb, 0x57049a36, - 0x56fffe7b, 0x56fb628b, - 0x56f6c664, 0x56f22a09, 0x56ed8d77, 0x56e8f0b0, 0x56e453b4, 0x56dfb681, - 0x56db1919, 0x56d67b7c, - 0x56d1dda9, 0x56cd3fa1, 0x56c8a162, 0x56c402ef, 0x56bf6446, 0x56bac567, - 0x56b62653, 0x56b18709, - 0x56ace78a, 0x56a847d6, 0x56a3a7ec, 0x569f07cc, 0x569a6777, 0x5695c6ed, - 0x5691262d, 0x568c8538, - 0x5687e40e, 0x568342ae, 0x567ea118, 0x5679ff4e, 0x56755d4e, 0x5670bb19, - 0x566c18ae, 0x5667760e, - 0x5662d339, 0x565e302e, 0x56598cee, 0x5654e979, 0x565045cf, 0x564ba1f0, - 0x5646fddb, 0x56425991, - 0x563db512, 0x5639105d, 0x56346b74, 0x562fc655, 0x562b2101, 0x56267b78, - 0x5621d5ba, 0x561d2fc6, - 0x5618899e, 0x5613e340, 0x560f3cae, 0x560a95e6, 0x5605eee9, 0x560147b7, - 0x55fca050, 0x55f7f8b4, - 0x55f350e3, 0x55eea8dd, 0x55ea00a2, 0x55e55832, 0x55e0af8d, 0x55dc06b3, - 0x55d75da4, 0x55d2b460, - 0x55ce0ae7, 0x55c96139, 0x55c4b757, 0x55c00d3f, 0x55bb62f3, 0x55b6b871, - 0x55b20dbb, 0x55ad62d0, - 0x55a8b7b0, 0x55a40c5b, 0x559f60d1, 0x559ab513, 0x55960920, 0x55915cf8, - 0x558cb09b, 0x55880409, - 0x55835743, 0x557eaa48, 0x5579fd18, 0x55754fb3, 0x5570a21a, 0x556bf44c, - 0x55674649, 0x55629812, - 0x555de9a6, 0x55593b05, 0x55548c30, 0x554fdd26, 0x554b2de7, 0x55467e74, - 0x5541cecc, 0x553d1ef0, - 0x55386edf, 0x5533be99, 0x552f0e1f, 0x552a5d70, 0x5525ac8d, 0x5520fb75, - 0x551c4a29, 0x551798a8, - 0x5512e6f3, 0x550e3509, 0x550982eb, 0x5504d099, 0x55001e12, 0x54fb6b56, - 0x54f6b866, 0x54f20542, - 0x54ed51e9, 0x54e89e5c, 0x54e3ea9a, 0x54df36a5, 0x54da827a, 0x54d5ce1c, - 0x54d11989, 0x54cc64c2, - 0x54c7afc6, 0x54c2fa96, 0x54be4532, 0x54b98f9a, 0x54b4d9cd, 0x54b023cc, - 0x54ab6d97, 0x54a6b72e, - 0x54a20090, 0x549d49bf, 0x549892b9, 0x5493db7f, 0x548f2410, 0x548a6c6e, - 0x5485b497, 0x5480fc8c, - 0x547c444d, 0x54778bda, 0x5472d333, 0x546e1a58, 0x54696149, 0x5464a805, - 0x545fee8e, 0x545b34e3, - 0x54567b03, 0x5451c0f0, 0x544d06a8, 0x54484c2d, 0x5443917d, 0x543ed699, - 0x543a1b82, 0x54356037, - 0x5430a4b7, 0x542be904, 0x54272d1d, 0x54227102, 0x541db4b3, 0x5418f830, - 0x54143b79, 0x540f7e8e, - 0x540ac170, 0x5406041d, 0x54014697, 0x53fc88dd, 0x53f7caef, 0x53f30cce, - 0x53ee4e78, 0x53e98fef, - 0x53e4d132, 0x53e01242, 0x53db531d, 0x53d693c5, 0x53d1d439, 0x53cd147a, - 0x53c85486, 0x53c3945f, - 0x53bed405, 0x53ba1377, 0x53b552b5, 0x53b091bf, 0x53abd096, 0x53a70f39, - 0x53a24da9, 0x539d8be5, - 0x5398c9ed, 0x539407c2, 0x538f4564, 0x538a82d1, 0x5385c00c, 0x5380fd12, - 0x537c39e6, 0x53777685, - 0x5372b2f2, 0x536def2a, 0x53692b30, 0x53646701, 0x535fa2a0, 0x535ade0b, - 0x53561942, 0x53515447, - 0x534c8f17, 0x5347c9b5, 0x5343041f, 0x533e3e55, 0x53397859, 0x5334b229, - 0x532febc5, 0x532b252f, - 0x53265e65, 0x53219767, 0x531cd037, 0x531808d3, 0x5313413c, 0x530e7972, - 0x5309b174, 0x5304e943, - 0x530020df, 0x52fb5848, 0x52f68f7e, 0x52f1c680, 0x52ecfd4f, 0x52e833ec, - 0x52e36a55, 0x52dea08a, - 0x52d9d68d, 0x52d50c5d, 0x52d041f9, 0x52cb7763, 0x52c6ac99, 0x52c1e19d, - 0x52bd166d, 0x52b84b0a, - 0x52b37f74, 0x52aeb3ac, 0x52a9e7b0, 0x52a51b81, 0x52a04f1f, 0x529b828a, - 0x5296b5c3, 0x5291e8c8, - 0x528d1b9b, 0x52884e3a, 0x528380a7, 0x527eb2e0, 0x5279e4e7, 0x527516bb, - 0x5270485c, 0x526b79ca, - 0x5266ab06, 0x5261dc0e, 0x525d0ce4, 0x52583d87, 0x52536df7, 0x524e9e34, - 0x5249ce3f, 0x5244fe17, - 0x52402dbc, 0x523b5d2e, 0x52368c6e, 0x5231bb7b, 0x522cea55, 0x522818fc, - 0x52234771, 0x521e75b3, - 0x5219a3c3, 0x5214d1a0, 0x520fff4a, 0x520b2cc2, 0x52065a07, 0x52018719, - 0x51fcb3f9, 0x51f7e0a6, - 0x51f30d21, 0x51ee3969, 0x51e9657e, 0x51e49162, 0x51dfbd12, 0x51dae890, - 0x51d613dc, 0x51d13ef5, - 0x51cc69db, 0x51c79490, 0x51c2bf11, 0x51bde960, 0x51b9137d, 0x51b43d68, - 0x51af6720, 0x51aa90a5, - 0x51a5b9f9, 0x51a0e31a, 0x519c0c08, 0x519734c4, 0x51925d4e, 0x518d85a6, - 0x5188adcb, 0x5183d5be, - 0x517efd7f, 0x517a250d, 0x51754c69, 0x51707393, 0x516b9a8b, 0x5166c150, - 0x5161e7e4, 0x515d0e45, - 0x51583473, 0x51535a70, 0x514e803b, 0x5149a5d3, 0x5144cb39, 0x513ff06d, - 0x513b156f, 0x51363a3f, - 0x51315edd, 0x512c8348, 0x5127a782, 0x5122cb8a, 0x511def5f, 0x51191302, - 0x51143674, 0x510f59b3, - 0x510a7cc1, 0x51059f9c, 0x5100c246, 0x50fbe4bd, 0x50f70703, 0x50f22916, - 0x50ed4af8, 0x50e86ca8, - 0x50e38e25, 0x50deaf71, 0x50d9d08b, 0x50d4f173, 0x50d0122a, 0x50cb32ae, - 0x50c65301, 0x50c17322, - 0x50bc9311, 0x50b7b2ce, 0x50b2d259, 0x50adf1b3, 0x50a910db, 0x50a42fd1, - 0x509f4e95, 0x509a6d28, - 0x50958b88, 0x5090a9b8, 0x508bc7b5, 0x5086e581, 0x5082031b, 0x507d2083, - 0x50783dba, 0x50735abf, - 0x506e7793, 0x50699435, 0x5064b0a5, 0x505fcce4, 0x505ae8f1, 0x505604cd, - 0x50512077, 0x504c3bef, - 0x50475736, 0x5042724c, 0x503d8d30, 0x5038a7e2, 0x5033c263, 0x502edcb2, - 0x5029f6d1, 0x502510bd, - 0x50202a78, 0x501b4402, 0x50165d5a, 0x50117681, 0x500c8f77, 0x5007a83b, - 0x5002c0cd, 0x4ffdd92f, - 0x4ff8f15f, 0x4ff4095e, 0x4fef212b, 0x4fea38c7, 0x4fe55032, 0x4fe0676c, - 0x4fdb7e74, 0x4fd6954b, - 0x4fd1abf0, 0x4fccc265, 0x4fc7d8a8, 0x4fc2eeba, 0x4fbe049b, 0x4fb91a4b, - 0x4fb42fc9, 0x4faf4517, - 0x4faa5a33, 0x4fa56f1e, 0x4fa083d8, 0x4f9b9861, 0x4f96acb8, 0x4f91c0df, - 0x4f8cd4d4, 0x4f87e899, - 0x4f82fc2c, 0x4f7e0f8f, 0x4f7922c0, 0x4f7435c0, 0x4f6f488f, 0x4f6a5b2e, - 0x4f656d9b, 0x4f607fd7, - 0x4f5b91e3, 0x4f56a3bd, 0x4f51b566, 0x4f4cc6df, 0x4f47d827, 0x4f42e93d, - 0x4f3dfa23, 0x4f390ad8, - 0x4f341b5c, 0x4f2f2baf, 0x4f2a3bd2, 0x4f254bc3, 0x4f205b84, 0x4f1b6b14, - 0x4f167a73, 0x4f1189a1, - 0x4f0c989f, 0x4f07a76b, 0x4f02b608, 0x4efdc473, 0x4ef8d2ad, 0x4ef3e0b7, - 0x4eeeee90, 0x4ee9fc39, - 0x4ee509b1, 0x4ee016f8, 0x4edb240e, 0x4ed630f4, 0x4ed13da9, 0x4ecc4a2e, - 0x4ec75682, 0x4ec262a5, - 0x4ebd6e98, 0x4eb87a5a, 0x4eb385ec, 0x4eae914d, 0x4ea99c7d, 0x4ea4a77d, - 0x4e9fb24d, 0x4e9abcec, - 0x4e95c75b, 0x4e90d199, 0x4e8bdba6, 0x4e86e583, 0x4e81ef30, 0x4e7cf8ac, - 0x4e7801f8, 0x4e730b14, - 0x4e6e13ff, 0x4e691cba, 0x4e642544, 0x4e5f2d9e, 0x4e5a35c7, 0x4e553dc1, - 0x4e50458a, 0x4e4b4d22, - 0x4e46548b, 0x4e415bc3, 0x4e3c62cb, 0x4e3769a2, 0x4e32704a, 0x4e2d76c1, - 0x4e287d08, 0x4e23831e, - 0x4e1e8905, 0x4e198ebb, 0x4e149441, 0x4e0f9997, 0x4e0a9ebd, 0x4e05a3b2, - 0x4e00a878, 0x4dfbad0d, - 0x4df6b173, 0x4df1b5a8, 0x4decb9ad, 0x4de7bd82, 0x4de2c127, 0x4dddc49c, - 0x4dd8c7e1, 0x4dd3caf6, - 0x4dcecdda, 0x4dc9d08f, 0x4dc4d314, 0x4dbfd569, 0x4dbad78e, 0x4db5d983, - 0x4db0db48, 0x4dabdcdd, - 0x4da6de43, 0x4da1df78, 0x4d9ce07d, 0x4d97e153, 0x4d92e1f9, 0x4d8de26f, - 0x4d88e2b5, 0x4d83e2cb, - 0x4d7ee2b1, 0x4d79e268, 0x4d74e1ef, 0x4d6fe146, 0x4d6ae06d, 0x4d65df64, - 0x4d60de2c, 0x4d5bdcc4, - 0x4d56db2d, 0x4d51d965, 0x4d4cd76e, 0x4d47d547, 0x4d42d2f1, 0x4d3dd06b, - 0x4d38cdb5, 0x4d33cad0, - 0x4d2ec7bb, 0x4d29c476, 0x4d24c102, 0x4d1fbd5e, 0x4d1ab98b, 0x4d15b588, - 0x4d10b155, 0x4d0bacf3, - 0x4d06a862, 0x4d01a3a0, 0x4cfc9eb0, 0x4cf79990, 0x4cf29440, 0x4ced8ec1, - 0x4ce88913, 0x4ce38335, - 0x4cde7d28, 0x4cd976eb, 0x4cd4707f, 0x4ccf69e3, 0x4cca6318, 0x4cc55c1e, - 0x4cc054f4, 0x4cbb4d9b, - 0x4cb64613, 0x4cb13e5b, 0x4cac3674, 0x4ca72e5e, 0x4ca22619, 0x4c9d1da4, - 0x4c981500, 0x4c930c2d, - 0x4c8e032a, 0x4c88f9f8, 0x4c83f097, 0x4c7ee707, 0x4c79dd48, 0x4c74d359, - 0x4c6fc93b, 0x4c6abeef, - 0x4c65b473, 0x4c60a9c8, 0x4c5b9eed, 0x4c5693e4, 0x4c5188ac, 0x4c4c7d44, - 0x4c4771ae, 0x4c4265e8, - 0x4c3d59f3, 0x4c384dd0, 0x4c33417d, 0x4c2e34fb, 0x4c29284b, 0x4c241b6b, - 0x4c1f0e5c, 0x4c1a011f, - 0x4c14f3b2, 0x4c0fe617, 0x4c0ad84c, 0x4c05ca53, 0x4c00bc2b, 0x4bfbadd4, - 0x4bf69f4e, 0x4bf19099, - 0x4bec81b5, 0x4be772a3, 0x4be26362, 0x4bdd53f2, 0x4bd84453, 0x4bd33485, - 0x4bce2488, 0x4bc9145d, - 0x4bc40403, 0x4bbef37b, 0x4bb9e2c3, 0x4bb4d1dd, 0x4bafc0c8, 0x4baaaf85, - 0x4ba59e12, 0x4ba08c72, - 0x4b9b7aa2, 0x4b9668a4, 0x4b915677, 0x4b8c441c, 0x4b873192, 0x4b821ed9, - 0x4b7d0bf2, 0x4b77f8dc, - 0x4b72e598, 0x4b6dd225, 0x4b68be84, 0x4b63aab4, 0x4b5e96b6, 0x4b598289, - 0x4b546e2d, 0x4b4f59a4, - 0x4b4a44eb, 0x4b453005, 0x4b401aef, 0x4b3b05ac, 0x4b35f03a, 0x4b30da9a, - 0x4b2bc4cb, 0x4b26aece, - 0x4b2198a2, 0x4b1c8248, 0x4b176bc0, 0x4b12550a, 0x4b0d3e25, 0x4b082712, - 0x4b030fd1, 0x4afdf861, - 0x4af8e0c3, 0x4af3c8f7, 0x4aeeb0fd, 0x4ae998d4, 0x4ae4807d, 0x4adf67f8, - 0x4ada4f45, 0x4ad53664, - 0x4ad01d54, 0x4acb0417, 0x4ac5eaab, 0x4ac0d111, 0x4abbb749, 0x4ab69d53, - 0x4ab1832f, 0x4aac68dc, - 0x4aa74e5c, 0x4aa233ae, 0x4a9d18d1, 0x4a97fdc7, 0x4a92e28e, 0x4a8dc728, - 0x4a88ab93, 0x4a838fd1, - 0x4a7e73e0, 0x4a7957c2, 0x4a743b76, 0x4a6f1efc, 0x4a6a0253, 0x4a64e57d, - 0x4a5fc879, 0x4a5aab48, - 0x4a558de8, 0x4a50705a, 0x4a4b529f, 0x4a4634b6, 0x4a41169f, 0x4a3bf85a, - 0x4a36d9e7, 0x4a31bb47, - 0x4a2c9c79, 0x4a277d7d, 0x4a225e53, 0x4a1d3efc, 0x4a181f77, 0x4a12ffc4, - 0x4a0ddfe4, 0x4a08bfd5, - 0x4a039f9a, 0x49fe7f30, 0x49f95e99, 0x49f43dd4, 0x49ef1ce2, 0x49e9fbc2, - 0x49e4da74, 0x49dfb8f9, - 0x49da9750, 0x49d5757a, 0x49d05376, 0x49cb3145, 0x49c60ee6, 0x49c0ec59, - 0x49bbc9a0, 0x49b6a6b8, - 0x49b183a3, 0x49ac6061, 0x49a73cf1, 0x49a21954, 0x499cf589, 0x4997d191, - 0x4992ad6c, 0x498d8919, - 0x49886499, 0x49833fec, 0x497e1b11, 0x4978f609, 0x4973d0d3, 0x496eab70, - 0x496985e0, 0x49646023, - 0x495f3a38, 0x495a1420, 0x4954eddb, 0x494fc768, 0x494aa0c9, 0x494579fc, - 0x49405302, 0x493b2bdb, - 0x49360486, 0x4930dd05, 0x492bb556, 0x49268d7a, 0x49216571, 0x491c3d3b, - 0x491714d8, 0x4911ec47, - 0x490cc38a, 0x49079aa0, 0x49027188, 0x48fd4844, 0x48f81ed2, 0x48f2f534, - 0x48edcb68, 0x48e8a170, - 0x48e3774a, 0x48de4cf8, 0x48d92278, 0x48d3f7cc, 0x48ceccf3, 0x48c9a1ed, - 0x48c476b9, 0x48bf4b59, - 0x48ba1fcd, 0x48b4f413, 0x48afc82c, 0x48aa9c19, 0x48a56fd9, 0x48a0436c, - 0x489b16d2, 0x4895ea0b, - 0x4890bd18, 0x488b8ff8, 0x488662ab, 0x48813531, 0x487c078b, 0x4876d9b8, - 0x4871abb8, 0x486c7d8c, - 0x48674f33, 0x486220ad, 0x485cf1fa, 0x4857c31b, 0x48529410, 0x484d64d7, - 0x48483572, 0x484305e1, - 0x483dd623, 0x4838a638, 0x48337621, 0x482e45dd, 0x4829156d, 0x4823e4d0, - 0x481eb407, 0x48198311, - 0x481451ef, 0x480f20a0, 0x4809ef25, 0x4804bd7e, 0x47ff8baa, 0x47fa59a9, - 0x47f5277d, 0x47eff523, - 0x47eac29e, 0x47e58fec, 0x47e05d0e, 0x47db2a03, 0x47d5f6cc, 0x47d0c369, - 0x47cb8fd9, 0x47c65c1d, - 0x47c12835, 0x47bbf421, 0x47b6bfe0, 0x47b18b74, 0x47ac56da, 0x47a72215, - 0x47a1ed24, 0x479cb806, - 0x479782bc, 0x47924d46, 0x478d17a4, 0x4787e1d6, 0x4782abdb, 0x477d75b5, - 0x47783f62, 0x477308e3, - 0x476dd239, 0x47689b62, 0x4763645f, 0x475e2d30, 0x4758f5d5, 0x4753be4e, - 0x474e869b, 0x47494ebc, - 0x474416b1, 0x473ede7a, 0x4739a617, 0x47346d89, 0x472f34ce, 0x4729fbe7, - 0x4724c2d5, 0x471f8996, - 0x471a502c, 0x47151696, 0x470fdcd4, 0x470aa2e6, 0x470568cd, 0x47002e87, - 0x46faf416, 0x46f5b979, - 0x46f07eb0, 0x46eb43bc, 0x46e6089b, 0x46e0cd4f, 0x46db91d8, 0x46d65634, - 0x46d11a65, 0x46cbde6a, - 0x46c6a244, 0x46c165f1, 0x46bc2974, 0x46b6ecca, 0x46b1aff5, 0x46ac72f4, - 0x46a735c8, 0x46a1f870, - 0x469cbaed, 0x46977d3e, 0x46923f63, 0x468d015d, 0x4687c32c, 0x468284cf, - 0x467d4646, 0x46780792, - 0x4672c8b3, 0x466d89a8, 0x46684a71, 0x46630b0f, 0x465dcb82, 0x46588bc9, - 0x46534be5, 0x464e0bd6, - 0x4648cb9b, 0x46438b35, 0x463e4aa3, 0x463909e7, 0x4633c8fe, 0x462e87eb, - 0x462946ac, 0x46240542, - 0x461ec3ad, 0x461981ec, 0x46144001, 0x460efde9, 0x4609bba7, 0x4604793a, - 0x45ff36a1, 0x45f9f3dd, - 0x45f4b0ee, 0x45ef6dd4, 0x45ea2a8f, 0x45e4e71f, 0x45dfa383, 0x45da5fbc, - 0x45d51bcb, 0x45cfd7ae, - 0x45ca9366, 0x45c54ef3, 0x45c00a55, 0x45bac58c, 0x45b58098, 0x45b03b79, - 0x45aaf630, 0x45a5b0bb, - 0x45a06b1b, 0x459b2550, 0x4595df5a, 0x45909939, 0x458b52ee, 0x45860c77, - 0x4580c5d6, 0x457b7f0a, - 0x45763813, 0x4570f0f1, 0x456ba9a4, 0x4566622c, 0x45611a8a, 0x455bd2bc, - 0x45568ac4, 0x455142a2, - 0x454bfa54, 0x4546b1dc, 0x45416939, 0x453c206b, 0x4536d773, 0x45318e4f, - 0x452c4502, 0x4526fb89, - 0x4521b1e6, 0x451c6818, 0x45171e20, 0x4511d3fd, 0x450c89af, 0x45073f37, - 0x4501f494, 0x44fca9c6, - 0x44f75ecf, 0x44f213ac, 0x44ecc85f, 0x44e77ce7, 0x44e23145, 0x44dce579, - 0x44d79982, 0x44d24d60, - 0x44cd0114, 0x44c7b49e, 0x44c267fd, 0x44bd1b32, 0x44b7ce3c, 0x44b2811c, - 0x44ad33d2, 0x44a7e65d, - 0x44a298be, 0x449d4af5, 0x4497fd01, 0x4492aee3, 0x448d609b, 0x44881228, - 0x4482c38b, 0x447d74c4, - 0x447825d2, 0x4472d6b7, 0x446d8771, 0x44683801, 0x4462e866, 0x445d98a2, - 0x445848b3, 0x4452f89b, - 0x444da858, 0x444857ea, 0x44430753, 0x443db692, 0x443865a7, 0x44331491, - 0x442dc351, 0x442871e8, - 0x44232054, 0x441dce96, 0x44187caf, 0x44132a9d, 0x440dd861, 0x440885fc, - 0x4403336c, 0x43fde0b2, - 0x43f88dcf, 0x43f33ac1, 0x43ede78a, 0x43e89429, 0x43e3409d, 0x43ddece8, - 0x43d8990a, 0x43d34501, - 0x43cdf0ce, 0x43c89c72, 0x43c347eb, 0x43bdf33b, 0x43b89e62, 0x43b3495e, - 0x43adf431, 0x43a89ed9, - 0x43a34959, 0x439df3ae, 0x43989dda, 0x439347dc, 0x438df1b4, 0x43889b63, - 0x438344e8, 0x437dee43, - 0x43789775, 0x4373407d, 0x436de95b, 0x43689210, 0x43633a9c, 0x435de2fd, - 0x43588b36, 0x43533344, - 0x434ddb29, 0x434882e5, 0x43432a77, 0x433dd1e0, 0x4338791f, 0x43332035, - 0x432dc721, 0x43286de4, - 0x4323147d, 0x431dbaed, 0x43186133, 0x43130751, 0x430dad44, 0x4308530f, - 0x4302f8b0, 0x42fd9e28, - 0x42f84376, 0x42f2e89b, 0x42ed8d97, 0x42e83269, 0x42e2d713, 0x42dd7b93, - 0x42d81fe9, 0x42d2c417, - 0x42cd681b, 0x42c80bf6, 0x42c2afa8, 0x42bd5331, 0x42b7f690, 0x42b299c7, - 0x42ad3cd4, 0x42a7dfb8, - 0x42a28273, 0x429d2505, 0x4297c76e, 0x429269ae, 0x428d0bc4, 0x4287adb2, - 0x42824f76, 0x427cf112, - 0x42779285, 0x427233ce, 0x426cd4ef, 0x426775e6, 0x426216b5, 0x425cb75a, - 0x425757d7, 0x4251f82b, - 0x424c9856, 0x42473858, 0x4241d831, 0x423c77e1, 0x42371769, 0x4231b6c7, - 0x422c55fd, 0x4226f50a, - 0x422193ee, 0x421c32a9, 0x4216d13c, 0x42116fa5, 0x420c0de6, 0x4206abfe, - 0x420149ee, 0x41fbe7b5, - 0x41f68553, 0x41f122c8, 0x41ebc015, 0x41e65d39, 0x41e0fa35, 0x41db9707, - 0x41d633b1, 0x41d0d033, - 0x41cb6c8c, 0x41c608bc, 0x41c0a4c4, 0x41bb40a3, 0x41b5dc5a, 0x41b077e8, - 0x41ab134e, 0x41a5ae8b, - 0x41a049a0, 0x419ae48c, 0x41957f4f, 0x419019eb, 0x418ab45d, 0x41854ea8, - 0x417fe8ca, 0x417a82c3, - 0x41751c94, 0x416fb63d, 0x416a4fbd, 0x4164e916, 0x415f8245, 0x415a1b4d, - 0x4154b42c, 0x414f4ce2, - 0x4149e571, 0x41447dd7, 0x413f1615, 0x4139ae2b, 0x41344618, 0x412edddd, - 0x4129757b, 0x41240cef, - 0x411ea43c, 0x41193b61, 0x4113d25d, 0x410e6931, 0x4108ffdd, 0x41039661, - 0x40fe2cbd, 0x40f8c2f1, - 0x40f358fc, 0x40edeee0, 0x40e8849b, 0x40e31a2f, 0x40ddaf9b, 0x40d844de, - 0x40d2d9f9, 0x40cd6eed, - 0x40c803b8, 0x40c2985c, 0x40bd2cd8, 0x40b7c12b, 0x40b25557, 0x40ace95b, - 0x40a77d37, 0x40a210eb, - 0x409ca477, 0x409737dc, 0x4091cb18, 0x408c5e2d, 0x4086f11a, 0x408183df, - 0x407c167c, 0x4076a8f1, - 0x40713b3f, 0x406bcd65, 0x40665f63, 0x4060f13a, 0x405b82e9, 0x40561470, - 0x4050a5cf, 0x404b3707, - 0x4045c817, 0x404058ff, 0x403ae9c0, 0x40357a59, 0x40300acb, 0x402a9b15, - 0x40252b37, 0x401fbb32, - 0x401a4b05, 0x4014dab1, 0x400f6a35, 0x4009f992, 0x400488c7, 0x3fff17d5, - 0x3ff9a6bb, 0x3ff4357a, - 0x3feec411, 0x3fe95281, 0x3fe3e0c9, 0x3fde6eeb, 0x3fd8fce4, 0x3fd38ab6, - 0x3fce1861, 0x3fc8a5e5, - 0x3fc33341, 0x3fbdc076, 0x3fb84d83, 0x3fb2da6a, 0x3fad6729, 0x3fa7f3c0, - 0x3fa28031, 0x3f9d0c7a, - 0x3f97989c, 0x3f922496, 0x3f8cb06a, 0x3f873c16, 0x3f81c79b, 0x3f7c52f9, - 0x3f76de30, 0x3f71693f, - 0x3f6bf428, 0x3f667ee9, 0x3f610983, 0x3f5b93f6, 0x3f561e42, 0x3f50a867, - 0x3f4b3265, 0x3f45bc3c, - 0x3f4045ec, 0x3f3acf75, 0x3f3558d7, 0x3f2fe211, 0x3f2a6b25, 0x3f24f412, - 0x3f1f7cd8, 0x3f1a0577, - 0x3f148def, 0x3f0f1640, 0x3f099e6b, 0x3f04266e, 0x3efeae4a, 0x3ef93600, - 0x3ef3bd8f, 0x3eee44f7, - 0x3ee8cc38, 0x3ee35352, 0x3eddda46, 0x3ed86113, 0x3ed2e7b9, 0x3ecd6e38, - 0x3ec7f491, 0x3ec27ac2, - 0x3ebd00cd, 0x3eb786b2, 0x3eb20c6f, 0x3eac9206, 0x3ea71777, 0x3ea19cc1, - 0x3e9c21e4, 0x3e96a6e0, - 0x3e912bb6, 0x3e8bb065, 0x3e8634ee, 0x3e80b950, 0x3e7b3d8c, 0x3e75c1a1, - 0x3e70458f, 0x3e6ac957, - 0x3e654cf8, 0x3e5fd073, 0x3e5a53c8, 0x3e54d6f6, 0x3e4f59fe, 0x3e49dcdf, - 0x3e445f99, 0x3e3ee22e, - 0x3e39649c, 0x3e33e6e3, 0x3e2e6904, 0x3e28eaff, 0x3e236cd4, 0x3e1dee82, - 0x3e18700a, 0x3e12f16b, - 0x3e0d72a6, 0x3e07f3bb, 0x3e0274aa, 0x3dfcf572, 0x3df77615, 0x3df1f691, - 0x3dec76e6, 0x3de6f716, - 0x3de1771f, 0x3ddbf703, 0x3dd676c0, 0x3dd0f656, 0x3dcb75c7, 0x3dc5f512, - 0x3dc07436, 0x3dbaf335, - 0x3db5720d, 0x3daff0c0, 0x3daa6f4c, 0x3da4edb2, 0x3d9f6bf2, 0x3d99ea0d, - 0x3d946801, 0x3d8ee5cf, - 0x3d896377, 0x3d83e0f9, 0x3d7e5e56, 0x3d78db8c, 0x3d73589d, 0x3d6dd587, - 0x3d68524c, 0x3d62ceeb, - 0x3d5d4b64, 0x3d57c7b7, 0x3d5243e4, 0x3d4cbfeb, 0x3d473bcd, 0x3d41b789, - 0x3d3c331f, 0x3d36ae8f, - 0x3d3129da, 0x3d2ba4fe, 0x3d261ffd, 0x3d209ad7, 0x3d1b158a, 0x3d159018, - 0x3d100a80, 0x3d0a84c3, - 0x3d04fee0, 0x3cff78d7, 0x3cf9f2a9, 0x3cf46c55, 0x3ceee5db, 0x3ce95f3c, - 0x3ce3d877, 0x3cde518d, - 0x3cd8ca7d, 0x3cd34347, 0x3ccdbbed, 0x3cc8346c, 0x3cc2acc6, 0x3cbd24fb, - 0x3cb79d0a, 0x3cb214f4, - 0x3cac8cb8, 0x3ca70457, 0x3ca17bd0, 0x3c9bf324, 0x3c966a53, 0x3c90e15c, - 0x3c8b5840, 0x3c85cefe, - 0x3c804598, 0x3c7abc0c, 0x3c75325a, 0x3c6fa883, 0x3c6a1e87, 0x3c649466, - 0x3c5f0a20, 0x3c597fb4, - 0x3c53f523, 0x3c4e6a6d, 0x3c48df91, 0x3c435491, 0x3c3dc96b, 0x3c383e20, - 0x3c32b2b0, 0x3c2d271b, - 0x3c279b61, 0x3c220f81, 0x3c1c837d, 0x3c16f753, 0x3c116b04, 0x3c0bde91, - 0x3c0651f8, 0x3c00c53a, - 0x3bfb3857, 0x3bf5ab50, 0x3bf01e23, 0x3bea90d1, 0x3be5035a, 0x3bdf75bf, - 0x3bd9e7fe, 0x3bd45a19, - 0x3bcecc0e, 0x3bc93ddf, 0x3bc3af8b, 0x3bbe2112, 0x3bb89274, 0x3bb303b1, - 0x3bad74c9, 0x3ba7e5bd, - 0x3ba2568c, 0x3b9cc736, 0x3b9737bb, 0x3b91a81c, 0x3b8c1857, 0x3b86886e, - 0x3b80f861, 0x3b7b682e, - 0x3b75d7d7, 0x3b70475c, 0x3b6ab6bb, 0x3b6525f6, 0x3b5f950c, 0x3b5a03fe, - 0x3b5472cb, 0x3b4ee173, - 0x3b494ff7, 0x3b43be57, 0x3b3e2c91, 0x3b389aa8, 0x3b330899, 0x3b2d7666, - 0x3b27e40f, 0x3b225193, - 0x3b1cbef3, 0x3b172c2e, 0x3b119945, 0x3b0c0637, 0x3b067305, 0x3b00dfaf, - 0x3afb4c34, 0x3af5b894, - 0x3af024d1, 0x3aea90e9, 0x3ae4fcdc, 0x3adf68ac, 0x3ad9d457, 0x3ad43fdd, - 0x3aceab40, 0x3ac9167e, - 0x3ac38198, 0x3abdec8d, 0x3ab8575f, 0x3ab2c20c, 0x3aad2c95, 0x3aa796fa, - 0x3aa2013a, 0x3a9c6b57, - 0x3a96d54f, 0x3a913f23, 0x3a8ba8d3, 0x3a86125f, 0x3a807bc7, 0x3a7ae50a, - 0x3a754e2a, 0x3a6fb726, - 0x3a6a1ffd, 0x3a6488b1, 0x3a5ef140, 0x3a5959ab, 0x3a53c1f3, 0x3a4e2a16, - 0x3a489216, 0x3a42f9f2, - 0x3a3d61a9, 0x3a37c93d, 0x3a3230ad, 0x3a2c97f9, 0x3a26ff21, 0x3a216625, - 0x3a1bcd05, 0x3a1633c1, - 0x3a109a5a, 0x3a0b00cf, 0x3a056720, 0x39ffcd4d, 0x39fa3356, 0x39f4993c, - 0x39eefefe, 0x39e9649c, - 0x39e3ca17, 0x39de2f6d, 0x39d894a0, 0x39d2f9b0, 0x39cd5e9b, 0x39c7c363, - 0x39c22808, 0x39bc8c89, - 0x39b6f0e6, 0x39b1551f, 0x39abb935, 0x39a61d28, 0x39a080f6, 0x399ae4a2, - 0x39954829, 0x398fab8e, - 0x398a0ece, 0x398471ec, 0x397ed4e5, 0x397937bc, 0x39739a6e, 0x396dfcfe, - 0x39685f6a, 0x3962c1b2, - 0x395d23d7, 0x395785d9, 0x3951e7b8, 0x394c4973, 0x3946ab0a, 0x39410c7f, - 0x393b6dd0, 0x3935cefd, - 0x39303008, 0x392a90ef, 0x3924f1b3, 0x391f5254, 0x3919b2d1, 0x3914132b, - 0x390e7362, 0x3908d376, - 0x39033367, 0x38fd9334, 0x38f7f2de, 0x38f25266, 0x38ecb1ca, 0x38e7110a, - 0x38e17028, 0x38dbcf23, - 0x38d62dfb, 0x38d08caf, 0x38caeb41, 0x38c549af, 0x38bfa7fb, 0x38ba0623, - 0x38b46429, 0x38aec20b, - 0x38a91fcb, 0x38a37d67, 0x389ddae1, 0x38983838, 0x3892956c, 0x388cf27d, - 0x38874f6b, 0x3881ac36, - 0x387c08de, 0x38766564, 0x3870c1c6, 0x386b1e06, 0x38657a23, 0x385fd61d, - 0x385a31f5, 0x38548daa, - 0x384ee93b, 0x384944ab, 0x38439ff7, 0x383dfb21, 0x38385628, 0x3832b10d, - 0x382d0bce, 0x3827666d, - 0x3821c0ea, 0x381c1b44, 0x3816757b, 0x3810cf90, 0x380b2982, 0x38058351, - 0x37ffdcfe, 0x37fa3688, - 0x37f48ff0, 0x37eee936, 0x37e94259, 0x37e39b59, 0x37ddf437, 0x37d84cf2, - 0x37d2a58b, 0x37ccfe02, - 0x37c75656, 0x37c1ae87, 0x37bc0697, 0x37b65e84, 0x37b0b64e, 0x37ab0df6, - 0x37a5657c, 0x379fbce0, - 0x379a1421, 0x37946b40, 0x378ec23d, 0x37891917, 0x37836fcf, 0x377dc665, - 0x37781cd9, 0x3772732a, - 0x376cc959, 0x37671f66, 0x37617551, 0x375bcb1a, 0x375620c1, 0x37507645, - 0x374acba7, 0x374520e7, - 0x373f7606, 0x3739cb02, 0x37341fdc, 0x372e7493, 0x3728c929, 0x37231d9d, - 0x371d71ef, 0x3717c61f, - 0x37121a2d, 0x370c6e19, 0x3706c1e2, 0x3701158a, 0x36fb6910, 0x36f5bc75, - 0x36f00fb7, 0x36ea62d7, - 0x36e4b5d6, 0x36df08b2, 0x36d95b6d, 0x36d3ae06, 0x36ce007d, 0x36c852d2, - 0x36c2a506, 0x36bcf718, - 0x36b74908, 0x36b19ad6, 0x36abec82, 0x36a63e0d, 0x36a08f76, 0x369ae0bd, - 0x369531e3, 0x368f82e7, - 0x3689d3c9, 0x3684248a, 0x367e7529, 0x3678c5a7, 0x36731602, 0x366d663d, - 0x3667b655, 0x3662064c, - 0x365c5622, 0x3656a5d6, 0x3650f569, 0x364b44da, 0x36459429, 0x363fe357, - 0x363a3264, 0x3634814f, - 0x362ed019, 0x36291ec1, 0x36236d48, 0x361dbbad, 0x361809f1, 0x36125814, - 0x360ca615, 0x3606f3f5, - 0x360141b4, 0x35fb8f52, 0x35f5dcce, 0x35f02a28, 0x35ea7762, 0x35e4c47a, - 0x35df1171, 0x35d95e47, - 0x35d3aafc, 0x35cdf78f, 0x35c84401, 0x35c29052, 0x35bcdc82, 0x35b72891, - 0x35b1747e, 0x35abc04b, - 0x35a60bf6, 0x35a05781, 0x359aa2ea, 0x3594ee32, 0x358f3959, 0x3589845f, - 0x3583cf44, 0x357e1a08, - 0x357864ab, 0x3572af2d, 0x356cf98e, 0x356743ce, 0x35618ded, 0x355bd7eb, - 0x355621c9, 0x35506b85, - 0x354ab520, 0x3544fe9b, 0x353f47f5, 0x3539912e, 0x3533da46, 0x352e233d, - 0x35286c14, 0x3522b4c9, - 0x351cfd5e, 0x351745d2, 0x35118e26, 0x350bd658, 0x35061e6a, 0x3500665c, - 0x34faae2c, 0x34f4f5dc, - 0x34ef3d6b, 0x34e984da, 0x34e3cc28, 0x34de1355, 0x34d85a62, 0x34d2a14e, - 0x34cce819, 0x34c72ec4, - 0x34c1754e, 0x34bbbbb8, 0x34b60202, 0x34b0482a, 0x34aa8e33, 0x34a4d41a, - 0x349f19e2, 0x34995f88, - 0x3493a50f, 0x348dea75, 0x34882fba, 0x348274e0, 0x347cb9e4, 0x3476fec9, - 0x3471438d, 0x346b8830, - 0x3465ccb4, 0x34601117, 0x345a5559, 0x3454997c, 0x344edd7e, 0x34492160, - 0x34436521, 0x343da8c3, - 0x3437ec44, 0x34322fa5, 0x342c72e6, 0x3426b606, 0x3420f907, 0x341b3be7, - 0x34157ea7, 0x340fc147, - 0x340a03c7, 0x34044626, 0x33fe8866, 0x33f8ca86, 0x33f30c85, 0x33ed4e65, - 0x33e79024, 0x33e1d1c4, - 0x33dc1343, 0x33d654a2, 0x33d095e2, 0x33cad701, 0x33c51801, 0x33bf58e1, - 0x33b999a0, 0x33b3da40, - 0x33ae1ac0, 0x33a85b20, 0x33a29b60, 0x339cdb81, 0x33971b81, 0x33915b62, - 0x338b9b22, 0x3385dac4, - 0x33801a45, 0x337a59a6, 0x337498e8, 0x336ed80a, 0x3369170c, 0x336355ef, - 0x335d94b2, 0x3357d355, - 0x335211d8, 0x334c503c, 0x33468e80, 0x3340cca5, 0x333b0aaa, 0x3335488f, - 0x332f8655, 0x3329c3fb, - 0x33240182, 0x331e3ee9, 0x33187c31, 0x3312b959, 0x330cf661, 0x3307334a, - 0x33017014, 0x32fbacbe, - 0x32f5e948, 0x32f025b4, 0x32ea61ff, 0x32e49e2c, 0x32deda39, 0x32d91626, - 0x32d351f5, 0x32cd8da4, - 0x32c7c933, 0x32c204a3, 0x32bc3ff4, 0x32b67b26, 0x32b0b638, 0x32aaf12b, - 0x32a52bff, 0x329f66b4, - 0x3299a149, 0x3293dbbf, 0x328e1616, 0x3288504e, 0x32828a67, 0x327cc460, - 0x3276fe3a, 0x327137f6, - 0x326b7192, 0x3265ab0f, 0x325fe46c, 0x325a1dab, 0x325456cb, 0x324e8fcc, - 0x3248c8ad, 0x32430170, - 0x323d3a14, 0x32377298, 0x3231aafe, 0x322be345, 0x32261b6c, 0x32205375, - 0x321a8b5f, 0x3214c32a, - 0x320efad6, 0x32093263, 0x320369d2, 0x31fda121, 0x31f7d852, 0x31f20f64, - 0x31ec4657, 0x31e67d2b, - 0x31e0b3e0, 0x31daea77, 0x31d520ef, 0x31cf5748, 0x31c98d83, 0x31c3c39e, - 0x31bdf99b, 0x31b82f7a, - 0x31b2653a, 0x31ac9adb, 0x31a6d05d, 0x31a105c1, 0x319b3b06, 0x3195702d, - 0x318fa535, 0x3189da1e, - 0x31840ee9, 0x317e4395, 0x31787823, 0x3172ac92, 0x316ce0e3, 0x31671515, - 0x31614929, 0x315b7d1e, - 0x3155b0f5, 0x314fe4ae, 0x314a1848, 0x31444bc3, 0x313e7f21, 0x3138b260, - 0x3132e580, 0x312d1882, - 0x31274b66, 0x31217e2c, 0x311bb0d3, 0x3115e35c, 0x311015c6, 0x310a4813, - 0x31047a41, 0x30feac51, - 0x30f8de42, 0x30f31016, 0x30ed41cb, 0x30e77362, 0x30e1a4db, 0x30dbd636, - 0x30d60772, 0x30d03891, - 0x30ca6991, 0x30c49a74, 0x30becb38, 0x30b8fbde, 0x30b32c66, 0x30ad5cd0, - 0x30a78d1c, 0x30a1bd4a, - 0x309bed5a, 0x30961d4c, 0x30904d20, 0x308a7cd6, 0x3084ac6e, 0x307edbe9, - 0x30790b45, 0x30733a83, - 0x306d69a4, 0x306798a7, 0x3061c78b, 0x305bf652, 0x305624fb, 0x30505387, - 0x304a81f4, 0x3044b044, - 0x303ede76, 0x30390c8a, 0x30333a80, 0x302d6859, 0x30279614, 0x3021c3b1, - 0x301bf131, 0x30161e93, - 0x30104bd7, 0x300a78fe, 0x3004a607, 0x2ffed2f2, 0x2ff8ffc0, 0x2ff32c70, - 0x2fed5902, 0x2fe78577, - 0x2fe1b1cf, 0x2fdbde09, 0x2fd60a25, 0x2fd03624, 0x2fca6206, 0x2fc48dc9, - 0x2fbeb970, 0x2fb8e4f9, - 0x2fb31064, 0x2fad3bb3, 0x2fa766e3, 0x2fa191f7, 0x2f9bbced, 0x2f95e7c5, - 0x2f901280, 0x2f8a3d1e, - 0x2f84679f, 0x2f7e9202, 0x2f78bc48, 0x2f72e671, 0x2f6d107c, 0x2f673a6a, - 0x2f61643b, 0x2f5b8def, - 0x2f55b785, 0x2f4fe0ff, 0x2f4a0a5b, 0x2f44339a, 0x2f3e5cbb, 0x2f3885c0, - 0x2f32aea8, 0x2f2cd772, - 0x2f27001f, 0x2f2128af, 0x2f1b5122, 0x2f157979, 0x2f0fa1b2, 0x2f09c9ce, - 0x2f03f1cd, 0x2efe19ae, - 0x2ef84173, 0x2ef2691b, 0x2eec90a7, 0x2ee6b815, 0x2ee0df66, 0x2edb069a, - 0x2ed52db1, 0x2ecf54ac, - 0x2ec97b89, 0x2ec3a24a, 0x2ebdc8ee, 0x2eb7ef75, 0x2eb215df, 0x2eac3c2d, - 0x2ea6625d, 0x2ea08871, - 0x2e9aae68, 0x2e94d443, 0x2e8efa00, 0x2e891fa1, 0x2e834525, 0x2e7d6a8d, - 0x2e778fd8, 0x2e71b506, - 0x2e6bda17, 0x2e65ff0c, 0x2e6023e5, 0x2e5a48a0, 0x2e546d3f, 0x2e4e91c2, - 0x2e48b628, 0x2e42da71, - 0x2e3cfe9e, 0x2e3722ae, 0x2e3146a2, 0x2e2b6a79, 0x2e258e34, 0x2e1fb1d3, - 0x2e19d554, 0x2e13f8ba, - 0x2e0e1c03, 0x2e083f30, 0x2e026240, 0x2dfc8534, 0x2df6a80b, 0x2df0cac6, - 0x2deaed65, 0x2de50fe8, - 0x2ddf324e, 0x2dd95498, 0x2dd376c5, 0x2dcd98d7, 0x2dc7bacc, 0x2dc1dca4, - 0x2dbbfe61, 0x2db62001, - 0x2db04186, 0x2daa62ee, 0x2da4843a, 0x2d9ea569, 0x2d98c67d, 0x2d92e774, - 0x2d8d084f, 0x2d87290f, - 0x2d8149b2, 0x2d7b6a39, 0x2d758aa4, 0x2d6faaf3, 0x2d69cb26, 0x2d63eb3d, - 0x2d5e0b38, 0x2d582b17, - 0x2d524ada, 0x2d4c6a81, 0x2d468a0c, 0x2d40a97b, 0x2d3ac8ce, 0x2d34e805, - 0x2d2f0721, 0x2d292620, - 0x2d234504, 0x2d1d63cc, 0x2d178278, 0x2d11a108, 0x2d0bbf7d, 0x2d05ddd5, - 0x2cfffc12, 0x2cfa1a33, - 0x2cf43839, 0x2cee5622, 0x2ce873f0, 0x2ce291a2, 0x2cdcaf39, 0x2cd6ccb4, - 0x2cd0ea13, 0x2ccb0756, - 0x2cc5247e, 0x2cbf418b, 0x2cb95e7b, 0x2cb37b51, 0x2cad980a, 0x2ca7b4a8, - 0x2ca1d12a, 0x2c9bed91, - 0x2c9609dd, 0x2c90260d, 0x2c8a4221, 0x2c845e1a, 0x2c7e79f7, 0x2c7895b9, - 0x2c72b160, 0x2c6ccceb, - 0x2c66e85b, 0x2c6103af, 0x2c5b1ee8, 0x2c553a06, 0x2c4f5508, 0x2c496fef, - 0x2c438abb, 0x2c3da56b, - 0x2c37c000, 0x2c31da7a, 0x2c2bf4d8, 0x2c260f1c, 0x2c202944, 0x2c1a4351, - 0x2c145d42, 0x2c0e7719, - 0x2c0890d4, 0x2c02aa74, 0x2bfcc3f9, 0x2bf6dd63, 0x2bf0f6b1, 0x2beb0fe5, - 0x2be528fd, 0x2bdf41fb, - 0x2bd95add, 0x2bd373a4, 0x2bcd8c51, 0x2bc7a4e2, 0x2bc1bd58, 0x2bbbd5b3, - 0x2bb5edf4, 0x2bb00619, - 0x2baa1e23, 0x2ba43613, 0x2b9e4de7, 0x2b9865a1, 0x2b927d3f, 0x2b8c94c3, - 0x2b86ac2c, 0x2b80c37a, - 0x2b7adaae, 0x2b74f1c6, 0x2b6f08c4, 0x2b691fa6, 0x2b63366f, 0x2b5d4d1c, - 0x2b5763ae, 0x2b517a26, - 0x2b4b9083, 0x2b45a6c6, 0x2b3fbced, 0x2b39d2fa, 0x2b33e8ed, 0x2b2dfec5, - 0x2b281482, 0x2b222a24, - 0x2b1c3fac, 0x2b165519, 0x2b106a6c, 0x2b0a7fa4, 0x2b0494c2, 0x2afea9c5, - 0x2af8bead, 0x2af2d37b, - 0x2aece82f, 0x2ae6fcc8, 0x2ae11146, 0x2adb25aa, 0x2ad539f4, 0x2acf4e23, - 0x2ac96238, 0x2ac37633, - 0x2abd8a13, 0x2ab79dd8, 0x2ab1b184, 0x2aabc515, 0x2aa5d88b, 0x2a9febe8, - 0x2a99ff2a, 0x2a941252, - 0x2a8e255f, 0x2a883853, 0x2a824b2c, 0x2a7c5deb, 0x2a76708f, 0x2a70831a, - 0x2a6a958a, 0x2a64a7e0, - 0x2a5eba1c, 0x2a58cc3e, 0x2a52de46, 0x2a4cf033, 0x2a470207, 0x2a4113c0, - 0x2a3b2560, 0x2a3536e5, - 0x2a2f4850, 0x2a2959a1, 0x2a236ad9, 0x2a1d7bf6, 0x2a178cf9, 0x2a119de2, - 0x2a0baeb2, 0x2a05bf67, - 0x29ffd003, 0x29f9e084, 0x29f3f0ec, 0x29ee013a, 0x29e8116e, 0x29e22188, - 0x29dc3188, 0x29d6416f, - 0x29d0513b, 0x29ca60ee, 0x29c47087, 0x29be8007, 0x29b88f6c, 0x29b29eb8, - 0x29acadea, 0x29a6bd02, - 0x29a0cc01, 0x299adae6, 0x2994e9b1, 0x298ef863, 0x298906fb, 0x2983157a, - 0x297d23df, 0x2977322a, - 0x2971405b, 0x296b4e74, 0x29655c72, 0x295f6a57, 0x29597823, 0x295385d5, - 0x294d936d, 0x2947a0ec, - 0x2941ae52, 0x293bbb9e, 0x2935c8d1, 0x292fd5ea, 0x2929e2ea, 0x2923efd0, - 0x291dfc9d, 0x29180951, - 0x291215eb, 0x290c226c, 0x29062ed4, 0x29003b23, 0x28fa4758, 0x28f45374, - 0x28ee5f76, 0x28e86b5f, - 0x28e27730, 0x28dc82e6, 0x28d68e84, 0x28d09a09, 0x28caa574, 0x28c4b0c6, - 0x28bebbff, 0x28b8c71f, - 0x28b2d226, 0x28acdd13, 0x28a6e7e8, 0x28a0f2a3, 0x289afd46, 0x289507cf, - 0x288f123f, 0x28891c97, - 0x288326d5, 0x287d30fa, 0x28773b07, 0x287144fa, 0x286b4ed5, 0x28655896, - 0x285f623f, 0x28596bce, - 0x28537545, 0x284d7ea3, 0x284787e8, 0x28419114, 0x283b9a28, 0x2835a322, - 0x282fac04, 0x2829b4cd, - 0x2823bd7d, 0x281dc615, 0x2817ce93, 0x2811d6f9, 0x280bdf46, 0x2805e77b, - 0x27ffef97, 0x27f9f79a, - 0x27f3ff85, 0x27ee0756, 0x27e80f10, 0x27e216b0, 0x27dc1e38, 0x27d625a8, - 0x27d02cff, 0x27ca343d, - 0x27c43b63, 0x27be4270, 0x27b84965, 0x27b25041, 0x27ac5705, 0x27a65db0, - 0x27a06443, 0x279a6abd, - 0x2794711f, 0x278e7768, 0x27887d99, 0x278283b2, 0x277c89b3, 0x27768f9b, - 0x2770956a, 0x276a9b21, - 0x2764a0c0, 0x275ea647, 0x2758abb6, 0x2752b10c, 0x274cb64a, 0x2746bb6f, - 0x2740c07d, 0x273ac572, - 0x2734ca4f, 0x272ecf14, 0x2728d3c0, 0x2722d855, 0x271cdcd1, 0x2716e136, - 0x2710e582, 0x270ae9b6, - 0x2704edd2, 0x26fef1d5, 0x26f8f5c1, 0x26f2f995, 0x26ecfd51, 0x26e700f5, - 0x26e10480, 0x26db07f4, - 0x26d50b50, 0x26cf0e94, 0x26c911c0, 0x26c314d4, 0x26bd17d0, 0x26b71ab4, - 0x26b11d80, 0x26ab2034, - 0x26a522d1, 0x269f2556, 0x269927c3, 0x26932a18, 0x268d2c55, 0x26872e7b, - 0x26813088, 0x267b327e, - 0x2675345d, 0x266f3623, 0x266937d2, 0x26633969, 0x265d3ae9, 0x26573c50, - 0x26513da1, 0x264b3ed9, - 0x26453ffa, 0x263f4103, 0x263941f5, 0x263342cf, 0x262d4392, 0x2627443d, - 0x262144d0, 0x261b454c, - 0x261545b0, 0x260f45fd, 0x26094633, 0x26034651, 0x25fd4657, 0x25f74646, - 0x25f1461e, 0x25eb45de, - 0x25e54587, 0x25df4519, 0x25d94493, 0x25d343f6, 0x25cd4341, 0x25c74276, - 0x25c14192, 0x25bb4098, - 0x25b53f86, 0x25af3e5d, 0x25a93d1d, 0x25a33bc6, 0x259d3a57, 0x259738d1, - 0x25913734, 0x258b3580, - 0x258533b5, 0x257f31d2, 0x25792fd8, 0x25732dc8, 0x256d2ba0, 0x25672961, - 0x2561270b, 0x255b249e, - 0x2555221a, 0x254f1f7e, 0x25491ccc, 0x25431a03, 0x253d1723, 0x2537142c, - 0x2531111e, 0x252b0df9, - 0x25250abd, 0x251f076a, 0x25190400, 0x25130080, 0x250cfce8, 0x2506f93a, - 0x2500f574, 0x24faf198, - 0x24f4eda6, 0x24eee99c, 0x24e8e57c, 0x24e2e144, 0x24dcdcf6, 0x24d6d892, - 0x24d0d416, 0x24cacf84, - 0x24c4cadb, 0x24bec61c, 0x24b8c146, 0x24b2bc59, 0x24acb756, 0x24a6b23b, - 0x24a0ad0b, 0x249aa7c4, - 0x2494a266, 0x248e9cf1, 0x24889766, 0x248291c5, 0x247c8c0d, 0x2476863e, - 0x24708059, 0x246a7a5e, - 0x2464744c, 0x245e6e23, 0x245867e4, 0x2452618f, 0x244c5b24, 0x244654a1, - 0x24404e09, 0x243a475a, - 0x24344095, 0x242e39ba, 0x242832c8, 0x24222bc0, 0x241c24a1, 0x24161d6d, - 0x24101622, 0x240a0ec1, - 0x24040749, 0x23fdffbc, 0x23f7f818, 0x23f1f05e, 0x23ebe88e, 0x23e5e0a7, - 0x23dfd8ab, 0x23d9d098, - 0x23d3c86f, 0x23cdc031, 0x23c7b7dc, 0x23c1af71, 0x23bba6f0, 0x23b59e59, - 0x23af95ac, 0x23a98ce8, - 0x23a3840f, 0x239d7b20, 0x2397721b, 0x23916900, 0x238b5fcf, 0x23855688, - 0x237f4d2b, 0x237943b9, - 0x23733a30, 0x236d3092, 0x236726dd, 0x23611d13, 0x235b1333, 0x2355093e, - 0x234eff32, 0x2348f511, - 0x2342eada, 0x233ce08d, 0x2336d62a, 0x2330cbb2, 0x232ac124, 0x2324b680, - 0x231eabc7, 0x2318a0f8, - 0x23129613, 0x230c8b19, 0x23068009, 0x230074e3, 0x22fa69a8, 0x22f45e57, - 0x22ee52f1, 0x22e84775, - 0x22e23be4, 0x22dc303d, 0x22d62480, 0x22d018ae, 0x22ca0cc7, 0x22c400ca, - 0x22bdf4b8, 0x22b7e890, - 0x22b1dc53, 0x22abd001, 0x22a5c399, 0x229fb71b, 0x2299aa89, 0x22939de1, - 0x228d9123, 0x22878451, - 0x22817769, 0x227b6a6c, 0x22755d59, 0x226f5032, 0x226942f5, 0x226335a2, - 0x225d283b, 0x22571abe, - 0x22510d2d, 0x224aff86, 0x2244f1c9, 0x223ee3f8, 0x2238d612, 0x2232c816, - 0x222cba06, 0x2226abe0, - 0x22209da5, 0x221a8f56, 0x221480f1, 0x220e7277, 0x220863e8, 0x22025544, - 0x21fc468b, 0x21f637be, - 0x21f028db, 0x21ea19e3, 0x21e40ad7, 0x21ddfbb5, 0x21d7ec7f, 0x21d1dd34, - 0x21cbcdd3, 0x21c5be5e, - 0x21bfaed5, 0x21b99f36, 0x21b38f83, 0x21ad7fba, 0x21a76fdd, 0x21a15fec, - 0x219b4fe5, 0x21953fca, - 0x218f2f9a, 0x21891f55, 0x21830efc, 0x217cfe8e, 0x2176ee0b, 0x2170dd74, - 0x216accc8, 0x2164bc08, - 0x215eab33, 0x21589a49, 0x2152894b, 0x214c7838, 0x21466710, 0x214055d4, - 0x213a4484, 0x2134331f, - 0x212e21a6, 0x21281018, 0x2121fe76, 0x211becbf, 0x2115daf4, 0x210fc914, - 0x2109b720, 0x2103a518, - 0x20fd92fb, 0x20f780ca, 0x20f16e84, 0x20eb5c2b, 0x20e549bd, 0x20df373a, - 0x20d924a4, 0x20d311f9, - 0x20ccff3a, 0x20c6ec66, 0x20c0d97f, 0x20bac683, 0x20b4b373, 0x20aea04f, - 0x20a88d17, 0x20a279ca, - 0x209c666a, 0x209652f5, 0x20903f6c, 0x208a2bcf, 0x2084181e, 0x207e0459, - 0x2077f080, 0x2071dc93, - 0x206bc892, 0x2065b47d, 0x205fa054, 0x20598c17, 0x205377c6, 0x204d6361, - 0x20474ee8, 0x20413a5b, - 0x203b25bb, 0x20351106, 0x202efc3e, 0x2028e761, 0x2022d271, 0x201cbd6d, - 0x2016a856, 0x2010932a, - 0x200a7deb, 0x20046898, 0x1ffe5331, 0x1ff83db6, 0x1ff22828, 0x1fec1286, - 0x1fe5fcd0, 0x1fdfe707, - 0x1fd9d12a, 0x1fd3bb39, 0x1fcda535, 0x1fc78f1d, 0x1fc178f1, 0x1fbb62b2, - 0x1fb54c60, 0x1faf35f9, - 0x1fa91f80, 0x1fa308f2, 0x1f9cf252, 0x1f96db9d, 0x1f90c4d5, 0x1f8aadfa, - 0x1f84970b, 0x1f7e8009, - 0x1f7868f4, 0x1f7251ca, 0x1f6c3a8e, 0x1f66233e, 0x1f600bdb, 0x1f59f465, - 0x1f53dcdb, 0x1f4dc53d, - 0x1f47ad8d, 0x1f4195c9, 0x1f3b7df2, 0x1f356608, 0x1f2f4e0a, 0x1f2935f9, - 0x1f231dd5, 0x1f1d059e, - 0x1f16ed54, 0x1f10d4f6, 0x1f0abc85, 0x1f04a401, 0x1efe8b6a, 0x1ef872c0, - 0x1ef25a03, 0x1eec4132, - 0x1ee6284f, 0x1ee00f58, 0x1ed9f64f, 0x1ed3dd32, 0x1ecdc402, 0x1ec7aac0, - 0x1ec1916a, 0x1ebb7802, - 0x1eb55e86, 0x1eaf44f8, 0x1ea92b56, 0x1ea311a2, 0x1e9cf7db, 0x1e96de01, - 0x1e90c414, 0x1e8aaa14, - 0x1e849001, 0x1e7e75dc, 0x1e785ba3, 0x1e724158, 0x1e6c26fa, 0x1e660c8a, - 0x1e5ff206, 0x1e59d770, - 0x1e53bcc7, 0x1e4da20c, 0x1e47873d, 0x1e416c5d, 0x1e3b5169, 0x1e353663, - 0x1e2f1b4a, 0x1e29001e, - 0x1e22e4e0, 0x1e1cc990, 0x1e16ae2c, 0x1e1092b6, 0x1e0a772e, 0x1e045b93, - 0x1dfe3fe6, 0x1df82426, - 0x1df20853, 0x1debec6f, 0x1de5d077, 0x1ddfb46e, 0x1dd99851, 0x1dd37c23, - 0x1dcd5fe2, 0x1dc7438e, - 0x1dc12729, 0x1dbb0ab0, 0x1db4ee26, 0x1daed189, 0x1da8b4da, 0x1da29819, - 0x1d9c7b45, 0x1d965e5f, - 0x1d904167, 0x1d8a245c, 0x1d840740, 0x1d7dea11, 0x1d77ccd0, 0x1d71af7d, - 0x1d6b9217, 0x1d6574a0, - 0x1d5f5716, 0x1d59397a, 0x1d531bcc, 0x1d4cfe0d, 0x1d46e03a, 0x1d40c256, - 0x1d3aa460, 0x1d348658, - 0x1d2e683e, 0x1d284a12, 0x1d222bd3, 0x1d1c0d83, 0x1d15ef21, 0x1d0fd0ad, - 0x1d09b227, 0x1d03938f, - 0x1cfd74e5, 0x1cf7562a, 0x1cf1375c, 0x1ceb187d, 0x1ce4f98c, 0x1cdeda89, - 0x1cd8bb74, 0x1cd29c4d, - 0x1ccc7d15, 0x1cc65dca, 0x1cc03e6e, 0x1cba1f01, 0x1cb3ff81, 0x1caddff0, - 0x1ca7c04d, 0x1ca1a099, - 0x1c9b80d3, 0x1c9560fb, 0x1c8f4112, 0x1c892117, 0x1c83010a, 0x1c7ce0ec, - 0x1c76c0bc, 0x1c70a07b, - 0x1c6a8028, 0x1c645fc3, 0x1c5e3f4d, 0x1c581ec6, 0x1c51fe2d, 0x1c4bdd83, - 0x1c45bcc7, 0x1c3f9bf9, - 0x1c397b1b, 0x1c335a2b, 0x1c2d3929, 0x1c271816, 0x1c20f6f2, 0x1c1ad5bc, - 0x1c14b475, 0x1c0e931d, - 0x1c0871b4, 0x1c025039, 0x1bfc2ead, 0x1bf60d0f, 0x1befeb60, 0x1be9c9a1, - 0x1be3a7cf, 0x1bdd85ed, - 0x1bd763fa, 0x1bd141f5, 0x1bcb1fdf, 0x1bc4fdb8, 0x1bbedb80, 0x1bb8b937, - 0x1bb296dc, 0x1bac7471, - 0x1ba651f5, 0x1ba02f67, 0x1b9a0cc8, 0x1b93ea19, 0x1b8dc758, 0x1b87a487, - 0x1b8181a4, 0x1b7b5eb0, - 0x1b753bac, 0x1b6f1897, 0x1b68f570, 0x1b62d239, 0x1b5caef1, 0x1b568b98, - 0x1b50682e, 0x1b4a44b3, - 0x1b442127, 0x1b3dfd8b, 0x1b37d9de, 0x1b31b620, 0x1b2b9251, 0x1b256e71, - 0x1b1f4a81, 0x1b192680, - 0x1b13026e, 0x1b0cde4c, 0x1b06ba19, 0x1b0095d5, 0x1afa7180, 0x1af44d1b, - 0x1aee28a6, 0x1ae8041f, - 0x1ae1df88, 0x1adbbae1, 0x1ad59629, 0x1acf7160, 0x1ac94c87, 0x1ac3279d, - 0x1abd02a3, 0x1ab6dd98, - 0x1ab0b87d, 0x1aaa9352, 0x1aa46e16, 0x1a9e48c9, 0x1a98236c, 0x1a91fdff, - 0x1a8bd881, 0x1a85b2f3, - 0x1a7f8d54, 0x1a7967a6, 0x1a7341e6, 0x1a6d1c17, 0x1a66f637, 0x1a60d047, - 0x1a5aaa47, 0x1a548436, - 0x1a4e5e15, 0x1a4837e4, 0x1a4211a3, 0x1a3beb52, 0x1a35c4f0, 0x1a2f9e7e, - 0x1a2977fc, 0x1a23516a, - 0x1a1d2ac8, 0x1a170416, 0x1a10dd53, 0x1a0ab681, 0x1a048f9e, 0x19fe68ac, - 0x19f841a9, 0x19f21a96, - 0x19ebf374, 0x19e5cc41, 0x19dfa4fe, 0x19d97dac, 0x19d35649, 0x19cd2ed7, - 0x19c70754, 0x19c0dfc2, - 0x19bab820, 0x19b4906e, 0x19ae68ac, 0x19a840da, 0x19a218f9, 0x199bf107, - 0x1995c906, 0x198fa0f5, - 0x198978d4, 0x198350a4, 0x197d2864, 0x19770014, 0x1970d7b4, 0x196aaf45, - 0x196486c6, 0x195e5e37, - 0x19583599, 0x19520ceb, 0x194be42d, 0x1945bb60, 0x193f9283, 0x19396997, - 0x1933409b, 0x192d178f, - 0x1926ee74, 0x1920c54a, 0x191a9c10, 0x191472c6, 0x190e496d, 0x19082005, - 0x1901f68d, 0x18fbcd06, - 0x18f5a36f, 0x18ef79c9, 0x18e95014, 0x18e3264f, 0x18dcfc7b, 0x18d6d297, - 0x18d0a8a4, 0x18ca7ea2, - 0x18c45491, 0x18be2a70, 0x18b80040, 0x18b1d601, 0x18ababb2, 0x18a58154, - 0x189f56e8, 0x18992c6b, - 0x189301e0, 0x188cd746, 0x1886ac9c, 0x188081e4, 0x187a571c, 0x18742c45, - 0x186e015f, 0x1867d66a, - 0x1861ab66, 0x185b8053, 0x18555530, 0x184f29ff, 0x1848febf, 0x1842d370, - 0x183ca812, 0x18367ca5, - 0x18305129, 0x182a259e, 0x1823fa04, 0x181dce5b, 0x1817a2a4, 0x181176dd, - 0x180b4b08, 0x18051f24, - 0x17fef331, 0x17f8c72f, 0x17f29b1e, 0x17ec6eff, 0x17e642d1, 0x17e01694, - 0x17d9ea49, 0x17d3bdee, - 0x17cd9186, 0x17c7650e, 0x17c13888, 0x17bb0bf3, 0x17b4df4f, 0x17aeb29d, - 0x17a885dc, 0x17a2590d, - 0x179c2c2f, 0x1795ff42, 0x178fd247, 0x1789a53d, 0x17837825, 0x177d4afe, - 0x17771dc9, 0x1770f086, - 0x176ac333, 0x176495d3, 0x175e6864, 0x17583ae7, 0x17520d5b, 0x174bdfc1, - 0x1745b218, 0x173f8461, - 0x1739569c, 0x173328c8, 0x172cfae6, 0x1726ccf6, 0x17209ef8, 0x171a70eb, - 0x171442d0, 0x170e14a7, - 0x1707e670, 0x1701b82a, 0x16fb89d6, 0x16f55b74, 0x16ef2d04, 0x16e8fe86, - 0x16e2cff9, 0x16dca15f, - 0x16d672b6, 0x16d043ff, 0x16ca153a, 0x16c3e667, 0x16bdb787, 0x16b78898, - 0x16b1599b, 0x16ab2a90, - 0x16a4fb77, 0x169ecc50, 0x16989d1b, 0x16926dd8, 0x168c3e87, 0x16860f29, - 0x167fdfbc, 0x1679b042, - 0x167380ba, 0x166d5123, 0x1667217f, 0x1660f1ce, 0x165ac20e, 0x16549241, - 0x164e6266, 0x1648327d, - 0x16420286, 0x163bd282, 0x1635a270, 0x162f7250, 0x16294222, 0x162311e7, - 0x161ce19e, 0x1616b148, - 0x161080e4, 0x160a5072, 0x16041ff3, 0x15fdef66, 0x15f7becc, 0x15f18e24, - 0x15eb5d6e, 0x15e52cab, - 0x15defbdb, 0x15d8cafd, 0x15d29a11, 0x15cc6918, 0x15c63812, 0x15c006fe, - 0x15b9d5dd, 0x15b3a4ae, - 0x15ad7372, 0x15a74228, 0x15a110d2, 0x159adf6e, 0x1594adfc, 0x158e7c7d, - 0x15884af1, 0x15821958, - 0x157be7b1, 0x1575b5fe, 0x156f843c, 0x1569526e, 0x15632093, 0x155ceeaa, - 0x1556bcb4, 0x15508ab1, - 0x154a58a1, 0x15442683, 0x153df459, 0x1537c221, 0x15318fdd, 0x152b5d8b, - 0x15252b2c, 0x151ef8c0, - 0x1518c648, 0x151293c2, 0x150c612f, 0x15062e8f, 0x14fffbe2, 0x14f9c928, - 0x14f39662, 0x14ed638e, - 0x14e730ae, 0x14e0fdc0, 0x14dacac6, 0x14d497bf, 0x14ce64ab, 0x14c8318a, - 0x14c1fe5c, 0x14bbcb22, - 0x14b597da, 0x14af6486, 0x14a93125, 0x14a2fdb8, 0x149cca3e, 0x149696b7, - 0x14906323, 0x148a2f82, - 0x1483fbd5, 0x147dc81c, 0x14779455, 0x14716082, 0x146b2ca3, 0x1464f8b7, - 0x145ec4be, 0x145890b9, - 0x14525ca7, 0x144c2888, 0x1445f45d, 0x143fc026, 0x14398be2, 0x14335792, - 0x142d2335, 0x1426eecb, - 0x1420ba56, 0x141a85d3, 0x14145145, 0x140e1caa, 0x1407e803, 0x1401b34f, - 0x13fb7e8f, 0x13f549c3, - 0x13ef14ea, 0x13e8e005, 0x13e2ab14, 0x13dc7616, 0x13d6410d, 0x13d00bf7, - 0x13c9d6d4, 0x13c3a1a6, - 0x13bd6c6b, 0x13b73725, 0x13b101d2, 0x13aacc73, 0x13a49707, 0x139e6190, - 0x13982c0d, 0x1391f67d, - 0x138bc0e1, 0x13858b3a, 0x137f5586, 0x13791fc6, 0x1372e9fb, 0x136cb423, - 0x13667e3f, 0x13604850, - 0x135a1254, 0x1353dc4c, 0x134da639, 0x1347701a, 0x134139ee, 0x133b03b7, - 0x1334cd74, 0x132e9725, - 0x132860ca, 0x13222a64, 0x131bf3f2, 0x1315bd73, 0x130f86ea, 0x13095054, - 0x130319b3, 0x12fce305, - 0x12f6ac4d, 0x12f07588, 0x12ea3eb8, 0x12e407dc, 0x12ddd0f4, 0x12d79a01, - 0x12d16303, 0x12cb2bf8, - 0x12c4f4e2, 0x12bebdc1, 0x12b88693, 0x12b24f5b, 0x12ac1817, 0x12a5e0c7, - 0x129fa96c, 0x12997205, - 0x12933a93, 0x128d0315, 0x1286cb8c, 0x128093f7, 0x127a5c57, 0x127424ac, - 0x126decf5, 0x1267b533, - 0x12617d66, 0x125b458d, 0x12550da9, 0x124ed5ba, 0x12489dbf, 0x124265b9, - 0x123c2da8, 0x1235f58b, - 0x122fbd63, 0x12298530, 0x12234cf2, 0x121d14a9, 0x1216dc54, 0x1210a3f5, - 0x120a6b8a, 0x12043314, - 0x11fdfa93, 0x11f7c207, 0x11f18970, 0x11eb50cd, 0x11e51820, 0x11dedf68, - 0x11d8a6a4, 0x11d26dd6, - 0x11cc34fc, 0x11c5fc18, 0x11bfc329, 0x11b98a2e, 0x11b35129, 0x11ad1819, - 0x11a6defe, 0x11a0a5d8, - 0x119a6ca7, 0x1194336b, 0x118dfa25, 0x1187c0d3, 0x11818777, 0x117b4e10, - 0x1175149e, 0x116edb22, - 0x1168a19b, 0x11626809, 0x115c2e6c, 0x1155f4c4, 0x114fbb12, 0x11498156, - 0x1143478e, 0x113d0dbc, - 0x1136d3df, 0x113099f8, 0x112a6006, 0x11242609, 0x111dec02, 0x1117b1f0, - 0x111177d4, 0x110b3dad, - 0x1105037c, 0x10fec940, 0x10f88efa, 0x10f254a9, 0x10ec1a4e, 0x10e5dfe8, - 0x10dfa578, 0x10d96afe, - 0x10d33079, 0x10ccf5ea, 0x10c6bb50, 0x10c080ac, 0x10ba45fe, 0x10b40b45, - 0x10add082, 0x10a795b5, - 0x10a15ade, 0x109b1ffc, 0x1094e510, 0x108eaa1a, 0x10886f19, 0x1082340f, - 0x107bf8fa, 0x1075bddb, - 0x106f82b2, 0x1069477f, 0x10630c41, 0x105cd0fa, 0x105695a8, 0x10505a4d, - 0x104a1ee7, 0x1043e377, - 0x103da7fd, 0x10376c79, 0x103130ec, 0x102af554, 0x1024b9b2, 0x101e7e06, - 0x10184251, 0x10120691, - 0x100bcac7, 0x10058ef4, 0xfff5317, 0xff91730, 0xff2db3e, 0xfec9f44, - 0xfe6633f, 0xfe02730, - 0xfd9eb18, 0xfd3aef6, 0xfcd72ca, 0xfc73695, 0xfc0fa55, 0xfbabe0c, 0xfb481ba, - 0xfae455d, - 0xfa808f7, 0xfa1cc87, 0xf9b900e, 0xf95538b, 0xf8f16fe, 0xf88da68, 0xf829dc8, - 0xf7c611f, - 0xf76246c, 0xf6fe7af, 0xf69aae9, 0xf636e1a, 0xf5d3141, 0xf56f45e, 0xf50b773, - 0xf4a7a7d, - 0xf443d7e, 0xf3e0076, 0xf37c365, 0xf318649, 0xf2b4925, 0xf250bf7, 0xf1ecec0, - 0xf189180, - 0xf125436, 0xf0c16e3, 0xf05d987, 0xeff9c21, 0xef95eb2, 0xef3213a, 0xeece3b9, - 0xee6a62f, - 0xee0689b, 0xeda2afe, 0xed3ed58, 0xecdafa9, 0xec771f1, 0xec1342f, 0xebaf665, - 0xeb4b891, - 0xeae7ab4, 0xea83ccf, 0xea1fee0, 0xe9bc0e8, 0xe9582e7, 0xe8f44dd, 0xe8906cb, - 0xe82c8af, - 0xe7c8a8a, 0xe764c5c, 0xe700e26, 0xe69cfe6, 0xe63919e, 0xe5d534d, 0xe5714f3, - 0xe50d690, - 0xe4a9824, 0xe4459af, 0xe3e1b32, 0xe37dcac, 0xe319e1d, 0xe2b5f85, 0xe2520e5, - 0xe1ee23c, - 0xe18a38a, 0xe1264cf, 0xe0c260c, 0xe05e740, 0xdffa86b, 0xdf9698e, 0xdf32aa8, - 0xdecebba, - 0xde6acc3, 0xde06dc3, 0xdda2ebb, 0xdd3efab, 0xdcdb091, 0xdc77170, 0xdc13245, - 0xdbaf313, - 0xdb4b3d7, 0xdae7494, 0xda83548, 0xda1f5f3, 0xd9bb696, 0xd957731, 0xd8f37c3, - 0xd88f84d, - 0xd82b8cf, 0xd7c7948, 0xd7639b9, 0xd6ffa22, 0xd69ba82, 0xd637ada, 0xd5d3b2a, - 0xd56fb71, - 0xd50bbb1, 0xd4a7be8, 0xd443c17, 0xd3dfc3e, 0xd37bc5c, 0xd317c73, 0xd2b3c81, - 0xd24fc87, - 0xd1ebc85, 0xd187c7b, 0xd123c69, 0xd0bfc4f, 0xd05bc2d, 0xcff7c02, 0xcf93bd0, - 0xcf2fb96, - 0xcecbb53, 0xce67b09, 0xce03ab7, 0xcd9fa5d, 0xcd3b9fb, 0xccd7991, 0xcc7391f, - 0xcc0f8a5, - 0xcbab824, 0xcb4779a, 0xcae3709, 0xca7f670, 0xca1b5cf, 0xc9b7526, 0xc953475, - 0xc8ef3bd, - 0xc88b2fd, 0xc827235, 0xc7c3166, 0xc75f08f, 0xc6fafb0, 0xc696ec9, 0xc632ddb, - 0xc5cece5, - 0xc56abe8, 0xc506ae3, 0xc4a29d6, 0xc43e8c2, 0xc3da7a6, 0xc376683, 0xc312558, - 0xc2ae425, - 0xc24a2eb, 0xc1e61aa, 0xc182061, 0xc11df11, 0xc0b9db9, 0xc055c5a, 0xbff1af3, - 0xbf8d985, - 0xbf29810, 0xbec5693, 0xbe6150f, 0xbdfd383, 0xbd991f0, 0xbd35056, 0xbcd0eb5, - 0xbc6cd0c, - 0xbc08b5c, 0xbba49a5, 0xbb407e7, 0xbadc621, 0xba78454, 0xba14280, 0xb9b00a5, - 0xb94bec2, - 0xb8e7cd9, 0xb883ae8, 0xb81f8f0, 0xb7bb6f2, 0xb7574ec, 0xb6f32df, 0xb68f0cb, - 0xb62aeaf, - 0xb5c6c8d, 0xb562a64, 0xb4fe834, 0xb49a5fd, 0xb4363bf, 0xb3d217a, 0xb36df2e, - 0xb309cdb, - 0xb2a5a81, 0xb241820, 0xb1dd5b9, 0xb17934b, 0xb1150d5, 0xb0b0e59, 0xb04cbd6, - 0xafe894d, - 0xaf846bc, 0xaf20425, 0xaebc187, 0xae57ee2, 0xadf3c37, 0xad8f985, 0xad2b6cc, - 0xacc740c, - 0xac63146, 0xabfee79, 0xab9aba6, 0xab368cc, 0xaad25eb, 0xaa6e304, 0xaa0a016, - 0xa9a5d22, - 0xa941a27, 0xa8dd725, 0xa87941d, 0xa81510f, 0xa7b0dfa, 0xa74cadf, 0xa6e87bd, - 0xa684495, - 0xa620166, 0xa5bbe31, 0xa557af5, 0xa4f37b3, 0xa48f46b, 0xa42b11d, 0xa3c6dc8, - 0xa362a6d, - 0xa2fe70b, 0xa29a3a3, 0xa236035, 0xa1d1cc1, 0xa16d946, 0xa1095c6, 0xa0a523f, - 0xa040eb1, - 0x9fdcb1e, 0x9f78784, 0x9f143e5, 0x9eb003f, 0x9e4bc93, 0x9de78e1, 0x9d83529, - 0x9d1f16b, - 0x9cbada7, 0x9c569dc, 0x9bf260c, 0x9b8e236, 0x9b29e59, 0x9ac5a77, 0x9a6168f, - 0x99fd2a0, - 0x9998eac, 0x9934ab2, 0x98d06b2, 0x986c2ac, 0x9807ea1, 0x97a3a8f, 0x973f678, - 0x96db25a, - 0x9676e37, 0x9612a0e, 0x95ae5e0, 0x954a1ab, 0x94e5d71, 0x9481931, 0x941d4eb, - 0x93b90a0, - 0x9354c4f, 0x92f07f8, 0x928c39b, 0x9227f39, 0x91c3ad2, 0x915f664, 0x90fb1f1, - 0x9096d79, - 0x90328fb, 0x8fce477, 0x8f69fee, 0x8f05b5f, 0x8ea16cb, 0x8e3d231, 0x8dd8d92, - 0x8d748ed, - 0x8d10443, 0x8cabf93, 0x8c47ade, 0x8be3624, 0x8b7f164, 0x8b1ac9f, 0x8ab67d4, - 0x8a52304, - 0x89ede2f, 0x8989955, 0x8925475, 0x88c0f90, 0x885caa5, 0x87f85b5, 0x87940c1, - 0x872fbc6, - 0x86cb6c7, 0x86671c2, 0x8602cb9, 0x859e7aa, 0x853a296, 0x84d5d7d, 0x847185e, - 0x840d33b, - 0x83a8e12, 0x83448e5, 0x82e03b2, 0x827be7a, 0x821793e, 0x81b33fc, 0x814eeb5, - 0x80ea969, - 0x8086419, 0x8021ec3, 0x7fbd968, 0x7f59409, 0x7ef4ea4, 0x7e9093b, 0x7e2c3cd, - 0x7dc7e5a, - 0x7d638e2, 0x7cff365, 0x7c9ade4, 0x7c3685d, 0x7bd22d2, 0x7b6dd42, 0x7b097ad, - 0x7aa5214, - 0x7a40c76, 0x79dc6d3, 0x797812b, 0x7913b7f, 0x78af5ce, 0x784b019, 0x77e6a5e, - 0x77824a0, - 0x771dedc, 0x76b9914, 0x7655347, 0x75f0d76, 0x758c7a1, 0x75281c6, 0x74c3be7, - 0x745f604, - 0x73fb01c, 0x7396a30, 0x733243f, 0x72cde4a, 0x7269851, 0x7205253, 0x71a0c50, - 0x713c64a, - 0x70d803f, 0x7073a2f, 0x700f41b, 0x6faae03, 0x6f467e7, 0x6ee21c6, 0x6e7dba1, - 0x6e19578, - 0x6db4f4a, 0x6d50919, 0x6cec2e3, 0x6c87ca9, 0x6c2366a, 0x6bbf028, 0x6b5a9e1, - 0x6af6396, - 0x6a91d47, 0x6a2d6f4, 0x69c909d, 0x6964a42, 0x69003e3, 0x689bd80, 0x6837718, - 0x67d30ad, - 0x676ea3d, 0x670a3ca, 0x66a5d53, 0x66416d8, 0x65dd058, 0x65789d5, 0x651434e, - 0x64afcc3, - 0x644b634, 0x63e6fa2, 0x638290b, 0x631e271, 0x62b9bd3, 0x6255531, 0x61f0e8b, - 0x618c7e1, - 0x6128134, 0x60c3a83, 0x605f3ce, 0x5ffad15, 0x5f96659, 0x5f31f99, 0x5ecd8d6, - 0x5e6920e, - 0x5e04b43, 0x5da0475, 0x5d3bda3, 0x5cd76cd, 0x5c72ff4, 0x5c0e917, 0x5baa237, - 0x5b45b53, - 0x5ae146b, 0x5a7cd80, 0x5a18692, 0x59b3fa0, 0x594f8aa, 0x58eb1b2, 0x5886ab5, - 0x58223b6, - 0x57bdcb3, 0x57595ac, 0x56f4ea2, 0x5690795, 0x562c085, 0x55c7971, 0x556325a, - 0x54feb3f, - 0x549a422, 0x5435d01, 0x53d15dd, 0x536ceb5, 0x530878a, 0x52a405d, 0x523f92c, - 0x51db1f7, - 0x5176ac0, 0x5112385, 0x50adc48, 0x5049507, 0x4fe4dc3, 0x4f8067c, 0x4f1bf32, - 0x4eb77e5, - 0x4e53095, 0x4dee942, 0x4d8a1ec, 0x4d25a93, 0x4cc1337, 0x4c5cbd8, 0x4bf8476, - 0x4b93d11, - 0x4b2f5a9, 0x4acae3e, 0x4a666d1, 0x4a01f60, 0x499d7ed, 0x4939077, 0x48d48fe, - 0x4870182, - 0x480ba04, 0x47a7282, 0x4742afe, 0x46de377, 0x4679bee, 0x4615461, 0x45b0cd2, - 0x454c541, - 0x44e7dac, 0x4483615, 0x441ee7c, 0x43ba6df, 0x4355f40, 0x42f179f, 0x428cffb, - 0x4228854, - 0x41c40ab, 0x415f8ff, 0x40fb151, 0x40969a0, 0x40321ed, 0x3fcda37, 0x3f6927f, - 0x3f04ac4, - 0x3ea0307, 0x3e3bb48, 0x3dd7386, 0x3d72bc2, 0x3d0e3fb, 0x3ca9c32, 0x3c45467, - 0x3be0c99, - 0x3b7c4c9, 0x3b17cf7, 0x3ab3523, 0x3a4ed4c, 0x39ea573, 0x3985d97, 0x39215ba, - 0x38bcdda, - 0x38585f8, 0x37f3e14, 0x378f62e, 0x372ae46, 0x36c665b, 0x3661e6f, 0x35fd680, - 0x3598e8f, - 0x353469c, 0x34cfea8, 0x346b6b1, 0x3406eb8, 0x33a26bd, 0x333dec0, 0x32d96c1, - 0x3274ec0, - 0x32106bd, 0x31abeb9, 0x31476b2, 0x30e2ea9, 0x307e69f, 0x3019e93, 0x2fb5684, - 0x2f50e74, - 0x2eec663, 0x2e87e4f, 0x2e2363a, 0x2dbee22, 0x2d5a609, 0x2cf5def, 0x2c915d2, - 0x2c2cdb4, - 0x2bc8594, 0x2b63d73, 0x2aff54f, 0x2a9ad2a, 0x2a36504, 0x29d1cdc, 0x296d4b2, - 0x2908c87, - 0x28a445a, 0x283fc2b, 0x27db3fb, 0x2776bc9, 0x2712396, 0x26adb62, 0x264932b, - 0x25e4af4, - 0x25802bb, 0x251ba80, 0x24b7244, 0x2452a07, 0x23ee1c8, 0x2389988, 0x2325147, - 0x22c0904, - 0x225c0bf, 0x21f787a, 0x2193033, 0x212e7eb, 0x20c9fa1, 0x2065757, 0x2000f0b, - 0x1f9c6be, - 0x1f37e6f, 0x1ed3620, 0x1e6edcf, 0x1e0a57d, 0x1da5d2a, 0x1d414d6, 0x1cdcc80, - 0x1c7842a, - 0x1c13bd2, 0x1baf37a, 0x1b4ab20, 0x1ae62c5, 0x1a81a69, 0x1a1d20c, 0x19b89ae, - 0x1954150, - 0x18ef8f0, 0x188b08f, 0x182682d, 0x17c1fcb, 0x175d767, 0x16f8f03, 0x169469d, - 0x162fe37, - 0x15cb5d0, 0x1566d68, 0x15024ff, 0x149dc96, 0x143942b, 0x13d4bc0, 0x1370354, - 0x130bae7, - 0x12a727a, 0x1242a0c, 0x11de19d, 0x117992e, 0x11150be, 0x10b084d, 0x104bfdb, - 0xfe7769, - 0xf82ef6, 0xf1e683, 0xeb9e0f, 0xe5559b, 0xdf0d26, 0xd8c4b0, 0xd27c3a, - 0xcc33c3, - 0xc5eb4c, 0xbfa2d5, 0xb95a5d, 0xb311e4, 0xacc96b, 0xa680f2, 0xa03878, - 0x99effe, - 0x93a784, 0x8d5f09, 0x87168e, 0x80ce12, 0x7a8597, 0x743d1a, 0x6df49e, - 0x67ac21, - 0x6163a5, 0x5b1b27, 0x54d2aa, 0x4e8a2c, 0x4841af, 0x41f931, 0x3bb0b3, - 0x356835, - 0x2f1fb6, 0x28d738, 0x228eb9, 0x1c463b, 0x15fdbc, 0xfb53d, 0x96cbe, 0x3243f, - -}; - -/** - * @brief Initialization function for the Q31 DCT4/IDCT4. - * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure. - * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure - * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - * \par Normalizing factor: - * The normalizing factor is sqrt(2/N), which depends on the size of transform N. - * Normalizing factors in 1.31 format are mentioned in the table below for different DCT sizes: - * \image html dct4NormalizingQ31Table.gif - */ - -arm_status arm_dct4_init_q31( - arm_dct4_instance_q31 * S, - arm_rfft_instance_q31 * S_RFFT, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q31_t normalize) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initializing the pointer array with the weight table base addresses of different lengths */ - q31_t *twiddlePtr[4] = { (q31_t *) WeightsQ31_128, (q31_t *) WeightsQ31_512, - (q31_t *) WeightsQ31_2048, (q31_t *) WeightsQ31_8192 - }; - - /* Initializing the pointer array with the cos factor table base addresses of different lengths */ - q31_t *pCosFactor[4] = - { (q31_t *) cos_factorsQ31_128, (q31_t *) cos_factorsQ31_512, - (q31_t *) cos_factorsQ31_2048, (q31_t *) cos_factorsQ31_8192 - }; - - /* Initialize the DCT4 length */ - S->N = N; - - /* Initialize the half of DCT4 length */ - S->Nby2 = Nby2; - - /* Initialize the DCT4 Normalizing factor */ - S->normalize = normalize; - - /* Initialize Real FFT Instance */ - S->pRfft = S_RFFT; - - /* Initialize Complex FFT Instance */ - S->pCfft = S_CFFT; - - switch (N) - { - /* Initialize the table modifier values */ - case 8192u: - S->pTwiddle = twiddlePtr[3]; - S->pCosFactor = pCosFactor[3]; - break; - case 2048u: - S->pTwiddle = twiddlePtr[2]; - S->pCosFactor = pCosFactor[2]; - break; - case 512u: - S->pTwiddle = twiddlePtr[1]; - S->pCosFactor = pCosFactor[1]; - break; - case 128u: - S->pTwiddle = twiddlePtr[0]; - S->pCosFactor = pCosFactor[0]; - break; - default: - status = ARM_MATH_ARGUMENT_ERROR; - } - - /* Initialize the RFFT/RIFFT Function */ - arm_rfft_init_q31(S->pRfft, S->pCfft, S->N, 0, 1); - - /* return the status of DCT4 Init function */ - return (status); -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c deleted file mode 100644 index feaa2ae3c0..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q15.c +++ /dev/null @@ -1,386 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_q15.c -* -* Description: Processing function of DCT4 & IDCT4 Q15. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the Q15 DCT4/IDCT4. - * @param[in] *S points to an instance of the Q15 DCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - * - * \par Input an output formats: - * Internally inputs are downscaled in the RFFT process function to avoid overflows. - * Number of bits downscaled, depends on the size of the transform. - * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: - * - * \image html dct4FormatsQ15Table.gif - */ - -void arm_dct4_q15( - const arm_dct4_instance_q15 * S, - q15_t * pState, - q15_t * pInlineBuffer) -{ - uint32_t i; /* Loop counter */ - q15_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - q15_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - q15_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - q15_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_mult_q15(pInlineBuffer, cosFact, pInlineBuffer, S->N); - arm_shift_q15(pInlineBuffer, 1, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = (uint32_t) S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q15(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.13 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ - arm_shift_q15(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = ((uint32_t) S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = ((uint32_t) S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = (uint32_t) S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = (uint32_t) S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q15(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q15(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.13 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.15 format by shifting left by 2 bits. */ - arm_shift_q15(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter */ - i = ((uint32_t) S->N - 1u); - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = (uint32_t) S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q15_t) (((q31_t) in * S->normalize) >> 15)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c deleted file mode 100644 index 887cfb385d..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_dct4_q31.c +++ /dev/null @@ -1,387 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_dct4_q31.c -* -* Description: Processing function of DCT4 & IDCT4 Q31. -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @addtogroup DCT4_IDCT4 - * @{ - */ - -/** - * @brief Processing function for the Q31 DCT4/IDCT4. - * @param[in] *S points to an instance of the Q31 DCT4 structure. - * @param[in] *pState points to state buffer. - * @param[in,out] *pInlineBuffer points to the in-place input and output buffer. - * @return none. - * \par Input an output formats: - * Input samples need to be downscaled by 1 bit to avoid saturations in the Q31 DCT process, - * as the conversion from DCT2 to DCT4 involves one subtraction. - * Internally inputs are downscaled in the RFFT process function to avoid overflows. - * Number of bits downscaled, depends on the size of the transform. - * The input and output formats for different DCT sizes and number of bits to upscale are mentioned in the table below: - * - * \image html dct4FormatsQ31Table.gif - */ - -void arm_dct4_q31( - const arm_dct4_instance_q31 * S, - q31_t * pState, - q31_t * pInlineBuffer) -{ - uint16_t i; /* Loop counter */ - q31_t *weights = S->pTwiddle; /* Pointer to the Weights table */ - q31_t *cosFact = S->pCosFactor; /* Pointer to the cos factors table */ - q31_t *pS1, *pS2, *pbuff; /* Temporary pointers for input buffer and pState buffer */ - q31_t in; /* Temporary variable */ - - - /* DCT4 computation involves DCT2 (which is calculated using RFFT) - * along with some pre-processing and post-processing. - * Computational procedure is explained as follows: - * (a) Pre-processing involves multiplying input with cos factor, - * r(n) = 2 * u(n) * cos(pi*(2*n+1)/(4*n)) - * where, - * r(n) -- output of preprocessing - * u(n) -- input to preprocessing(actual Source buffer) - * (b) Calculation of DCT2 using FFT is divided into three steps: - * Step1: Re-ordering of even and odd elements of input. - * Step2: Calculating FFT of the re-ordered input. - * Step3: Taking the real part of the product of FFT output and weights. - * (c) Post-processing - DCT4 can be obtained from DCT2 output using the following equation: - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * where, - * Y4 -- DCT4 output, Y2 -- DCT2 output - * (d) Multiplying the output with the normalizing factor sqrt(2/N). - */ - - /*-------- Pre-processing ------------*/ - /* Multiplying input with cos factor i.e. r(n) = 2 * x(n) * cos(pi*(2*n+1)/(4*n)) */ - arm_mult_q31(pInlineBuffer, cosFact, pInlineBuffer, S->N); - arm_shift_q31(pInlineBuffer, 1, pInlineBuffer, S->N); - - /* ---------------------------------------------------------------- - * Step1: Re-ordering of even and odd elements as - * pState[i] = pInlineBuffer[2*i] and - * pState[N-i-1] = pInlineBuffer[2*i+1] where i = 0 to N/2 - ---------------------------------------------------------------------*/ - - /* pS1 initialized to pState */ - pS1 = pState; - - /* pS2 initialized to pState+N-1, so that it points to the end of the state buffer */ - pS2 = pState + (S->N - 1u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - /* Initializing the loop counter to N/2 >> 2 for loop unrolling by 4 */ - i = S->Nby2 >> 2u; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - *pS1++ = *pbuff++; - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = S->N >> 2u; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. - * Compute 4 outputs at a time */ - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q31(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.29 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ - arm_shift_q31(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* Initializing the loop counter to N >> 2 for loop unrolling by 4 */ - i = (S->N - 1u) >> 2u; - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* First part of the processing with loop unrolling. Compute 4 outputs at a time. - ** a second loop below computes the remaining 1 to 3 samples. */ - do - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - in = *pS1++ - in; - *pbuff++ = in; - pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* If the blockSize is not a multiple of 4, compute any remaining output samples here. - ** No loop unrolling is used. */ - i = (S->N - 1u) % 0x4u; - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter to N/4 instead of N for loop unrolling */ - i = S->N >> 2u; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - /* Processing with loop unrolling 4 times as N is always multiple of 4. Compute 4 outputs at a time */ - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - -#else - - /* Run the below code for Cortex-M0 */ - - /* Initializing the loop counter to N/2 */ - i = S->Nby2; - - do - { - /* Re-ordering of even and odd elements */ - /* pState[i] = pInlineBuffer[2*i] */ - *pS1++ = *pbuff++; - /* pState[N-i-1] = pInlineBuffer[2*i+1] */ - *pS2-- = *pbuff++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - /* pbuff initialized to input buffer */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Initializing the loop counter */ - i = S->N; - - do - { - /* Writing the re-ordered output back to inplace input buffer */ - *pbuff++ = *pS1++; - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - - - /* --------------------------------------------------------- - * Step2: Calculate RFFT for N-point input - * ---------------------------------------------------------- */ - /* pInlineBuffer is real input of length N , pState is the complex output of length 2N */ - arm_rfft_q31(S->pRfft, pInlineBuffer, pState); - - /*---------------------------------------------------------------------- - * Step3: Multiply the FFT output with the weights. - *----------------------------------------------------------------------*/ - arm_cmplx_mult_cmplx_q31(pState, weights, pState, S->N); - - /* The output of complex multiplication is in 3.29 format. - * Hence changing the format of N (i.e. 2*N elements) complex numbers to 1.31 format by shifting left by 2 bits. */ - arm_shift_q31(pState, 2, pState, S->N * 2); - - /* ----------- Post-processing ---------- */ - /* DCT-IV can be obtained from DCT-II by the equation, - * Y4(k) = Y2(k) - Y4(k-1) and Y4(-1) = Y4(0) - * Hence, Y4(0) = Y2(0)/2 */ - /* Getting only real part from the output and Converting to DCT-IV */ - - /* pbuff initialized to input buffer. */ - pbuff = pInlineBuffer; - - /* pS1 initialized to pState */ - pS1 = pState; - - /* Calculating Y4(0) from Y2(0) using Y4(0) = Y2(0)/2 */ - in = *pS1++ >> 1u; - /* input buffer acts as inplace, so output values are stored in the input itself. */ - *pbuff++ = in; - - /* pState pointer is incremented twice as the real values are located alternatively in the array */ - pS1++; - - /* Initializing the loop counter */ - i = (S->N - 1u); - - while(i > 0u) - { - /* Calculating Y4(1) to Y4(N-1) from Y2 using equation Y4(k) = Y2(k) - Y4(k-1) */ - /* pState pointer (pS1) is incremented twice as the real values are located alternatively in the array */ - in = *pS1++ - in; - *pbuff++ = in; - /* points to the next real value */ - pS1++; - - /* Decrement the loop counter */ - i--; - } - - - /*------------ Normalizing the output by multiplying with the normalizing factor ----------*/ - - /* Initializing the loop counter */ - i = S->N; - - /* pbuff initialized to the pInlineBuffer(now contains the output values) */ - pbuff = pInlineBuffer; - - do - { - /* Multiplying pInlineBuffer with the normalizing factor sqrt(2/N) */ - in = *pbuff; - *pbuff++ = ((q31_t) (((q63_t) in * S->normalize) >> 31)); - - /* Decrement the loop counter */ - i--; - } while(i > 0u); - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - -/** - * @} end of DCT4_IDCT4 group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c deleted file mode 100644 index 2043a4e0df..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_f32.c +++ /dev/null @@ -1,382 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_f32.c -* -* Description: RFFT & RIFFT Floating point process function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @defgroup RFFT_RIFFT Real FFT Functions - * - * \par - * Complex FFT/IFFT typically assumes complex input and output. However many applications use real valued data in time domain. - * Real FFT/IFFT efficiently process real valued sequences with the advantage of requirement of low memory and with less complexity. - * - * \par - * This set of functions implements Real Fast Fourier Transforms(RFFT) and Real Inverse Fast Fourier Transform(RIFFT) - * for Q15, Q31, and floating-point data types. - * - * - * \par Algorithm: - * - * Real Fast Fourier Transform: - * \par - * Real FFT of N-point is calculated using CFFT of N/2-point and Split RFFT process as shown below figure. - * \par - * \image html RFFT.gif "Real Fast Fourier Transform" - * \par - * The RFFT functions operate on blocks of input and output data and each call to the function processes - * fftLenR samples through the transform. pSrc points to input array containing fftLenR values. - * pDst points to output array containing 2*fftLenR values. \n - * Input for real FFT is in the order of - *
{real[0], real[1], real[2], real[3], ..}
- * Output for real FFT is complex and are in the order of - *
{real(0), imag(0), real(1), imag(1), ...}
- * - * Real Inverse Fast Fourier Transform: - * \par - * Real IFFT of N-point is calculated using Split RIFFT process and CFFT of N/2-point as shown below figure. - * \par - * \image html RIFFT.gif "Real Inverse Fast Fourier Transform" - * \par - * The RIFFT functions operate on blocks of input and output data and each call to the function processes - * 2*fftLenR samples through the transform. pSrc points to input array containing 2*fftLenR values. - * pDst points to output array containing fftLenR values. \n - * Input for real IFFT is complex and are in the order of - *
{real(0), imag(0), real(1), imag(1), ...}
- * Output for real IFFT is real and in the order of - *
{real[0], real[1], real[2], real[3], ..}
- * - * \par Lengths supported by the transform: - * \par - * Real FFT/IFFT supports the lengths [128, 512, 2048], as it internally uses CFFT/CIFFT. - * - * \par Instance Structure - * A separate instance structure must be defined for each Instance but the twiddle factors can be reused. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Sets the values of the internal structure fields. - * - Initializes twiddle factor tables. - * - Initializes CFFT data structure fields. - * \par - * Use of the initialization function is optional. - * However, if the initialization function is used, then the instance structure cannot be placed into a const data section. - * To place an instance structure into a const data section, the instance structure must be manually initialized. - * Manually initialize the instance structure as follows: - *
    
- *arm_rfft_instance_f32 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};    
- *arm_rfft_instance_q31 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};    
- *arm_rfft_instance_q15 S = {fftLenReal, fftLenBy2, ifftFlagR, bitReverseFlagR, twidCoefRModifier, pTwiddleAReal, pTwiddleBReal, pCfft};    
- * 
- * where fftLenReal length of RFFT/RIFFT; fftLenBy2 length of CFFT/CIFFT. - * ifftFlagR Flag for selection of RFFT or RIFFT(Set ifftFlagR to calculate RIFFT otherwise calculates RFFT); - * bitReverseFlagR Flag for selection of output order(Set bitReverseFlagR to output in normal order otherwise output in bit reversed order); - * twidCoefRModifier modifier for twiddle factor table which supports 128, 512, 2048 RFFT lengths with same table; - * pTwiddleARealpoints to A array of twiddle coefficients; pTwiddleBRealpoints to B array of twiddle coefficients; - * pCfft points to the CFFT Instance structure. The CFFT structure also needs to be initialized, refer to arm_cfft_radix4_f32() for details regarding - * static initialization of cfft structure. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the RFFT/RIFFT function. - * Refer to the function specific documentation below for usage guidelines. - */ - -/*-------------------------------------------------------------------- - * Internal functions prototypes - *--------------------------------------------------------------------*/ - -void arm_split_rfft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier); -void arm_split_rifft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the floating-point RFFT/RIFFT. - * @param[in] *S points to an instance of the floating-point RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - */ - -void arm_rfft_f32( - const arm_rfft_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst) -{ - const arm_cfft_radix4_instance_f32 *S_CFFT = S->pCfft; - - - /* Calculation of Real IFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - - /* Complex radix-4 IFFT process */ - arm_radix4_butterfly_inverse_f32(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier, - S_CFFT->onebyfftLen); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_f32(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - - /* Calculation of RFFT of input */ - - /* Complex radix-4 FFT process */ - arm_radix4_butterfly_f32(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_f32(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - - /* Real FFT core process */ - arm_split_rfft_f32(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - -/** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rfft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - float32_t outR, outI; /* Temporary variables for output */ - float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - float32_t *pDst1 = &pDst[2], *pDst2 = &pDst[(4u * fftLen) - 1u]; /* temp pointers for output buffer */ - float32_t *pSrc1 = &pSrc[2], *pSrc2 = &pSrc[(2u * fftLen) - 1u]; /* temp pointers for input buffer */ - - /* Init coefficient pointers */ - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - i = fftLen - 1u; - - while(i > 0u) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - /* read pATable[2 * i] */ - CoefA1 = *pCoefA++; - /* pATable[2 * i + 1] */ - CoefA2 = *pCoefA; - - /* pSrc[2 * i] * pATable[2 * i] */ - outR = *pSrc1 * CoefA1; - /* pSrc[2 * i] * CoefA2 */ - outI = *pSrc1++ * CoefA2; - - /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ - outR -= (*pSrc1 + *pSrc2) * CoefA2; - /* pSrc[2 * i + 1] * CoefA1 */ - outI += *pSrc1++ * CoefA1; - - CoefB1 = *pCoefB; - - /* pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ - outI -= *pSrc2-- * CoefB1; - /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ - outI -= *pSrc2 * CoefA2; - - /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ - outR += *pSrc2-- * CoefB1; - - /* write output */ - *pDst1++ = outR; - *pDst1++ = outI; - - /* write complex conjugate output */ - *pDst2-- = -outI; - *pDst2-- = outR; - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - i--; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0.0f; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0.0f; - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rifft_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pATable, - float32_t * pBTable, - float32_t * pDst, - uint32_t modifier) -{ - float32_t outR, outI; /* Temporary variables for output */ - float32_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - float32_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - float32_t *pSrc1 = &pSrc[0], *pSrc2 = &pSrc[(2u * fftLen) + 1u]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - while(fftLen > 0u) - { - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pSrc[2 * i] * CoefA1 */ - outR = *pSrc1 * CoefA1; - - /* - pSrc[2 * i] * CoefA2 */ - outI = -(*pSrc1++) * CoefA2; - - /* (pSrc[2 * i + 1] + pSrc[2 * fftLen - 2 * i + 1]) * CoefA2 */ - outR += (*pSrc1 + *pSrc2) * CoefA2; - - /* pSrc[2 * i + 1] * CoefA1 */ - outI += (*pSrc1++) * CoefA1; - - CoefB1 = *pCoefB; - - /* - pSrc[2 * fftLen - 2 * i + 1] * CoefB1 */ - outI -= *pSrc2-- * CoefB1; - - /* pSrc[2 * fftLen - 2 * i] * CoefB1 */ - outR += *pSrc2 * CoefB1; - - /* pSrc[2 * fftLen - 2 * i] * CoefA2 */ - outI += *pSrc2-- * CoefA2; - - /* write output */ - *pDst++ = outR; - *pDst++ = outI; - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - /* Decrement loop count */ - fftLen--; - } - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c deleted file mode 100644 index 7a54df6e21..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_f32.c +++ /dev/null @@ -1,8369 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_f32.c -* -* Description: RFFT & RIFFT Floating point initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** -* \par -* Generation of realCoefA array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-*  {    
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-*  } 
-*/ - - - -static const float32_t realCoefA[8192] = { - 0.500000000000000f, -0.500000000000000f, 0.499616503715515f, - -0.499999850988388f, - 0.499233007431030f, -0.499999403953552f, 0.498849511146545f, - -0.499998688697815f, - 0.498466014862061f, -0.499997645616531f, 0.498082518577576f, - -0.499996334314346f, - 0.497699022293091f, -0.499994695186615f, 0.497315555810928f, - -0.499992787837982f, - 0.496932059526443f, -0.499990582466125f, 0.496548563241959f, - -0.499988079071045f, - 0.496165096759796f, -0.499985307455063f, 0.495781600475311f, - -0.499982208013535f, - 0.495398133993149f, -0.499978810548782f, 0.495014637708664f, - -0.499975144863129f, - 0.494631171226501f, -0.499971181154251f, 0.494247704744339f, - -0.499966919422150f, - 0.493864238262177f, -0.499962359666824f, 0.493480771780014f, - -0.499957501888275f, - 0.493097305297852f, -0.499952346086502f, 0.492713838815689f, - -0.499946922063828f, - 0.492330402135849f, -0.499941170215607f, 0.491946935653687f, - -0.499935150146484f, - 0.491563498973846f, -0.499928832054138f, 0.491180062294006f, - -0.499922215938568f, - 0.490796625614166f, -0.499915301799774f, 0.490413218736649f, - -0.499908089637756f, - 0.490029782056808f, -0.499900579452515f, 0.489646375179291f, - -0.499892801046371f, - 0.489262968301773f, -0.499884694814682f, 0.488879561424255f, - -0.499876320362091f, - 0.488496154546738f, -0.499867647886276f, 0.488112777471542f, - -0.499858677387238f, - 0.487729400396347f, -0.499849408864975f, 0.487346023321152f, - -0.499839842319489f, - 0.486962646245956f, -0.499830007553101f, 0.486579269170761f, - -0.499819844961166f, - 0.486195921897888f, -0.499809414148331f, 0.485812574625015f, - -0.499798685312271f, - 0.485429257154465f, -0.499787658452988f, 0.485045909881592f, - -0.499776333570480f, - 0.484662592411041f, -0.499764710664749f, 0.484279274940491f, - -0.499752789735794f, - 0.483895987272263f, -0.499740600585938f, 0.483512699604034f, - -0.499728083610535f, - 0.483129411935806f, -0.499715298414230f, 0.482746154069901f, - -0.499702215194702f, - 0.482362866401672f, -0.499688833951950f, 0.481979638338089f, - -0.499675154685974f, - 0.481596380472183f, -0.499661177396774f, 0.481213152408600f, - -0.499646931886673f, - 0.480829954147339f, -0.499632388353348f, 0.480446726083755f, - -0.499617516994476f, - 0.480063527822495f, -0.499602377414703f, 0.479680359363556f, - -0.499586939811707f, - 0.479297190904617f, -0.499571204185486f, 0.478914022445679f, - -0.499555170536041f, - 0.478530883789063f, -0.499538868665695f, 0.478147745132446f, - -0.499522238969803f, - 0.477764606475830f, -0.499505341053009f, 0.477381497621536f, - -0.499488145112991f, - 0.476998418569565f, -0.499470651149750f, 0.476615339517593f, - -0.499452859163284f, - 0.476232260465622f, -0.499434769153595f, 0.475849211215973f, - -0.499416410923004f, - 0.475466161966324f, -0.499397724866867f, 0.475083142518997f, - -0.499378770589828f, - 0.474700123071671f, -0.499359518289566f, 0.474317133426666f, - -0.499339967966080f, - 0.473934143781662f, -0.499320119619370f, 0.473551183938980f, - -0.499299973249435f, - 0.473168224096298f, -0.499279528856277f, 0.472785294055939f, - -0.499258816242218f, - 0.472402364015579f, -0.499237775802612f, 0.472019463777542f, - -0.499216467142105f, - 0.471636593341827f, -0.499194860458374f, 0.471253722906113f, - -0.499172955751419f, - 0.470870882272720f, -0.499150782823563f, 0.470488041639328f, - -0.499128282070160f, - 0.470105201005936f, -0.499105513095856f, 0.469722419977188f, - -0.499082416296005f, - 0.469339638948441f, -0.499059051275253f, 0.468956857919693f, - -0.499035388231277f, - 0.468574106693268f, -0.499011427164078f, 0.468191385269165f, - -0.498987197875977f, - 0.467808693647385f, -0.498962640762329f, 0.467426002025604f, - -0.498937815427780f, - 0.467043310403824f, -0.498912662267685f, 0.466660678386688f, - -0.498887240886688f, - 0.466278046369553f, -0.498861521482468f, 0.465895414352417f, - -0.498835533857346f, - 0.465512841939926f, -0.498809218406677f, 0.465130269527435f, - -0.498782604932785f, - 0.464747726917267f, -0.498755723237991f, 0.464365184307098f, - -0.498728543519974f, - 0.463982671499252f, -0.498701065778732f, 0.463600188493729f, - -0.498673290014267f, - 0.463217705488205f, -0.498645216226578f, 0.462835282087326f, - -0.498616874217987f, - 0.462452858686447f, -0.498588204383850f, 0.462070435285568f, - -0.498559266328812f, - 0.461688071489334f, -0.498530030250549f, 0.461305707693100f, - -0.498500496149063f, - 0.460923373699188f, -0.498470664024353f, 0.460541069507599f, - -0.498440563678741f, - 0.460158795118332f, -0.498410135507584f, 0.459776520729065f, - -0.498379439115524f, - 0.459394276142120f, -0.498348444700241f, 0.459012061357498f, - -0.498317152261734f, - 0.458629876375198f, -0.498285561800003f, 0.458247691392899f, - -0.498253703117371f, - 0.457865566015244f, -0.498221516609192f, 0.457483440637589f, - -0.498189061880112f, - 0.457101345062256f, -0.498156309127808f, 0.456719279289246f, - -0.498123258352280f, - 0.456337243318558f, -0.498089909553528f, 0.455955207347870f, - -0.498056292533875f, - 0.455573230981827f, -0.498022347688675f, 0.455191254615784f, - -0.497988134622574f, - 0.454809308052063f, -0.497953623533249f, 0.454427421092987f, - -0.497918814420700f, - 0.454045534133911f, -0.497883707284927f, 0.453663676977158f, - -0.497848302125931f, - 0.453281819820404f, -0.497812628746033f, 0.452900022268295f, - -0.497776657342911f, - 0.452518254518509f, -0.497740387916565f, 0.452136516571045f, - -0.497703820466995f, - 0.451754778623581f, -0.497666954994202f, 0.451373100280762f, - -0.497629791498184f, - 0.450991421937943f, -0.497592359781265f, 0.450609803199768f, - -0.497554630041122f, - 0.450228184461594f, -0.497516602277756f, 0.449846625328064f, - -0.497478276491165f, - 0.449465066194534f, -0.497439652681351f, 0.449083566665649f, - -0.497400760650635f, - 0.448702067136765f, -0.497361570596695f, 0.448320597410202f, - -0.497322082519531f, - 0.447939187288284f, -0.497282296419144f, 0.447557777166367f, - -0.497242212295532f, - 0.447176426649094f, -0.497201830148697f, 0.446795076131821f, - -0.497161179780960f, - 0.446413785219193f, -0.497120231389999f, 0.446032524108887f, - -0.497078984975815f, - 0.445651292800903f, -0.497037440538406f, 0.445270061492920f, - -0.496995598077774f, - 0.444888889789581f, -0.496953487396240f, 0.444507747888565f, - -0.496911078691483f, - 0.444126635789871f, -0.496868371963501f, 0.443745553493500f, - -0.496825367212296f, - 0.443364530801773f, -0.496782064437866f, 0.442983508110046f, - -0.496738493442535f, - 0.442602545022964f, -0.496694594621658f, 0.442221581935883f, - -0.496650427579880f, - 0.441840678453445f, -0.496605962514877f, 0.441459804773331f, - -0.496561229228973f, - 0.441078960895538f, -0.496516168117523f, 0.440698176622391f, - -0.496470838785172f, - 0.440317392349243f, -0.496425211429596f, 0.439936667680740f, - -0.496379286050797f, - 0.439555943012238f, -0.496333062648773f, 0.439175277948380f, - -0.496286571025848f, - 0.438794672489166f, -0.496239781379700f, 0.438414067029953f, - -0.496192663908005f, - 0.438033521175385f, -0.496145308017731f, 0.437653005123138f, - -0.496097624301910f, - 0.437272518873215f, -0.496049642562866f, 0.436892062425613f, - -0.496001392602921f, - 0.436511665582657f, -0.495952844619751f, 0.436131268739700f, - -0.495903998613358f, - 0.435750931501389f, -0.495854884386063f, 0.435370653867722f, - -0.495805442333221f, - 0.434990376234055f, -0.495755732059479f, 0.434610158205032f, - -0.495705723762512f, - 0.434229999780655f, -0.495655417442322f, 0.433849841356277f, - -0.495604842901230f, - 0.433469742536545f, -0.495553970336914f, 0.433089673519135f, - -0.495502769947052f, - 0.432709634304047f, -0.495451331138611f, 0.432329654693604f, - -0.495399564504623f, - 0.431949704885483f, -0.495347499847412f, 0.431569814682007f, - -0.495295166969299f, - 0.431189924478531f, -0.495242536067963f, 0.430810123682022f, - -0.495189607143402f, - 0.430430322885513f, -0.495136409997940f, 0.430050581693649f, - -0.495082914829254f, - 0.429670870304108f, -0.495029091835022f, 0.429291218519211f, - -0.494975030422211f, - 0.428911596536636f, -0.494920641183853f, 0.428532034158707f, - -0.494865983724594f, - 0.428152471780777f, -0.494810998439789f, 0.427772998809814f, - -0.494755744934082f, - 0.427393525838852f, -0.494700223207474f, 0.427014142274857f, - -0.494644373655319f, - 0.426634758710861f, -0.494588255882263f, 0.426255434751511f, - -0.494531840085983f, - 0.425876170396805f, -0.494475126266479f, 0.425496935844421f, - -0.494418144226074f, - 0.425117731094360f, -0.494360834360123f, 0.424738585948944f, - -0.494303256273270f, - 0.424359470605850f, -0.494245409965515f, 0.423980414867401f, - -0.494187235832214f, - 0.423601418733597f, -0.494128793478012f, 0.423222452402115f, - -0.494070053100586f, - 0.422843515872955f, -0.494011014699936f, 0.422464638948441f, - -0.493951678276062f, - 0.422085791826248f, -0.493892073631287f, 0.421707004308701f, - -0.493832170963287f, - 0.421328276395798f, -0.493771970272064f, 0.420949578285217f, - -0.493711471557617f, - 0.420570939779282f, -0.493650704622269f, 0.420192331075668f, - -0.493589639663696f, - 0.419813781976700f, -0.493528276681900f, 0.419435262680054f, - -0.493466645479202f, - 0.419056802988052f, -0.493404686450958f, 0.418678402900696f, - -0.493342459201813f, - 0.418300032615662f, -0.493279963731766f, 0.417921721935272f, - -0.493217140436172f, - 0.417543441057205f, -0.493154048919678f, 0.417165219783783f, - -0.493090659379959f, - 0.416787058115005f, -0.493026971817017f, 0.416408926248550f, - -0.492963016033173f, - 0.416030853986740f, -0.492898762226105f, 0.415652841329575f, - -0.492834210395813f, - 0.415274858474731f, -0.492769360542297f, 0.414896935224533f, - -0.492704242467880f, - 0.414519041776657f, -0.492638826370239f, 0.414141237735748f, - -0.492573112249374f, - 0.413763463497162f, -0.492507129907608f, 0.413385748863220f, - -0.492440819740295f, - 0.413008064031601f, -0.492374241352081f, 0.412630438804626f, - -0.492307394742966f, - 0.412252873182297f, -0.492240220308304f, 0.411875367164612f, - -0.492172777652740f, - 0.411497890949249f, -0.492105036973953f, 0.411120474338531f, - -0.492037028074265f, - 0.410743117332459f, -0.491968721151352f, 0.410365819931030f, - -0.491900116205215f, - 0.409988552331924f, -0.491831213235855f, 0.409611344337463f, - -0.491762012243271f, - 0.409234195947647f, -0.491692543029785f, 0.408857107162476f, - -0.491622805595398f, - 0.408480048179626f, -0.491552740335464f, 0.408103078603745f, - -0.491482406854630f, - 0.407726138830185f, -0.491411775350571f, 0.407349258661270f, - -0.491340845823288f, - 0.406972438097000f, -0.491269648075104f, 0.406595647335052f, - -0.491198152303696f, - 0.406218945980072f, -0.491126358509064f, 0.405842274427414f, - -0.491054296493530f, - 0.405465662479401f, -0.490981936454773f, 0.405089110136032f, - -0.490909278392792f, - 0.404712617397308f, -0.490836352109909f, 0.404336184263229f, - -0.490763127803802f, - 0.403959810733795f, -0.490689605474472f, 0.403583467006683f, - -0.490615785121918f, - 0.403207212686539f, -0.490541696548462f, 0.402830988168716f, - -0.490467309951782f, - 0.402454853057861f, -0.490392625331879f, 0.402078747749329f, - -0.490317672491074f, - 0.401702702045441f, -0.490242421627045f, 0.401326715946198f, - -0.490166902542114f, - 0.400950789451599f, -0.490091055631638f, 0.400574922561646f, - -0.490014940500259f, - 0.400199115276337f, -0.489938557147980f, 0.399823367595673f, - -0.489861875772476f, - 0.399447679519653f, -0.489784896373749f, 0.399072051048279f, - -0.489707618951797f, - 0.398696482181549f, -0.489630073308945f, 0.398320972919464f, - -0.489552229642868f, - 0.397945523262024f, -0.489474087953568f, 0.397570133209229f, - -0.489395678043365f, - 0.397194802761078f, -0.489316970109940f, 0.396819531917572f, - -0.489237964153290f, - 0.396444320678711f, -0.489158689975739f, 0.396069169044495f, - -0.489079117774963f, - 0.395694077014923f, -0.488999247550964f, 0.395319044589996f, - -0.488919109106064f, - 0.394944071769714f, -0.488838672637939f, 0.394569188356400f, - -0.488757967948914f, - 0.394194334745407f, -0.488676935434341f, 0.393819570541382f, - -0.488595664501190f, - 0.393444836139679f, -0.488514065742493f, 0.393070191144943f, - -0.488432198762894f, - 0.392695605754852f, -0.488350033760071f, 0.392321079969406f, - -0.488267600536346f, - 0.391946613788605f, -0.488184869289398f, 0.391572207212448f, - -0.488101840019226f, - 0.391197860240936f, -0.488018542528152f, 0.390823602676392f, - -0.487934947013855f, - 0.390449374914169f, -0.487851053476334f, 0.390075236558914f, - -0.487766891717911f, - 0.389701157808304f, -0.487682431936264f, 0.389327138662338f, - -0.487597703933716f, - 0.388953179121017f, -0.487512677907944f, 0.388579308986664f, - -0.487427353858948f, - 0.388205498456955f, -0.487341761589050f, 0.387831717729568f, - -0.487255871295929f, - 0.387458056211472f, -0.487169682979584f, 0.387084424495697f, - -0.487083226442337f, - 0.386710882186890f, -0.486996471881866f, 0.386337369680405f, - -0.486909449100494f, - 0.385963946580887f, -0.486822128295898f, 0.385590612888336f, - -0.486734509468079f, - 0.385217308998108f, -0.486646622419357f, 0.384844094514847f, - -0.486558437347412f, - 0.384470939636230f, -0.486469984054565f, 0.384097874164581f, - -0.486381232738495f, - 0.383724838495255f, -0.486292183399200f, 0.383351892232895f, - -0.486202865839005f, - 0.382979035377502f, -0.486113250255585f, 0.382606208324432f, - -0.486023366451263f, - 0.382233470678329f, -0.485933154821396f, 0.381860792636871f, - -0.485842704772949f, - 0.381488204002380f, -0.485751956701279f, 0.381115674972534f, - -0.485660910606384f, - 0.380743205547333f, -0.485569566488266f, 0.380370795726776f, - -0.485477954149246f, - 0.379998475313187f, -0.485386073589325f, 0.379626244306564f, - -0.485293895006180f, - 0.379254043102264f, -0.485201418399811f, 0.378881961107254f, - -0.485108673572540f, - 0.378509908914566f, -0.485015630722046f, 0.378137946128845f, - -0.484922289848328f, - 0.377766042947769f, -0.484828680753708f, 0.377394229173660f, - -0.484734803438187f, - 0.377022475004196f, -0.484640628099442f, 0.376650810241699f, - -0.484546154737473f, - 0.376279205083847f, -0.484451413154602f, 0.375907659530640f, - -0.484356373548508f, - 0.375536203384399f, -0.484261035919189f, 0.375164806842804f, - -0.484165430068970f, - 0.374793499708176f, -0.484069555997849f, 0.374422252178192f, - -0.483973383903503f, - 0.374051094055176f, -0.483876913785934f, 0.373679995536804f, - -0.483780175447464f, - 0.373308986425400f, -0.483683139085770f, 0.372938036918640f, - -0.483585834503174f, - 0.372567176818848f, -0.483488231897354f, 0.372196376323700f, - -0.483390361070633f, - 0.371825665235519f, -0.483292192220688f, 0.371455013751984f, - -0.483193725347519f, - 0.371084451675415f, -0.483094990253448f, 0.370713949203491f, - -0.482995986938477f, - 0.370343536138535f, -0.482896685600281f, 0.369973212480545f, - -0.482797086238861f, - 0.369602948427200f, -0.482697218656540f, 0.369232743978500f, - -0.482597053050995f, - 0.368862658739090f, -0.482496619224548f, 0.368492603302002f, - -0.482395917177200f, - 0.368122667074203f, -0.482294887304306f, 0.367752790451050f, - -0.482193619012833f, - 0.367382973432541f, -0.482092022895813f, 0.367013275623322f, - -0.481990188360214f, - 0.366643607616425f, -0.481888025999069f, 0.366274058818817f, - -0.481785595417023f, - 0.365904569625854f, -0.481682896614075f, 0.365535169839859f, - -0.481579899787903f, - 0.365165829658508f, -0.481476634740829f, 0.364796578884125f, - -0.481373071670532f, - 0.364427417516708f, -0.481269240379334f, 0.364058345556259f, - -0.481165111064911f, - 0.363689333200455f, -0.481060713529587f, 0.363320380449295f, - -0.480956017971039f, - 0.362951546907425f, -0.480851024389267f, 0.362582772970200f, - -0.480745792388916f, - 0.362214088439941f, -0.480640232563019f, 0.361845493316650f, - -0.480534434318542f, - 0.361476957798004f, -0.480428308248520f, 0.361108511686325f, - -0.480321943759918f, - 0.360740154981613f, -0.480215251445770f, 0.360371887683868f, - -0.480108320713043f, - 0.360003679990768f, -0.480001062154770f, 0.359635561704636f, - -0.479893565177917f, - 0.359267532825470f, -0.479785770177841f, 0.358899593353271f, - -0.479677677154541f, - 0.358531713485718f, -0.479569315910339f, 0.358163923025131f, - -0.479460656642914f, - 0.357796221971512f, -0.479351729154587f, 0.357428610324860f, - -0.479242533445358f, - 0.357061088085175f, -0.479133039712906f, 0.356693625450134f, - -0.479023247957230f, - 0.356326282024384f, -0.478913217782974f, 0.355958998203278f, - -0.478802859783173f, - 0.355591803789139f, -0.478692263364792f, 0.355224698781967f, - -0.478581339120865f, - 0.354857653379440f, -0.478470176458359f, 0.354490727186203f, - -0.478358715772629f, - 0.354123860597610f, -0.478246957063675f, 0.353757113218308f, - -0.478134930133820f, - 0.353390425443649f, -0.478022634983063f, 0.353023827075958f, - -0.477910041809082f, - 0.352657318115234f, -0.477797180414200f, 0.352290898561478f, - -0.477684020996094f, - 0.351924568414688f, -0.477570593357086f, 0.351558297872543f, - -0.477456867694855f, - 0.351192146539688f, -0.477342873811722f, 0.350826084613800f, - -0.477228611707687f, - 0.350460082292557f, -0.477114051580429f, 0.350094199180603f, - -0.476999223232269f, - 0.349728375673294f, -0.476884096860886f, 0.349362671375275f, - -0.476768702268600f, - 0.348997026681900f, -0.476653009653091f, 0.348631471395493f, - -0.476537048816681f, - 0.348266035318375f, -0.476420819759369f, 0.347900658845901f, - -0.476304292678833f, - 0.347535371780396f, -0.476187497377396f, 0.347170203924179f, - -0.476070433855057f, - 0.346805095672607f, -0.475953072309494f, 0.346440106630325f, - -0.475835442543030f, - 0.346075177192688f, -0.475717514753342f, 0.345710366964340f, - -0.475599318742752f, - 0.345345616340637f, -0.475480824708939f, 0.344980984926224f, - -0.475362062454224f, - 0.344616413116455f, -0.475243031978607f, 0.344251960515976f, - -0.475123733282089f, - 0.343887597322464f, -0.475004136562347f, 0.343523323535919f, - -0.474884241819382f, - 0.343159139156342f, -0.474764078855515f, 0.342795044183731f, - -0.474643647670746f, - 0.342431038618088f, -0.474522948265076f, 0.342067122459412f, - -0.474401950836182f, - 0.341703325510025f, -0.474280685186386f, 0.341339588165283f, - -0.474159121513367f, - 0.340975970029831f, -0.474037289619446f, 0.340612411499023f, - -0.473915189504623f, - 0.340248972177505f, -0.473792791366577f, 0.339885622262955f, - -0.473670125007629f, - 0.339522391557693f, -0.473547190427780f, 0.339159220457077f, - -0.473423957824707f, - 0.338796168565750f, -0.473300457000732f, 0.338433176279068f, - -0.473176687955856f, - 0.338070303201675f, -0.473052620887756f, 0.337707549333572f, - -0.472928285598755f, - 0.337344855070114f, -0.472803652286530f, 0.336982280015945f, - -0.472678780555725f, - 0.336619764566422f, -0.472553610801697f, 0.336257368326187f, - -0.472428143024445f, - 0.335895091295242f, -0.472302407026291f, 0.335532873868942f, - -0.472176402807236f, - 0.335170775651932f, -0.472050130367279f, 0.334808766841888f, - -0.471923559904099f, - 0.334446847438812f, -0.471796721220016f, 0.334085017442703f, - -0.471669614315033f, - 0.333723306655884f, -0.471542209386826f, 0.333361685276031f, - -0.471414536237717f, - 0.333000183105469f, -0.471286594867706f, 0.332638740539551f, - -0.471158385276794f, - 0.332277417182922f, -0.471029877662659f, 0.331916213035584f, - -0.470901101827621f, - 0.331555068492889f, -0.470772027969360f, 0.331194043159485f, - -0.470642685890198f, - 0.330833107233047f, -0.470513075590134f, 0.330472290515900f, - -0.470383197069168f, - 0.330111563205719f, -0.470253020524979f, 0.329750925302505f, - -0.470122605562210f, - 0.329390406608582f, -0.469991862773895f, 0.329029977321625f, - -0.469860881567001f, - 0.328669637441635f, -0.469729602336884f, 0.328309416770935f, - -0.469598054885864f, - 0.327949285507202f, -0.469466239213943f, 0.327589273452759f, - -0.469334155321121f, - 0.327229350805283f, -0.469201773405075f, 0.326869517564774f, - -0.469069123268127f, - 0.326509803533554f, -0.468936175107956f, 0.326150178909302f, - -0.468802988529205f, - 0.325790673494339f, -0.468669503927231f, 0.325431257486343f, - -0.468535751104355f, - 0.325071930885315f, -0.468401730060577f, 0.324712723493576f, - -0.468267410993576f, - 0.324353635311127f, -0.468132823705673f, 0.323994606733322f, - -0.467997968196869f, - 0.323635727167130f, -0.467862844467163f, 0.323276937007904f, - -0.467727422714233f, - 0.322918236255646f, -0.467591762542725f, 0.322559654712677f, - -0.467455804347992f, - 0.322201162576675f, -0.467319577932358f, 0.321842789649963f, - -0.467183053493500f, - 0.321484506130219f, -0.467046260833740f, 0.321126341819763f, - -0.466909229755402f, - 0.320768296718597f, -0.466771900653839f, 0.320410341024399f, - -0.466634273529053f, - 0.320052474737167f, -0.466496407985687f, 0.319694727659225f, - -0.466358244419098f, - 0.319337099790573f, -0.466219812631607f, 0.318979561328888f, - -0.466081112623215f, - 0.318622142076492f, -0.465942144393921f, 0.318264812231064f, - -0.465802878141403f, - 0.317907601594925f, -0.465663343667984f, 0.317550510168076f, - -0.465523540973663f, - 0.317193508148193f, -0.465383470058441f, 0.316836595535278f, - -0.465243130922318f, - 0.316479831933975f, -0.465102523565292f, 0.316123157739639f, - -0.464961618185043f, - 0.315766572952271f, -0.464820444583893f, 0.315410137176514f, - -0.464679002761841f, - 0.315053790807724f, -0.464537292718887f, 0.314697533845901f, - -0.464395314455032f, - 0.314341396093369f, -0.464253038167953f, 0.313985377550125f, - -0.464110493659973f, - 0.313629478216171f, -0.463967710733414f, 0.313273668289185f, - -0.463824629783630f, - 0.312917977571487f, -0.463681250810623f, 0.312562376260757f, - -0.463537633419037f, - 0.312206923961639f, -0.463393747806549f, 0.311851561069489f, - -0.463249564170837f, - 0.311496287584305f, -0.463105112314224f, 0.311141163110733f, - -0.462960392236710f, - 0.310786128044128f, -0.462815403938293f, 0.310431212186813f, - -0.462670147418976f, - 0.310076385736465f, -0.462524622678757f, 0.309721708297729f, - -0.462378799915314f, - 0.309367120265961f, -0.462232738733292f, 0.309012651443481f, - -0.462086379528046f, - 0.308658272027969f, -0.461939752101898f, 0.308304041624069f, - -0.461792886257172f, - 0.307949900627136f, -0.461645722389221f, 0.307595878839493f, - -0.461498260498047f, - 0.307241976261139f, -0.461350560188293f, 0.306888192892075f, - -0.461202591657639f, - 0.306534498929977f, -0.461054325103760f, 0.306180924177170f, - -0.460905820131302f, - 0.305827468633652f, -0.460757017135620f, 0.305474132299423f, - -0.460607945919037f, - 0.305120915174484f, -0.460458606481552f, 0.304767817258835f, - -0.460309028625488f, - 0.304414808750153f, -0.460159152746201f, 0.304061919450760f, - -0.460008978843689f, - 0.303709149360657f, -0.459858566522598f, 0.303356528282166f, - -0.459707885980606f, - 0.303003966808319f, -0.459556937217712f, 0.302651554346085f, - -0.459405690431595f, - 0.302299261093140f, -0.459254205226898f, 0.301947087049484f, - -0.459102421998978f, - 0.301595002412796f, -0.458950400352478f, 0.301243066787720f, - -0.458798080682755f, - 0.300891220569611f, -0.458645492792130f, 0.300539493560791f, - -0.458492636680603f, - 0.300187885761261f, -0.458339542150497f, 0.299836426973343f, - -0.458186149597168f, - 0.299485057592392f, -0.458032488822937f, 0.299133807420731f, - -0.457878559827805f, - 0.298782676458359f, -0.457724362611771f, 0.298431664705276f, - -0.457569897174835f, - 0.298080772161484f, -0.457415163516998f, 0.297729998826981f, - -0.457260161638260f, - 0.297379344701767f, -0.457104891538620f, 0.297028809785843f, - -0.456949323415756f, - 0.296678394079208f, -0.456793516874313f, 0.296328097581863f, - -0.456637442111969f, - 0.295977920293808f, -0.456481099128723f, 0.295627862215042f, - -0.456324487924576f, - 0.295277923345566f, -0.456167578697205f, 0.294928103685379f, - -0.456010431051254f, - 0.294578403234482f, -0.455853015184402f, 0.294228851795197f, - -0.455695331096649f, - 0.293879389762878f, -0.455537378787994f, 0.293530046939850f, - -0.455379128456116f, - 0.293180853128433f, -0.455220639705658f, 0.292831748723984f, - -0.455061882734299f, - 0.292482793331146f, -0.454902857542038f, 0.292133957147598f, - -0.454743564128876f, - 0.291785210371017f, -0.454584002494812f, 0.291436612606049f, - -0.454424172639847f, - 0.291088134050369f, -0.454264044761658f, 0.290739774703979f, - -0.454103678464890f, - 0.290391564369202f, -0.453943043947220f, 0.290043443441391f, - -0.453782171010971f, - 0.289695471525192f, -0.453621000051498f, 0.289347589015961f, - -0.453459560871124f, - 0.288999855518341f, -0.453297853469849f, 0.288652241230011f, - -0.453135877847672f, - 0.288304775953293f, -0.452973634004593f, 0.287957400083542f, - -0.452811151742935f, - 0.287610173225403f, -0.452648371458054f, 0.287263035774231f, - -0.452485352754593f, - 0.286916047334671f, -0.452322036027908f, 0.286569178104401f, - -0.452158480882645f, - 0.286222457885742f, -0.451994657516479f, 0.285875827074051f, - -0.451830536127090f, - 0.285529345273972f, -0.451666176319122f, 0.285182982683182f, - -0.451501548290253f, - 0.284836769104004f, -0.451336652040482f, 0.284490644931793f, - -0.451171487569809f, - 0.284144669771194f, -0.451006084680557f, 0.283798813819885f, - -0.450840383768082f, - 0.283453077077866f, -0.450674414634705f, 0.283107489347458f, - -0.450508207082748f, - 0.282762020826340f, -0.450341701507568f, 0.282416671514511f, - -0.450174957513809f, - 0.282071471214294f, -0.450007945299149f, 0.281726360321045f, - -0.449840664863586f, - 0.281381398439407f, -0.449673116207123f, 0.281036585569382f, - -0.449505299329758f, - 0.280691891908646f, -0.449337244033813f, 0.280347317457199f, - -0.449168890714645f, - 0.280002862215042f, -0.449000298976898f, 0.279658555984497f, - -0.448831409215927f, - 0.279314368963242f, -0.448662281036377f, 0.278970301151276f, - -0.448492884635925f, - 0.278626382350922f, -0.448323249816895f, 0.278282582759857f, - -0.448153316974640f, - 0.277938932180405f, -0.447983115911484f, 0.277595400810242f, - -0.447812676429749f, - 0.277251988649368f, -0.447641968727112f, 0.276908725500107f, - -0.447470992803574f, - 0.276565581560135f, -0.447299748659134f, 0.276222556829453f, - -0.447128236293793f, - 0.275879681110382f, -0.446956485509872f, 0.275536954402924f, - -0.446784436702728f, - 0.275194346904755f, -0.446612149477005f, 0.274851858615875f, - -0.446439594030380f, - 0.274509519338608f, -0.446266770362854f, 0.274167299270630f, - -0.446093708276749f, - 0.273825198411942f, -0.445920348167419f, 0.273483246564865f, - -0.445746749639511f, - 0.273141443729401f, -0.445572882890701f, 0.272799760103226f, - -0.445398747920990f, - 0.272458195686340f, -0.445224374532700f, 0.272116780281067f, - -0.445049703121185f, - 0.271775513887405f, -0.444874793291092f, 0.271434366703033f, - -0.444699615240097f, - 0.271093338727951f, -0.444524168968201f, 0.270752459764481f, - -0.444348484277725f, - 0.270411729812622f, -0.444172531366348f, 0.270071119070053f, - -0.443996280431747f, - 0.269730657339096f, -0.443819820880890f, 0.269390314817429f, - -0.443643063306808f, - 0.269050091505051f, -0.443466067314148f, 0.268710047006607f, - -0.443288803100586f, - 0.268370121717453f, -0.443111270666122f, 0.268030315637589f, - -0.442933470010757f, - 0.267690658569336f, -0.442755430936813f, 0.267351150512695f, - -0.442577123641968f, - 0.267011761665344f, -0.442398548126221f, 0.266672492027283f, - -0.442219734191895f, - 0.266333401203156f, -0.442040622234344f, 0.265994429588318f, - -0.441861271858215f, - 0.265655577182770f, -0.441681683063507f, 0.265316903591156f, - -0.441501796245575f, - 0.264978319406509f, -0.441321671009064f, 0.264639914035797f, - -0.441141277551651f, - 0.264301627874374f, -0.440960645675659f, 0.263963490724564f, - -0.440779715776443f, - 0.263625472784042f, -0.440598547458649f, 0.263287603855133f, - -0.440417140722275f, - 0.262949883937836f, -0.440235435962677f, 0.262612313032150f, - -0.440053492784500f, - 0.262274861335754f, -0.439871311187744f, 0.261937558650970f, - -0.439688831567764f, - 0.261600375175476f, -0.439506113529205f, 0.261263370513916f, - -0.439323127269745f, - 0.260926485061646f, -0.439139902591705f, 0.260589718818665f, - -0.438956409692764f, - 0.260253131389618f, -0.438772648572922f, 0.259916663169861f, - -0.438588619232178f, - 0.259580343961716f, -0.438404351472855f, 0.259244143962860f, - -0.438219845294952f, - 0.258908122777939f, -0.438035041093826f, 0.258572220802307f, - -0.437849998474121f, - 0.258236467838287f, -0.437664687633514f, 0.257900834083557f, - -0.437479138374329f, - 0.257565379142761f, -0.437293320894241f, 0.257230043411255f, - -0.437107264995575f, - 0.256894856691360f, -0.436920911073685f, 0.256559818983078f, - -0.436734348535538f, - 0.256224930286407f, -0.436547487974167f, 0.255890160799026f, - -0.436360388994217f, - 0.255555540323257f, -0.436173021793365f, 0.255221068859100f, - -0.435985416173935f, - 0.254886746406555f, -0.435797542333603f, 0.254552572965622f, - -0.435609430074692f, - 0.254218548536301f, -0.435421019792557f, 0.253884643316269f, - -0.435232400894165f, - 0.253550916910172f, -0.435043483972549f, 0.253217309713364f, - -0.434854328632355f, - 0.252883851528168f, -0.434664934873581f, 0.252550542354584f, - -0.434475272893906f, - 0.252217382192612f, -0.434285342693329f, 0.251884341239929f, - -0.434095174074173f, - 0.251551479101181f, -0.433904737234116f, 0.251218736171722f, - -0.433714061975479f, - 0.250886172056198f, -0.433523118495941f, 0.250553727149963f, - -0.433331936597824f, - 0.250221431255341f, -0.433140486478806f, 0.249889299273491f, - -0.432948768138886f, - 0.249557301402092f, -0.432756811380386f, 0.249225467443466f, - -0.432564586400986f, - 0.248893767595291f, -0.432372123003006f, 0.248562216758728f, - -0.432179391384125f, - 0.248230814933777f, -0.431986421346664f, 0.247899547219276f, - -0.431793183088303f, - 0.247568443417549f, -0.431599706411362f, 0.247237488627434f, - -0.431405961513519f, - 0.246906682848930f, -0.431211978197098f, 0.246576011180878f, - -0.431017726659775f, - 0.246245503425598f, -0.430823236703873f, 0.245915144681931f, - -0.430628478527069f, - 0.245584934949875f, -0.430433481931686f, 0.245254859328270f, - -0.430238217115402f, - 0.244924947619438f, -0.430042684078217f, 0.244595184922218f, - -0.429846942424774f, - 0.244265571236610f, -0.429650902748108f, 0.243936106562614f, - -0.429454624652863f, - 0.243606805801392f, -0.429258108139038f, 0.243277639150620f, - -0.429061323404312f, - 0.242948621511459f, -0.428864300251007f, 0.242619767785072f, - -0.428667008876801f, - 0.242291063070297f, -0.428469479084015f, 0.241962507367134f, - -0.428271710872650f, - 0.241634100675583f, -0.428073674440384f, 0.241305842995644f, - -0.427875369787216f, - 0.240977749228477f, -0.427676826715469f, 0.240649804472923f, - -0.427478045225143f, - 0.240322008728981f, -0.427278995513916f, 0.239994361996651f, - -0.427079707384110f, - 0.239666879177094f, -0.426880151033401f, 0.239339530467987f, - -0.426680356264114f, - 0.239012360572815f, -0.426480293273926f, 0.238685324788094f, - -0.426279991865158f, - 0.238358452916145f, -0.426079452037811f, 0.238031730055809f, - -0.425878643989563f, - 0.237705156207085f, -0.425677597522736f, 0.237378746271133f, - -0.425476282835007f, - 0.237052485346794f, -0.425274729728699f, 0.236726388335228f, - -0.425072938203812f, - 0.236400425434113f, -0.424870878458023f, 0.236074641346931f, - -0.424668580293655f, - 0.235749006271362f, -0.424466013908386f, 0.235423520207405f, - -0.424263238906860f, - 0.235098183155060f, -0.424060165882111f, 0.234773010015488f, - -0.423856884241104f, - 0.234448000788689f, -0.423653304576874f, 0.234123140573502f, - -0.423449516296387f, - 0.233798429369926f, -0.423245459794998f, 0.233473882079124f, - -0.423041164875031f, - 0.233149498701096f, -0.422836631536484f, 0.232825264334679f, - -0.422631829977036f, - 0.232501193881035f, -0.422426789999008f, 0.232177272439003f, - -0.422221481800079f, - 0.231853514909744f, -0.422015935182571f, 0.231529906392097f, - -0.421810150146484f, - 0.231206461787224f, -0.421604126691818f, 0.230883181095123f, - -0.421397835016251f, - 0.230560049414635f, -0.421191304922104f, 0.230237081646919f, - -0.420984506607056f, - 0.229914262890816f, -0.420777499675751f, 0.229591608047485f, - -0.420570224523544f, - 0.229269117116928f, -0.420362681150436f, 0.228946775197983f, - -0.420154929161072f, - 0.228624612092972f, -0.419946908950806f, 0.228302597999573f, - -0.419738620519638f, - 0.227980732917786f, -0.419530123472214f, 0.227659046649933f, - -0.419321358203888f, - 0.227337509393692f, -0.419112354516983f, 0.227016136050224f, - -0.418903112411499f, - 0.226694911718369f, -0.418693602085114f, 0.226373866200447f, - -0.418483853340149f, - 0.226052969694138f, -0.418273866176605f, 0.225732237100601f, - -0.418063640594482f, - 0.225411668419838f, -0.417853146791458f, 0.225091263651848f, - -0.417642414569855f, - 0.224771007895470f, -0.417431443929672f, 0.224450930953026f, - -0.417220205068588f, - 0.224131003022194f, -0.417008757591248f, 0.223811239004135f, - -0.416797041893005f, - 0.223491653800011f, -0.416585087776184f, 0.223172217607498f, - -0.416372895240784f, - 0.222852945327759f, -0.416160434484482f, 0.222533836960793f, - -0.415947735309601f, - 0.222214877605438f, -0.415734797716141f, 0.221896097064018f, - -0.415521621704102f, - 0.221577480435371f, -0.415308207273483f, 0.221259027719498f, - -0.415094524621964f, - 0.220940738916397f, -0.414880603551865f, 0.220622614026070f, - -0.414666473865509f, - 0.220304638147354f, -0.414452046155930f, 0.219986841082573f, - -0.414237409830093f, - 0.219669207930565f, -0.414022535085678f, 0.219351738691330f, - -0.413807392120361f, - 0.219034433364868f, -0.413592010736465f, 0.218717306852341f, - -0.413376390933990f, - 0.218400329351425f, -0.413160532712936f, 0.218083515763283f, - -0.412944436073303f, - 0.217766880989075f, -0.412728071212769f, 0.217450410127640f, - -0.412511497735977f, - 0.217134088277817f, -0.412294656038284f, 0.216817945241928f, - -0.412077575922012f, - 0.216501981019974f, -0.411860257387161f, 0.216186165809631f, - -0.411642700433731f, - 0.215870529413223f, -0.411424905061722f, 0.215555042028427f, - -0.411206841468811f, - 0.215239733457565f, -0.410988569259644f, 0.214924603700638f, - -0.410770028829575f, - 0.214609622955322f, -0.410551249980927f, 0.214294821023941f, - -0.410332232713699f, - 0.213980183005333f, -0.410112977027893f, 0.213665723800659f, - -0.409893482923508f, - 0.213351413607597f, -0.409673750400543f, 0.213037282228470f, - -0.409453779459000f, - 0.212723329663277f, -0.409233570098877f, 0.212409526109695f, - -0.409013092517853f, - 0.212095901370049f, -0.408792406320572f, 0.211782455444336f, - -0.408571451902390f, - 0.211469158530235f, -0.408350288867950f, 0.211156040430069f, - -0.408128857612610f, - 0.210843101143837f, -0.407907217741013f, 0.210530325770378f, - -0.407685309648514f, - 0.210217714309692f, -0.407463163137436f, 0.209905281662941f, - -0.407240778207779f, - 0.209593027830124f, -0.407018154859543f, 0.209280923008919f, - -0.406795293092728f, - 0.208969011902809f, -0.406572192907333f, 0.208657249808311f, - -0.406348884105682f, - 0.208345666527748f, -0.406125307083130f, 0.208034262061119f, - -0.405901491641998f, - 0.207723021507263f, -0.405677437782288f, 0.207411959767342f, - -0.405453115701675f, - 0.207101076841354f, -0.405228585004807f, 0.206790357828140f, - -0.405003815889359f, - 0.206479802727699f, -0.404778808355331f, 0.206169426441193f, - -0.404553562402725f, - 0.205859228968620f, -0.404328078031540f, 0.205549195408821f, - -0.404102355241776f, - 0.205239340662956f, -0.403876423835754f, 0.204929664731026f, - -0.403650224208832f, - 0.204620152711868f, -0.403423786163330f, 0.204310819506645f, - -0.403197109699249f, - 0.204001650214195f, -0.402970194816589f, 0.203692659735680f, - -0.402743041515350f, - 0.203383848071098f, -0.402515679597855f, 0.203075215220451f, - -0.402288049459457f, - 0.202766746282578f, -0.402060180902481f, 0.202458456158638f, - -0.401832103729248f, - 0.202150344848633f, -0.401603758335114f, 0.201842412352562f, - -0.401375204324722f, - 0.201534643769264f, -0.401146411895752f, 0.201227053999901f, - -0.400917351245880f, - 0.200919643044472f, -0.400688081979752f, 0.200612410902977f, - -0.400458574295044f, - 0.200305357575417f, -0.400228828191757f, 0.199998468160629f, - -0.399998843669891f, - 0.199691757559776f, -0.399768620729446f, 0.199385225772858f, - -0.399538189172745f, - 0.199078872799873f, -0.399307489395142f, 0.198772698640823f, - -0.399076581001282f, - 0.198466703295708f, -0.398845434188843f, 0.198160871863365f, - -0.398614019155502f, - 0.197855234146118f, -0.398382395505905f, 0.197549775242805f, - -0.398150533437729f, - 0.197244480252266f, -0.397918462753296f, 0.196939364075661f, - -0.397686123847961f, - 0.196634441614151f, -0.397453576326370f, 0.196329683065414f, - -0.397220760583878f, - 0.196025103330612f, -0.396987736225128f, 0.195720717310905f, - -0.396754473447800f, - 0.195416495203972f, -0.396520972251892f, 0.195112451910973f, - -0.396287262439728f, - 0.194808602333069f, -0.396053284406662f, 0.194504916667938f, - -0.395819097757339f, - 0.194201424717903f, -0.395584672689438f, 0.193898096680641f, - -0.395350009202957f, - 0.193594962358475f, -0.395115107297897f, 0.193292006850243f, - -0.394879996776581f, - 0.192989215254784f, -0.394644618034363f, 0.192686617374420f, - -0.394409030675888f, - 0.192384198307991f, -0.394173204898834f, 0.192081972956657f, - -0.393937170505524f, - 0.191779911518097f, -0.393700867891312f, 0.191478043794632f, - -0.393464356660843f, - 0.191176339983940f, -0.393227607011795f, 0.190874829888344f, - -0.392990618944168f, - 0.190573498606682f, -0.392753422260284f, 0.190272361040115f, - -0.392515957355499f, - 0.189971387386322f, -0.392278283834457f, 0.189670607447624f, - -0.392040401697159f, - 0.189370006322861f, -0.391802251338959f, 0.189069598913193f, - -0.391563892364502f, - 0.188769355416298f, -0.391325294971466f, 0.188469305634499f, - -0.391086459159851f, - 0.188169434666634f, -0.390847414731979f, 0.187869757413864f, - -0.390608131885529f, - 0.187570258975029f, -0.390368610620499f, 0.187270939350128f, - -0.390128880739212f, - 0.186971798539162f, -0.389888882637024f, 0.186672851443291f, - -0.389648675918579f, - 0.186374098062515f, -0.389408260583878f, 0.186075508594513f, - -0.389167606830597f, - 0.185777112841606f, -0.388926714658737f, 0.185478910803795f, - -0.388685584068298f, - 0.185180887579918f, -0.388444244861603f, 0.184883043169975f, - -0.388202667236328f, - 0.184585392475128f, -0.387960851192474f, 0.184287920594215f, - -0.387718826532364f, - 0.183990627527237f, -0.387476563453674f, 0.183693528175354f, - -0.387234061956406f, - 0.183396622538567f, -0.386991351842880f, 0.183099895715714f, - -0.386748403310776f, - 0.182803362607956f, -0.386505216360092f, 0.182507008314133f, - -0.386261820793152f, - 0.182210832834244f, -0.386018186807632f, 0.181914865970612f, - -0.385774344205856f, - 0.181619063019753f, -0.385530263185501f, 0.181323468685150f, - -0.385285943746567f, - 0.181028053164482f, -0.385041415691376f, 0.180732816457748f, - -0.384796649217606f, - 0.180437773466110f, -0.384551674127579f, 0.180142924189568f, - -0.384306460618973f, - 0.179848253726959f, -0.384061008691788f, 0.179553776979446f, - -0.383815348148346f, - 0.179259493947029f, -0.383569449186325f, 0.178965389728546f, - -0.383323341608047f, - 0.178671479225159f, -0.383076995611191f, 0.178377762436867f, - -0.382830440998077f, - 0.178084224462509f, -0.382583618164063f, 0.177790880203247f, - -0.382336616516113f, - 0.177497729659081f, -0.382089376449585f, 0.177204772830009f, - -0.381841897964478f, - 0.176911994814873f, -0.381594210863113f, 0.176619410514832f, - -0.381346285343170f, - 0.176327019929886f, -0.381098151206970f, 0.176034808158875f, - -0.380849778652191f, - 0.175742805004120f, -0.380601197481155f, 0.175450980663300f, - -0.380352377891541f, - 0.175159350037575f, -0.380103349685669f, 0.174867913126946f, - -0.379854083061218f, - 0.174576655030251f, -0.379604607820511f, 0.174285605549812f, - -0.379354894161224f, - 0.173994734883308f, -0.379104942083359f, 0.173704057931900f, - -0.378854811191559f, - 0.173413574695587f, -0.378604412078857f, 0.173123285174370f, - -0.378353834152222f, - 0.172833189368248f, -0.378102988004684f, 0.172543287277222f, - -0.377851963043213f, - 0.172253578901291f, -0.377600699663162f, 0.171964049339294f, - -0.377349197864532f, - 0.171674728393555f, -0.377097487449646f, 0.171385586261749f, - -0.376845568418503f, - 0.171096652746201f, -0.376593410968781f, 0.170807912945747f, - -0.376341015100479f, - 0.170519351959229f, -0.376088410615921f, 0.170230999588966f, - -0.375835597515106f, - 0.169942826032639f, -0.375582575798035f, 0.169654861092567f, - -0.375329315662384f, - 0.169367074966431f, -0.375075817108154f, 0.169079497456551f, - -0.374822109937668f, - 0.168792113661766f, -0.374568194150925f, 0.168504923582077f, - -0.374314039945602f, - 0.168217927217484f, -0.374059677124023f, 0.167931124567986f, - -0.373805105686188f, - 0.167644515633583f, -0.373550295829773f, 0.167358100414276f, - -0.373295277357101f, - 0.167071878910065f, -0.373040050268173f, 0.166785866022110f, - -0.372784584760666f, - 0.166500031948090f, -0.372528880834579f, 0.166214406490326f, - -0.372272998094559f, - 0.165928974747658f, -0.372016876935959f, 0.165643751621246f, - -0.371760547161102f, - 0.165358707308769f, -0.371503978967667f, 0.165073871612549f, - -0.371247202157974f, - 0.164789214730263f, -0.370990216732025f, 0.164504766464233f, - -0.370732992887497f, - 0.164220526814461f, -0.370475560426712f, 0.163936465978622f, - -0.370217919349670f, - 0.163652613759041f, -0.369960039854050f, 0.163368955254555f, - -0.369701951742172f, - 0.163085505366325f, -0.369443655014038f, 0.162802234292030f, - -0.369185149669647f, - 0.162519171833992f, -0.368926405906677f, 0.162236317992210f, - -0.368667453527451f, - 0.161953642964363f, -0.368408292531967f, 0.161671176552773f, - -0.368148893117905f, - 0.161388918757439f, -0.367889285087585f, 0.161106839776039f, - -0.367629468441010f, - 0.160824984312058f, -0.367369443178177f, 0.160543307662010f, - -0.367109179496765f, - 0.160261839628220f, -0.366848707199097f, 0.159980565309525f, - -0.366588026285172f, - 0.159699499607086f, -0.366327136754990f, 0.159418627619743f, - -0.366066008806229f, - 0.159137964248657f, -0.365804702043533f, 0.158857494592667f, - -0.365543156862259f, - 0.158577233552933f, -0.365281373262405f, 0.158297166228294f, - -0.365019410848618f, - 0.158017292618752f, -0.364757210016251f, 0.157737627625465f, - -0.364494800567627f, - 0.157458171248436f, -0.364232182502747f, 0.157178908586502f, - -0.363969355821610f, - 0.156899839639664f, -0.363706320524216f, 0.156620979309082f, - -0.363443046808243f, - 0.156342327594757f, -0.363179564476013f, 0.156063869595528f, - -0.362915903329849f, - 0.155785620212555f, -0.362651973962784f, 0.155507579445839f, - -0.362387865781784f, - 0.155229732394218f, -0.362123548984528f, 0.154952079057693f, - -0.361858993768692f, - 0.154674649238586f, -0.361594229936600f, 0.154397398233414f, - -0.361329287290573f, - 0.154120370745659f, -0.361064106225967f, 0.153843536973000f, - -0.360798716545105f, - 0.153566911816597f, -0.360533088445663f, 0.153290495276451f, - -0.360267281532288f, - 0.153014272451401f, -0.360001266002655f, 0.152738258242607f, - -0.359735012054443f, - 0.152462437748909f, -0.359468549489975f, 0.152186840772629f, - -0.359201908111572f, - 0.151911437511444f, -0.358935028314590f, 0.151636242866516f, - -0.358667939901352f, - 0.151361241936684f, -0.358400642871857f, 0.151086464524269f, - -0.358133137226105f, - 0.150811880826950f, -0.357865422964096f, 0.150537505745888f, - -0.357597470283508f, - 0.150263324379921f, -0.357329338788986f, 0.149989366531372f, - -0.357060998678207f, - 0.149715602397919f, -0.356792420148849f, 0.149442046880722f, - -0.356523662805557f, - 0.149168699979782f, -0.356254696846008f, 0.148895561695099f, - -0.355985492467880f, - 0.148622632026672f, -0.355716109275818f, 0.148349896073341f, - -0.355446487665176f, - 0.148077383637428f, -0.355176687240601f, 0.147805064916611f, - -0.354906648397446f, - 0.147532954812050f, -0.354636400938034f, 0.147261068224907f, - -0.354365974664688f, - 0.146989375352860f, -0.354095309972763f, 0.146717891097069f, - -0.353824466466904f, - 0.146446615457535f, -0.353553384542465f, 0.146175548434258f, - -0.353282123804092f, - 0.145904675126076f, -0.353010624647141f, 0.145634025335312f, - -0.352738946676254f, - 0.145363584160805f, -0.352467030286789f, 0.145093351602554f, - -0.352194935083389f, - 0.144823327660561f, -0.351922631263733f, 0.144553512334824f, - -0.351650089025497f, - 0.144283905625343f, -0.351377367973328f, 0.144014507532120f, - -0.351104438304901f, - 0.143745318055153f, -0.350831300020218f, 0.143476337194443f, - -0.350557953119278f, - 0.143207564949989f, -0.350284397602081f, 0.142939001321793f, - -0.350010633468628f, - 0.142670661211014f, -0.349736660718918f, 0.142402514815331f, - -0.349462509155273f, - 0.142134591937065f, -0.349188119173050f, 0.141866862773895f, - -0.348913550376892f, - 0.141599357128143f, -0.348638743162155f, 0.141332060098648f, - -0.348363757133484f, - 0.141064971685410f, -0.348088562488556f, 0.140798106789589f, - -0.347813159227371f, - 0.140531435608864f, -0.347537547349930f, 0.140264987945557f, - -0.347261756658554f, - 0.139998748898506f, -0.346985727548599f, 0.139732718467712f, - -0.346709519624710f, - 0.139466896653175f, -0.346433073282242f, 0.139201298356056f, - -0.346156448125839f, - 0.138935908675194f, -0.345879614353180f, 0.138670727610588f, - -0.345602601766586f, - 0.138405755162239f, -0.345325350761414f, 0.138141006231308f, - -0.345047920942307f, - 0.137876465916634f, -0.344770282506943f, 0.137612134218216f, - -0.344492435455322f, - 0.137348011136055f, -0.344214379787445f, 0.137084111571312f, - -0.343936115503311f, - 0.136820420622826f, -0.343657672405243f, 0.136556953191757f, - -0.343379020690918f, - 0.136293679475784f, -0.343100160360336f, 0.136030644178391f, - -0.342821091413498f, - 0.135767802596092f, -0.342541843652725f, 0.135505184531212f, - -0.342262357473373f, - 0.135242775082588f, -0.341982692480087f, 0.134980589151382f, - -0.341702848672867f, - 0.134718611836433f, -0.341422766447067f, 0.134456858038902f, - -0.341142505407333f, - 0.134195312857628f, -0.340862035751343f, 0.133933976292610f, - -0.340581357479095f, - 0.133672863245010f, -0.340300500392914f, 0.133411958813667f, - -0.340019434690475f, - 0.133151277899742f, -0.339738160371780f, 0.132890805602074f, - -0.339456677436829f, - 0.132630556821823f, -0.339175015687943f, 0.132370531558990f, - -0.338893145322800f, - 0.132110700011253f, -0.338611096143723f, 0.131851106882095f, - -0.338328808546066f, - 0.131591722369194f, -0.338046342134476f, 0.131332546472549f, - -0.337763696908951f, - 0.131073594093323f, -0.337480813264847f, 0.130814850330353f, - -0.337197750806808f, - 0.130556344985962f, -0.336914509534836f, 0.130298033356667f, - -0.336631029844284f, - 0.130039945244789f, -0.336347371339798f, 0.129782080650330f, - -0.336063534021378f, - 0.129524439573288f, -0.335779488086700f, 0.129267007112503f, - -0.335495233535767f, - 0.129009798169136f, -0.335210770368576f, 0.128752797842026f, - -0.334926128387451f, - 0.128496021032333f, -0.334641307592392f, 0.128239467740059f, - -0.334356248378754f, - 0.127983123064041f, -0.334071010351181f, 0.127727001905441f, - -0.333785593509674f, - 0.127471104264259f, -0.333499968051910f, 0.127215430140495f, - -0.333214133977890f, - 0.126959964632988f, -0.332928121089935f, 0.126704722642899f, - -0.332641899585724f, - 0.126449704170227f, -0.332355499267578f, 0.126194894313812f, - -0.332068890333176f, - 0.125940307974815f, -0.331782072782516f, 0.125685945153236f, - -0.331495076417923f, - 0.125431805849075f, -0.331207901239395f, 0.125177875161171f, - -0.330920487642288f, - 0.124924175441265f, -0.330632925033569f, 0.124670691788197f, - -0.330345153808594f, - 0.124417431652546f, -0.330057173967361f, 0.124164395034313f, - -0.329769015312195f, - 0.123911574482918f, -0.329480648040771f, 0.123658977448940f, - -0.329192101955414f, - 0.123406603932381f, -0.328903347253799f, 0.123154446482658f, - -0.328614413738251f, - 0.122902512550354f, -0.328325271606445f, 0.122650802135468f, - -0.328035950660706f, - 0.122399315237999f, -0.327746421098709f, 0.122148044407368f, - -0.327456712722778f, - 0.121896997094154f, -0.327166795730591f, 0.121646173298359f, - -0.326876699924469f, - 0.121395580470562f, -0.326586425304413f, 0.121145196259022f, - -0.326295942068100f, - 0.120895043015480f, -0.326005280017853f, 0.120645113289356f, - -0.325714409351349f, - 0.120395407080650f, -0.325423330068588f, 0.120145916938782f, - -0.325132101774216f, - 0.119896657764912f, -0.324840664863586f, 0.119647622108459f, - -0.324549019336700f, - 0.119398809969425f, -0.324257194995880f, 0.119150213897228f, - -0.323965191841125f, - 0.118901848793030f, -0.323672980070114f, 0.118653707206249f, - -0.323380589485168f, - 0.118405789136887f, -0.323088020086288f, 0.118158094584942f, - -0.322795242071152f, - 0.117910631000996f, -0.322502255439758f, 0.117663383483887f, - -0.322209119796753f, - 0.117416366934776f, -0.321915775537491f, 0.117169573903084f, - -0.321622252464294f, - 0.116923004388809f, -0.321328520774841f, 0.116676658391953f, - -0.321034610271454f, - 0.116430543363094f, -0.320740520954132f, 0.116184651851654f, - -0.320446223020554f, - 0.115938983857632f, -0.320151746273041f, 0.115693546831608f, - -0.319857090711594f, - 0.115448333323002f, -0.319562226533890f, 0.115203343331814f, - -0.319267183542252f, - 0.114958584308624f, -0.318971961736679f, 0.114714048802853f, - -0.318676531314850f, - 0.114469736814499f, -0.318380922079086f, 0.114225655794144f, - -0.318085134029388f, - 0.113981798291206f, -0.317789167165756f, 0.113738171756268f, - -0.317492991685867f, - 0.113494776189327f, -0.317196637392044f, 0.113251596689224f, - -0.316900104284287f, - 0.113008655607700f, -0.316603392362595f, 0.112765938043594f, - -0.316306471824646f, - 0.112523443996906f, -0.316009372472763f, 0.112281180918217f, - -0.315712094306946f, - 0.112039148807526f, -0.315414607524872f, 0.111797347664833f, - -0.315116971731186f, - 0.111555770039558f, -0.314819127321243f, 0.111314415931702f, - -0.314521104097366f, - 0.111073300242424f, -0.314222872257233f, 0.110832408070564f, - -0.313924491405487f, - 0.110591746866703f, -0.313625901937485f, 0.110351309180260f, - -0.313327133655548f, - 0.110111102461815f, -0.313028186559677f, 0.109871134161949f, - -0.312729060649872f, - 0.109631389379501f, -0.312429755926132f, 0.109391868114471f, - -0.312130242586136f, - 0.109152585268021f, -0.311830550432205f, 0.108913525938988f, - -0.311530679464340f, - 0.108674705028534f, -0.311230629682541f, 0.108436107635498f, - -0.310930401086807f, - 0.108197741210461f, -0.310629993677139f, 0.107959605753422f, - -0.310329377651215f, - 0.107721701264381f, -0.310028612613678f, 0.107484027743340f, - -0.309727638959885f, - 0.107246585190296f, -0.309426486492157f, 0.107009373605251f, - -0.309125155210495f, - 0.106772392988205f, -0.308823645114899f, 0.106535643339157f, - -0.308521956205368f, - 0.106299124658108f, -0.308220088481903f, 0.106062836945057f, - -0.307918041944504f, - 0.105826787650585f, -0.307615786790848f, 0.105590961873531f, - -0.307313382625580f, - 0.105355374515057f, -0.307010769844055f, 0.105120018124580f, - -0.306708008050919f, - 0.104884892702103f, -0.306405037641525f, 0.104649998247623f, - -0.306101888418198f, - 0.104415334761143f, -0.305798590183258f, 0.104180909693241f, - -0.305495083332062f, - 0.103946708142757f, -0.305191397666931f, 0.103712752461433f, - -0.304887533187866f, - 0.103479020297527f, -0.304583519697189f, 0.103245526552200f, - -0.304279297590256f, - 0.103012263774872f, -0.303974896669388f, 0.102779231965542f, - -0.303670316934586f, - 0.102546438574791f, -0.303365558385849f, 0.102313876152039f, - -0.303060621023178f, - 0.102081544697285f, -0.302755534648895f, 0.101849451661110f, - -0.302450239658356f, - 0.101617597043514f, -0.302144765853882f, 0.101385973393917f, - -0.301839113235474f, - 0.101154580712318f, -0.301533311605453f, 0.100923426449299f, - -0.301227301359177f, - 0.100692503154278f, -0.300921112298965f, 0.100461818277836f, - -0.300614774227142f, - 0.100231364369392f, -0.300308227539063f, 0.100001148879528f, - -0.300001531839371f, - 0.099771171808243f, -0.299694657325745f, 0.099541425704956f, - -0.299387603998184f, - 0.099311910569668f, -0.299080342054367f, 0.099082641303539f, - -0.298772931098938f, - 0.098853603005409f, -0.298465341329575f, 0.098624803125858f, - -0.298157602548599f, - 0.098396234214306f, -0.297849655151367f, 0.098167903721333f, - -0.297541528940201f, - 0.097939811646938f, -0.297233253717422f, 0.097711957991123f, - -0.296924799680710f, - 0.097484335303307f, -0.296616137027740f, 0.097256951034069f, - -0.296307325363159f, - 0.097029805183411f, -0.295998334884644f, 0.096802897751331f, - -0.295689195394516f, - 0.096576221287251f, -0.295379847288132f, 0.096349790692329f, - -0.295070350170136f, - 0.096123591065407f, -0.294760644435883f, 0.095897629857063f, - -0.294450789690018f, - 0.095671907067299f, -0.294140785932541f, 0.095446422696114f, - -0.293830573558807f, - 0.095221176743507f, -0.293520182371140f, 0.094996169209480f, - -0.293209642171860f, - 0.094771400094032f, -0.292898923158646f, 0.094546869397163f, - -0.292588025331497f, - 0.094322577118874f, -0.292276978492737f, 0.094098523259163f, - -0.291965723037720f, - 0.093874707818031f, -0.291654318571091f, 0.093651130795479f, - -0.291342735290527f, - 0.093427792191505f, -0.291031002998352f, 0.093204692006111f, - -0.290719062089920f, - 0.092981837689877f, -0.290406972169876f, 0.092759214341640f, - -0.290094703435898f, - 0.092536836862564f, -0.289782285690308f, 0.092314697802067f, - -0.289469659328461f, - 0.092092797160149f, -0.289156883955002f, 0.091871134936810f, - -0.288843959569931f, - 0.091649711132050f, -0.288530826568604f, 0.091428533196449f, - -0.288217544555664f, - 0.091207593679428f, -0.287904083728790f, 0.090986892580986f, - -0.287590473890305f, - 0.090766437351704f, -0.287276685237885f, 0.090546220541000f, - -0.286962717771530f, - 0.090326242148876f, -0.286648571491241f, 0.090106502175331f, - -0.286334276199341f, - 0.089887008070946f, -0.286019802093506f, 0.089667752385139f, - -0.285705178976059f, - 0.089448742568493f, -0.285390377044678f, 0.089229971170425f, - -0.285075396299362f, - 0.089011445641518f, -0.284760266542435f, 0.088793158531189f, - -0.284444957971573f, - 0.088575109839439f, -0.284129470586777f, 0.088357307016850f, - -0.283813834190369f, - 0.088139742612839f, -0.283498018980026f, 0.087922424077988f, - -0.283182054758072f, - 0.087705351412296f, -0.282865911722183f, 0.087488517165184f, - -0.282549589872360f, - 0.087271921336651f, -0.282233119010925f, 0.087055571377277f, - -0.281916469335556f, - 0.086839467287064f, -0.281599670648575f, 0.086623609066010f, - -0.281282693147659f, - 0.086407989263535f, -0.280965566635132f, 0.086192607879639f, - -0.280648261308670f, - 0.085977479815483f, -0.280330777168274f, 0.085762590169907f, - -0.280013144016266f, - 0.085547938942909f, -0.279695361852646f, 0.085333541035652f, - -0.279377400875092f, - 0.085119381546974f, -0.279059261083603f, 0.084905467927456f, - -0.278740972280502f, - 0.084691800177097f, -0.278422504663467f, 0.084478378295898f, - -0.278103888034821f, - 0.084265194833279f, -0.277785122394562f, 0.084052257239819f, - -0.277466177940369f, - 0.083839565515518f, -0.277147054672241f, 0.083627119660378f, - -0.276827782392502f, - 0.083414919674397f, -0.276508361101151f, 0.083202958106995f, - -0.276188760995865f, - 0.082991249859333f, -0.275868982076645f, 0.082779780030251f, - -0.275549083948135f, - 0.082568563520908f, -0.275228977203369f, 0.082357585430145f, - -0.274908751249313f, - 0.082146860659122f, -0.274588316679001f, 0.081936374306679f, - -0.274267762899399f, - 0.081726133823395f, -0.273947030305862f, 0.081516146659851f, - -0.273626148700714f, - 0.081306397914886f, -0.273305088281631f, 0.081096902489662f, - -0.272983878850937f, - 0.080887645483017f, -0.272662490606308f, 0.080678641796112f, - -0.272340953350067f, - 0.080469883978367f, -0.272019267082214f, 0.080261372029781f, - -0.271697402000427f, - 0.080053105950356f, -0.271375387907028f, 0.079845085740089f, - -0.271053224802017f, - 0.079637311398983f, -0.270730882883072f, 0.079429790377617f, - -0.270408391952515f, - 0.079222507774830f, -0.270085722208023f, 0.079015478491783f, - -0.269762933254242f, - 0.078808702528477f, -0.269439965486526f, 0.078602164983749f, - -0.269116818904877f, - 0.078395880758762f, -0.268793523311615f, 0.078189842402935f, - -0.268470078706741f, - 0.077984049916267f, -0.268146485090256f, 0.077778510749340f, - -0.267822742462158f, - 0.077573217451572f, -0.267498821020126f, 0.077368170022964f, - -0.267174720764160f, - 0.077163375914097f, -0.266850501298904f, 0.076958827674389f, - -0.266526103019714f, - 0.076754532754421f, -0.266201555728912f, 0.076550483703613f, - -0.265876859426498f, - 0.076346680521965f, -0.265552014112473f, 0.076143130660057f, - -0.265226989984512f, - 0.075939826667309f, -0.264901816844940f, 0.075736775994301f, - -0.264576494693756f, - 0.075533971190453f, -0.264250993728638f, 0.075331419706345f, - -0.263925373554230f, - 0.075129114091396f, -0.263599574565887f, 0.074927061796188f, - -0.263273626565933f, - 0.074725262820721f, -0.262947499752045f, 0.074523709714413f, - -0.262621253728867f, - 0.074322402477264f, -0.262294828891754f, 0.074121348559856f, - -0.261968284845352f, - 0.073920547962189f, -0.261641561985016f, 0.073720000684261f, - -0.261314690113068f, - 0.073519699275494f, -0.260987639427185f, 0.073319651186466f, - -0.260660469532013f, - 0.073119848966599f, -0.260333120822906f, 0.072920300066471f, - -0.260005623102188f, - 0.072721004486084f, -0.259678006172180f, 0.072521962225437f, - -0.259350210428238f, - 0.072323165833950f, -0.259022265672684f, 0.072124622762203f, - -0.258694142103195f, - 0.071926333010197f, -0.258365899324417f, 0.071728296577930f, - -0.258037507534027f, - 0.071530513465405f, -0.257708936929703f, 0.071332976222038f, - -0.257380217313766f, - 0.071135692298412f, -0.257051378488541f, 0.070938661694527f, - -0.256722360849380f, - 0.070741884410381f, -0.256393194198608f, 0.070545360445976f, - -0.256063878536224f, - 0.070349089801311f, -0.255734413862228f, 0.070153072476387f, - -0.255404800176620f, - 0.069957308471203f, -0.255075037479401f, 0.069761790335178f, - -0.254745125770569f, - 0.069566532969475f, -0.254415065050125f, 0.069371521472931f, - -0.254084855318069f, - 0.069176770746708f, -0.253754496574402f, 0.068982265889645f, - -0.253423988819122f, - 0.068788021802902f, -0.253093332052231f, 0.068594031035900f, - -0.252762526273727f, - 0.068400286138058f, -0.252431541681290f, 0.068206802010536f, - -0.252100437879562f, - 0.068013571202755f, -0.251769185066223f, 0.067820593714714f, - -0.251437783241272f, - 0.067627869546413f, -0.251106232404709f, 0.067435398697853f, - -0.250774532556534f, - 0.067243188619614f, -0.250442683696747f, 0.067051224410534f, - -0.250110685825348f, - 0.066859520971775f, -0.249778553843498f, 0.066668070852757f, - -0.249446272850037f, - 0.066476874053478f, -0.249113827943802f, 0.066285938024521f, - -0.248781248927116f, - 0.066095255315304f, -0.248448520898819f, 0.065904818475246f, - -0.248115643858910f, - 0.065714649856091f, -0.247782632708550f, 0.065524727106094f, - -0.247449472546577f, - 0.065335065126419f, -0.247116148471832f, 0.065145656466484f, - -0.246782705187798f, - 0.064956501126289f, -0.246449097990990f, 0.064767606556416f, - -0.246115356683731f, - 0.064578965306282f, -0.245781451463699f, 0.064390584826469f, - -0.245447427034378f, - 0.064202457666397f, -0.245113238692284f, 0.064014583826065f, - -0.244778916239738f, - 0.063826970756054f, -0.244444444775581f, 0.063639611005783f, - -0.244109839200974f, - 0.063452512025833f, -0.243775084614754f, 0.063265666365623f, - -0.243440181016922f, - 0.063079081475735f, -0.243105143308640f, 0.062892749905586f, - -0.242769956588745f, - 0.062706671655178f, -0.242434620857239f, 0.062520854175091f, - -0.242099151015282f, - 0.062335297465324f, -0.241763532161713f, 0.062149997800589f, - -0.241427779197693f, - 0.061964951455593f, -0.241091892123222f, 0.061780165880919f, - -0.240755841135979f, - 0.061595637351274f, -0.240419670939446f, 0.061411365866661f, - -0.240083336830139f, - 0.061227355152369f, -0.239746883511543f, 0.061043601483107f, - -0.239410281181335f, - 0.060860104858875f, -0.239073529839516f, 0.060676865279675f, - -0.238736644387245f, - 0.060493886470795f, -0.238399609923363f, 0.060311164706945f, - -0.238062441349030f, - 0.060128703713417f, -0.237725138664246f, 0.059946499764919f, - -0.237387686967850f, - 0.059764556586742f, -0.237050101161003f, 0.059582870453596f, - -0.236712381243706f, - 0.059401445090771f, -0.236374512314796f, 0.059220276772976f, - -0.236036509275436f, - 0.059039369225502f, -0.235698372125626f, 0.058858718723059f, - -0.235360085964203f, - 0.058678328990936f, -0.235021665692329f, 0.058498200029135f, - -0.234683111310005f, - 0.058318331837654f, -0.234344407916069f, 0.058138720691204f, - -0.234005570411682f, - 0.057959370315075f, -0.233666598796844f, 0.057780280709267f, - -0.233327493071556f, - 0.057601451873779f, -0.232988253235817f, 0.057422880083323f, - -0.232648864388466f, - 0.057244572788477f, -0.232309341430664f, 0.057066522538662f, - -0.231969684362412f, - 0.056888736784458f, -0.231629893183708f, 0.056711208075285f, - -0.231289967894554f, - 0.056533940136433f, -0.230949893593788f, 0.056356932967901f, - -0.230609700083733f, - 0.056180190294981f, -0.230269357562065f, 0.056003704667091f, - -0.229928880929947f, - 0.055827483534813f, -0.229588270187378f, 0.055651523172855f, - -0.229247525334358f, - 0.055475823581219f, -0.228906646370888f, 0.055300384759903f, - -0.228565633296967f, - 0.055125206708908f, -0.228224486112595f, 0.054950293153524f, - -0.227883204817772f, - 0.054775636643171f, -0.227541789412498f, 0.054601248353720f, - -0.227200239896774f, - 0.054427117109299f, -0.226858556270599f, 0.054253250360489f, - -0.226516738533974f, - 0.054079644382000f, -0.226174786686897f, 0.053906302899122f, - -0.225832715630531f, - 0.053733222186565f, -0.225490495562553f, 0.053560405969620f, - -0.225148141384125f, - 0.053387850522995f, -0.224805667996407f, 0.053215555846691f, - -0.224463045597076f, - 0.053043525665998f, -0.224120303988457f, 0.052871759980917f, - -0.223777428269386f, - 0.052700258791447f, -0.223434418439865f, 0.052529018372297f, - -0.223091274499893f, - 0.052358038723469f, -0.222748011350632f, 0.052187327295542f, - -0.222404599189758f, - 0.052016876637936f, -0.222061067819595f, 0.051846686750650f, - -0.221717402338982f, - 0.051676765084267f, -0.221373617649078f, 0.051507104188204f, - -0.221029683947563f, - 0.051337707787752f, -0.220685631036758f, 0.051168579608202f, - -0.220341444015503f, - 0.050999708473682f, -0.219997137784958f, 0.050831105560064f, - -0.219652697443962f, - 0.050662767142057f, -0.219308122992516f, 0.050494693219662f, - -0.218963414430618f, - 0.050326880067587f, -0.218618586659431f, 0.050159335136414f, - -0.218273624777794f, - 0.049992054700851f, -0.217928543686867f, 0.049825038760900f, - -0.217583328485489f, - 0.049658283591270f, -0.217237979173660f, 0.049491796642542f, - -0.216892510652542f, - 0.049325577914715f, -0.216546908020973f, 0.049159619957209f, - -0.216201186180115f, - 0.048993926495314f, -0.215855330228806f, 0.048828501254320f, - -0.215509355068207f, - 0.048663340508938f, -0.215163245797157f, 0.048498444259167f, - -0.214817002415657f, - 0.048333816230297f, -0.214470639824867f, 0.048169452697039f, - -0.214124158024788f, - 0.048005353659391f, -0.213777542114258f, 0.047841522842646f, - -0.213430806994438f, - 0.047677956521511f, -0.213083937764168f, 0.047514654695988f, - -0.212736949324608f, - 0.047351621091366f, -0.212389841675758f, 0.047188851982355f, - -0.212042599916458f, - 0.047026351094246f, -0.211695238947868f, 0.046864114701748f, - -0.211347743868828f, - 0.046702146530151f, -0.211000129580498f, 0.046540446579456f, - -0.210652396082878f, - 0.046379011124372f, -0.210304543375969f, 0.046217843890190f, - -0.209956556558609f, - 0.046056941151619f, -0.209608450531960f, 0.045896306633949f, - -0.209260210394859f, - 0.045735940337181f, -0.208911851048470f, 0.045575842261314f, - -0.208563387393951f, - 0.045416008681059f, -0.208214774727821f, 0.045256443321705f, - -0.207866057753563f, - 0.045097146183252f, -0.207517206668854f, 0.044938117265701f, - -0.207168251276016f, - 0.044779352843761f, -0.206819161772728f, 0.044620860368013f, - -0.206469938158989f, - 0.044462632387877f, -0.206120610237122f, 0.044304672628641f, - -0.205771163105965f, - 0.044146984815598f, -0.205421581864357f, 0.043989561498165f, - -0.205071896314621f, - 0.043832406401634f, -0.204722076654434f, 0.043675523251295f, - -0.204372137784958f, - 0.043518904596567f, -0.204022079706192f, 0.043362557888031f, - -0.203671902418137f, - 0.043206475675106f, -0.203321605920792f, 0.043050665408373f, - -0.202971190214157f, - 0.042895123362541f, -0.202620655298233f, 0.042739849537611f, - -0.202270001173019f, - 0.042584843933582f, -0.201919227838516f, 0.042430106550455f, - -0.201568335294724f, - 0.042275641113520f, -0.201217323541641f, 0.042121443897486f, - -0.200866192579269f, - 0.041967518627644f, -0.200514942407608f, 0.041813857853413f, - -0.200163587927818f, - 0.041660469025373f, -0.199812099337578f, 0.041507352143526f, - -0.199460506439209f, - 0.041354499757290f, -0.199108779430389f, 0.041201923042536f, - -0.198756948113441f, - 0.041049610823393f, -0.198404997587204f, 0.040897574275732f, - -0.198052927851677f, - 0.040745802223682f, -0.197700738906860f, 0.040594302117825f, - -0.197348430752754f, - 0.040443073958158f, -0.196996018290520f, 0.040292114019394f, - -0.196643486618996f, - 0.040141426026821f, -0.196290835738182f, 0.039991009980440f, - -0.195938065648079f, - 0.039840862154961f, -0.195585191249847f, 0.039690986275673f, - -0.195232197642326f, - 0.039541378617287f, -0.194879084825516f, 0.039392042905092f, - -0.194525867700577f, - 0.039242979139090f, -0.194172516465187f, 0.039094187319279f, - -0.193819075822830f, - 0.038945667445660f, -0.193465501070023f, 0.038797415792942f, - -0.193111822009087f, - 0.038649436086416f, -0.192758023738861f, 0.038501728326082f, - -0.192404121160507f, - 0.038354292511940f, -0.192050099372864f, 0.038207128643990f, - -0.191695958375931f, - 0.038060232996941f, -0.191341713070869f, 0.037913613021374f, - -0.190987363457680f, - 0.037767261266708f, -0.190632879734039f, 0.037621185183525f, - -0.190278306603432f, - 0.037475381046534f, -0.189923599362373f, 0.037329845130444f, - -0.189568802714348f, - 0.037184584885836f, -0.189213871955872f, 0.037039596587420f, - -0.188858851790428f, - 0.036894880235195f, -0.188503712415695f, 0.036750435829163f, - -0.188148453831673f, - 0.036606263369322f, -0.187793090939522f, 0.036462362855673f, - -0.187437608838081f, - 0.036318738013506f, -0.187082037329674f, 0.036175385117531f, - -0.186726331710815f, - 0.036032304167747f, -0.186370536684990f, 0.035889495164156f, - -0.186014622449875f, - 0.035746958106756f, -0.185658603906631f, 0.035604696720839f, - -0.185302466154099f, - 0.035462711006403f, -0.184946224093437f, 0.035320993512869f, - -0.184589877724648f, - 0.035179551690817f, -0.184233412146568f, 0.035038381814957f, - -0.183876842260361f, - 0.034897487610579f, -0.183520168066025f, 0.034756865352392f, - -0.183163389563560f, - 0.034616518765688f, -0.182806491851807f, 0.034476444125175f, - -0.182449504733086f, - 0.034336645156145f, -0.182092398405075f, 0.034197118133307f, - -0.181735187768936f, - 0.034057866781950f, -0.181377857923508f, 0.033918887376785f, - -0.181020438671112f, - 0.033780183643103f, -0.180662900209427f, 0.033641755580902f, - -0.180305257439613f, - 0.033503599464893f, -0.179947525262833f, 0.033365719020367f, - -0.179589673876762f, - 0.033228114247322f, -0.179231703281403f, 0.033090781420469f, - -0.178873643279076f, - 0.032953724265099f, -0.178515478968620f, 0.032816942781210f, - -0.178157210350037f, - 0.032680433243513f, -0.177798837423325f, 0.032544203102589f, - -0.177440345287323f, - 0.032408244907856f, -0.177081763744354f, 0.032272562384605f, - -0.176723077893257f, - 0.032137155532837f, -0.176364272832870f, 0.032002024352551f, - -0.176005378365517f, - 0.031867165118456f, -0.175646379590034f, 0.031732585281134f, - -0.175287276506424f, - 0.031598277390003f, -0.174928069114685f, 0.031464248895645f, - -0.174568757414818f, - 0.031330492347479f, -0.174209341406822f, 0.031197015196085f, - -0.173849821090698f, - 0.031063811853528f, -0.173490211367607f, 0.030930884182453f, - -0.173130482435226f, - 0.030798232182860f, -0.172770664095879f, 0.030665857717395f, - -0.172410741448402f, - 0.030533758923411f, -0.172050714492798f, 0.030401935800910f, - -0.171690583229065f, - 0.030270388349891f, -0.171330362558365f, 0.030139118432999f, - -0.170970037579536f, - 0.030008124187589f, -0.170609608292580f, 0.029877405613661f, - -0.170249074697495f, - 0.029746964573860f, -0.169888436794281f, 0.029616801068187f, - -0.169527709484100f, - 0.029486913233995f, -0.169166877865791f, 0.029357301071286f, - -0.168805956840515f, - 0.029227968305349f, -0.168444931507111f, 0.029098909348249f, - -0.168083801865578f, - 0.028970129787922f, -0.167722567915916f, 0.028841627761722f, - -0.167361244559288f, - 0.028713401407003f, -0.166999831795692f, 0.028585452586412f, - -0.166638299822807f, - 0.028457781299949f, -0.166276678442955f, 0.028330387547612f, - -0.165914967656136f, - 0.028203271329403f, -0.165553152561188f, 0.028076432645321f, - -0.165191248059273f, - 0.027949871495366f, -0.164829224348068f, 0.027823587879539f, - -0.164467126131058f, - 0.027697581797838f, -0.164104923605919f, 0.027571853250265f, - -0.163742616772652f, - 0.027446404099464f, -0.163380220532417f, 0.027321230620146f, - -0.163017734885216f, - 0.027196336537600f, -0.162655144929886f, 0.027071721851826f, - -0.162292465567589f, - 0.026947384700179f, -0.161929681897163f, 0.026823325082660f, - -0.161566808819771f, - 0.026699542999268f, -0.161203846335411f, 0.026576040312648f, - -0.160840779542923f, - 0.026452817022800f, -0.160477623343468f, 0.026329871267080f, - -0.160114362835884f, - 0.026207204908133f, -0.159751012921333f, 0.026084816083312f, - -0.159387573599815f, - 0.025962706655264f, -0.159024044871330f, 0.025840876623988f, - -0.158660411834717f, - 0.025719324126840f, -0.158296689391136f, 0.025598052889109f, - -0.157932877540588f, - 0.025477059185505f, -0.157568961381912f, 0.025356344878674f, - -0.157204970717430f, - 0.025235909968615f, -0.156840875744820f, 0.025115754455328f, - -0.156476691365242f, - 0.024995878338814f, -0.156112402677536f, 0.024876279756427f, - -0.155748039484024f, - 0.024756962433457f, -0.155383571982384f, 0.024637924507260f, - -0.155019029974937f, - 0.024519165977836f, -0.154654383659363f, 0.024400688707829f, - -0.154289647936821f, - 0.024282488971949f, -0.153924822807312f, 0.024164570495486f, - -0.153559908270836f, - 0.024046931415796f, -0.153194904327393f, 0.023929571732879f, - -0.152829796075821f, - 0.023812493309379f, -0.152464613318443f, 0.023695694282651f, - -0.152099341154099f, - 0.023579176515341f, -0.151733979582787f, 0.023462938144803f, - -0.151368513703346f, - 0.023346979171038f, -0.151002973318100f, 0.023231301456690f, - -0.150637343525887f, - 0.023115905001760f, -0.150271624326706f, 0.023000787943602f, - -0.149905815720558f, - 0.022885952144861f, -0.149539917707443f, 0.022771397605538f, - -0.149173930287361f, - 0.022657122462988f, -0.148807853460312f, 0.022543128579855f, - -0.148441687226295f, - 0.022429415956140f, -0.148075446486473f, 0.022315984591842f, - -0.147709101438522f, - 0.022202832624316f, -0.147342681884766f, 0.022089963778853f, - -0.146976172924042f, - 0.021977374330163f, -0.146609574556351f, 0.021865066140890f, - -0.146242901682854f, - 0.021753041073680f, -0.145876124501228f, 0.021641295403242f, - -0.145509272813797f, - 0.021529832854867f, -0.145142331719399f, 0.021418649703264f, - -0.144775316119194f, - 0.021307749673724f, -0.144408211112022f, 0.021197130903602f, - -0.144041016697884f, - 0.021086793392897f, -0.143673732876778f, 0.020976737141609f, - -0.143306359648705f, - 0.020866964012384f, -0.142938911914825f, 0.020757472142577f, - -0.142571389675140f, - 0.020648263394833f, -0.142203763127327f, 0.020539334043860f, - -0.141836062073708f, - 0.020430689677596f, -0.141468286514282f, 0.020322324708104f, - -0.141100421547890f, - 0.020214242860675f, -0.140732467174530f, 0.020106444135308f, - -0.140364438295364f, - 0.019998926669359f, -0.139996320009232f, 0.019891692325473f, - -0.139628127217293f, - 0.019784741103649f, -0.139259845018387f, 0.019678071141243f, - -0.138891488313675f, - 0.019571684300900f, -0.138523042201996f, 0.019465578719974f, - -0.138154521584511f, - 0.019359756261110f, -0.137785911560059f, 0.019254218786955f, - -0.137417227029800f, - 0.019148962572217f, -0.137048453092575f, 0.019043987616897f, - -0.136679604649544f, - 0.018939297646284f, -0.136310681700706f, 0.018834890797734f, - -0.135941669344902f, - 0.018730765208602f, -0.135572582483292f, 0.018626924604177f, - -0.135203406214714f, - 0.018523367121816f, -0.134834155440331f, 0.018420090898871f, - -0.134464830160141f, - 0.018317099660635f, -0.134095430374146f, 0.018214391544461f, - -0.133725941181183f, - 0.018111966550350f, -0.133356377482414f, 0.018009826540947f, - -0.132986739277840f, - 0.017907967790961f, -0.132617011666298f, 0.017806394025683f, - -0.132247209548950f, - 0.017705103382468f, -0.131877332925797f, 0.017604095861316f, - -0.131507381796837f, - 0.017503373324871f, -0.131137356162071f, 0.017402933910489f, - -0.130767241120338f, - 0.017302779480815f, -0.130397051572800f, 0.017202908173203f, - -0.130026802420616f, - 0.017103319987655f, -0.129656463861465f, 0.017004016786814f, - -0.129286035895348f, - 0.016904998570681f, -0.128915548324585f, 0.016806263476610f, - -0.128544986248016f, - 0.016707813367248f, -0.128174334764481f, 0.016609646379948f, - -0.127803623676300f, - 0.016511764377356f, -0.127432823181152f, 0.016414167359471f, - -0.127061963081360f, - 0.016316853463650f, -0.126691013574600f, 0.016219824552536f, - -0.126320004463196f, - 0.016123080626130f, -0.125948905944824f, 0.016026621684432f, - -0.125577747821808f, - 0.015930447727442f, -0.125206500291824f, 0.015834558755159f, - -0.124835193157196f, - 0.015738952904940f, -0.124463804066181f, 0.015643632039428f, - -0.124092340469360f, - 0.015548598021269f, -0.123720809817314f, 0.015453847125173f, - -0.123349204659462f, - 0.015359382145107f, -0.122977524995804f, 0.015265202149749f, - -0.122605770826340f, - 0.015171307139099f, -0.122233949601650f, 0.015077698044479f, - -0.121862053871155f, - 0.014984373003244f, -0.121490091085434f, 0.014891333878040f, - -0.121118053793907f, - 0.014798580668867f, -0.120745941996574f, 0.014706112444401f, - -0.120373763144016f, - 0.014613929204643f, -0.120001509785652f, 0.014522032812238f, - -0.119629189372063f, - 0.014430420473218f, -0.119256794452667f, 0.014339094981551f, - -0.118884332478046f, - 0.014248054474592f, -0.118511803448200f, 0.014157299883664f, - -0.118139199912548f, - 0.014066831208766f, -0.117766529321671f, 0.013976648449898f, - -0.117393791675568f, - 0.013886751607060f, -0.117020979523659f, 0.013797140680254f, - -0.116648100316525f, - 0.013707815669477f, -0.116275154054165f, 0.013618776574731f, - -0.115902140736580f, - 0.013530024327338f, -0.115529052913189f, 0.013441557064652f, - -0.115155905485153f, - 0.013353376649320f, -0.114782683551311f, 0.013265483081341f, - -0.114409394562244f, - 0.013177875429392f, -0.114036038517952f, 0.013090553693473f, - -0.113662622869015f, - 0.013003518804908f, -0.113289132714272f, 0.012916770763695f, - -0.112915575504303f, - 0.012830308638513f, -0.112541958689690f, 0.012744133360684f, - -0.112168267369270f, - 0.012658244930208f, -0.111794516444206f, 0.012572642415762f, - -0.111420698463917f, - 0.012487327679992f, -0.111046813428402f, 0.012402298860252f, - -0.110672861337662f, - 0.012317557819188f, -0.110298842191696f, 0.012233102694154f, - -0.109924763441086f, - 0.012148935347795f, -0.109550617635250f, 0.012065053917468f, - -0.109176412224770f, - 0.011981460265815f, -0.108802139759064f, 0.011898153461516f, - -0.108427800238132f, - 0.011815134435892f, -0.108053401112556f, 0.011732402257621f, - -0.107678934931755f, - 0.011649956926703f, -0.107304409146309f, 0.011567799374461f, - -0.106929816305637f, - 0.011485928669572f, -0.106555156409740f, 0.011404345743358f, - -0.106180444359779f, - 0.011323049664497f, -0.105805665254593f, 0.011242041364312f, - -0.105430819094181f, - 0.011161320842803f, -0.105055920779705f, 0.011080888099968f, - -0.104680955410004f, - 0.011000742204487f, -0.104305922985077f, 0.010920885019004f, - -0.103930838406086f, - 0.010841314680874f, -0.103555686771870f, 0.010762032121420f, - -0.103180475533009f, - 0.010683037340641f, -0.102805204689503f, 0.010604331269860f, - -0.102429874241352f, - 0.010525912046432f, -0.102054484188557f, 0.010447781533003f, - -0.101679034531116f, - 0.010369938798249f, -0.101303517818451f, 0.010292383842170f, - -0.100927948951721f, - 0.010215117596090f, -0.100552320480347f, 0.010138138197362f, - -0.100176624953747f, - 0.010061448439956f, -0.099800877273083f, 0.009985045529902f, - -0.099425069987774f, - 0.009908932261169f, -0.099049203097820f, 0.009833106771111f, - -0.098673284053802f, - 0.009757569059730f, -0.098297297954559f, 0.009682320058346f, - -0.097921259701252f, - 0.009607359766960f, -0.097545161843300f, 0.009532688185573f, - -0.097169004380703f, - 0.009458304382861f, -0.096792794764042f, 0.009384209290147f, - -0.096416525542736f, - 0.009310402907431f, -0.096040196716785f, 0.009236886166036f, - -0.095663815736771f, - 0.009163657203317f, -0.095287375152111f, 0.009090716950595f, - -0.094910882413387f, - 0.009018065407872f, -0.094534330070019f, 0.008945702575147f, - -0.094157725572586f, - 0.008873629383743f, -0.093781061470509f, 0.008801844902337f, - -0.093404345214367f, - 0.008730349130929f, -0.093027576804161f, 0.008659142069519f, - -0.092650748789310f, - 0.008588224649429f, -0.092273868620396f, 0.008517595939338f, - -0.091896936297417f, - 0.008447255939245f, -0.091519944369793f, 0.008377205580473f, - -0.091142900288105f, - 0.008307444863021f, -0.090765804052353f, 0.008237972855568f, - -0.090388655662537f, - 0.008168790489435f, -0.090011447668076f, 0.008099896833301f, - -0.089634194970131f, - 0.008031292818487f, -0.089256882667542f, 0.007962978444993f, - -0.088879525661469f, - 0.007894953712821f, -0.088502109050751f, 0.007827218621969f, - -0.088124647736549f, - 0.007759772241116f, -0.087747126817703f, 0.007692615967244f, - -0.087369553744793f, - 0.007625748869032f, -0.086991935968399f, 0.007559171877801f, - -0.086614266037941f, - 0.007492884527892f, -0.086236543953419f, 0.007426886819303f, - -0.085858769714832f, - 0.007361178752035f, -0.085480943322182f, 0.007295760791749f, - -0.085103072226048f, - 0.007230632472783f, -0.084725148975849f, 0.007165793795139f, - -0.084347173571587f, - 0.007101245224476f, -0.083969146013260f, 0.007036986760795f, - -0.083591073751450f, - 0.006973018404096f, -0.083212949335575f, 0.006909339688718f, - -0.082834780216217f, - 0.006845951545984f, -0.082456558942795f, 0.006782853044569f, - -0.082078292965889f, - 0.006720044650137f, -0.081699974834919f, 0.006657526828349f, - -0.081321612000465f, - 0.006595299113542f, -0.080943197011948f, 0.006533361505717f, - -0.080564737319946f, - 0.006471714470536f, -0.080186225473881f, 0.006410357542336f, - -0.079807676374912f, - 0.006349290721118f, -0.079429075121880f, 0.006288514938205f, - -0.079050421714783f, - 0.006228029262275f, -0.078671731054783f, 0.006167833693326f, - -0.078292988240719f, - 0.006107929162681f, -0.077914200723171f, 0.006048315204680f, - -0.077535368502140f, - 0.005988991353661f, -0.077156484127045f, 0.005929958540946f, - -0.076777562499046f, - 0.005871216300875f, -0.076398596167564f, 0.005812764633447f, - -0.076019577682018f, - 0.005754603538662f, -0.075640521943569f, 0.005696733482182f, - -0.075261414051056f, - 0.005639153998345f, -0.074882268905640f, 0.005581865552813f, - -0.074503071606159f, - 0.005524867679924f, -0.074123837053776f, 0.005468160845339f, - -0.073744557797909f, - 0.005411745049059f, -0.073365233838558f, 0.005355620291084f, - -0.072985872626305f, - 0.005299786105752f, -0.072606459259987f, 0.005244242958724f, - -0.072227008640766f, - 0.005188991315663f, -0.071847513318062f, 0.005134030245245f, - -0.071467980742455f, - 0.005079360678792f, -0.071088403463364f, 0.005024982150644f, - -0.070708781480789f, - 0.004970894660801f, -0.070329122245312f, 0.004917098674923f, - -0.069949418306351f, - 0.004863593727350f, -0.069569669663906f, 0.004810380283743f, - -0.069189883768559f, - 0.004757457878441f, -0.068810060620308f, 0.004704826977104f, - -0.068430192768574f, - 0.004652487114072f, -0.068050287663937f, 0.004600439220667f, - -0.067670337855816f, - 0.004548682365566f, -0.067290350794792f, 0.004497217014432f, - -0.066910326480865f, - 0.004446043167263f, -0.066530264914036f, 0.004395160824060f, - -0.066150158643723f, - 0.004344569984823f, -0.065770015120506f, 0.004294271115214f, - -0.065389834344387f, - 0.004244263283908f, -0.065009608864784f, 0.004194547422230f, - -0.064629353582859f, - 0.004145123064518f, -0.064249053597450f, 0.004095990676433f, - -0.063868723809719f, - 0.004047149792314f, -0.063488349318504f, 0.003998600877821f, - -0.063107937574387f, - 0.003950343467295f, -0.062727488577366f, 0.003902378026396f, - -0.062347009778023f, - 0.003854704322293f, -0.061966486275196f, 0.003807322587818f, - -0.061585929244757f, - 0.003760232590139f, -0.061205338686705f, 0.003713434794918f, - -0.060824707150459f, - 0.003666928736493f, -0.060444042086601f, 0.003620714880526f, - -0.060063343495131f, - 0.003574792761356f, -0.059682607650757f, 0.003529162844643f, - -0.059301838278770f, - 0.003483824897557f, -0.058921031653881f, 0.003438779152930f, - -0.058540191501379f, - 0.003394025377929f, -0.058159314095974f, 0.003349563805386f, - -0.057778406888247f, - 0.003305394435301f, -0.057397462427616f, 0.003261517267674f, - -0.057016488164663f, - 0.003217932302505f, -0.056635476648808f, 0.003174639539793f, - -0.056254431605339f, - 0.003131638979539f, -0.055873356759548f, 0.003088930854574f, - -0.055492244660854f, - 0.003046514932066f, -0.055111102759838f, 0.003004391444847f, - -0.054729927331209f, - 0.002962560392916f, -0.054348722100258f, 0.002921021543443f, - -0.053967483341694f, - 0.002879775362089f, -0.053586211055517f, 0.002838821383193f, - -0.053204908967018f, - 0.002798160072416f, -0.052823577076197f, 0.002757790964097f, - -0.052442211657763f, - 0.002717714523897f, -0.052060816437006f, 0.002677930751815f, - -0.051679391413927f, - 0.002638439415023f, -0.051297932863235f, 0.002599240746349f, - -0.050916448235512f, - 0.002560334512964f, -0.050534930080175f, 0.002521721180528f, - -0.050153385847807f, - 0.002483400283381f, -0.049771808087826f, 0.002445372054353f, - -0.049390204250813f, - 0.002407636726275f, -0.049008570611477f, 0.002370193833485f, - -0.048626907169819f, - 0.002333043841645f, -0.048245213925838f, 0.002296186750755f, - -0.047863494604826f, - 0.002259622327983f, -0.047481749206781f, 0.002223350573331f, - -0.047099970281124f, - 0.002187371719629f, -0.046718169003725f, 0.002151685766876f, - -0.046336337924004f, - 0.002116292715073f, -0.045954477041960f, 0.002081192564219f, - -0.045572593808174f, - 0.002046385314316f, -0.045190680772066f, 0.002011870965362f, - -0.044808741658926f, - 0.001977649517357f, -0.044426776468754f, 0.001943721086718f, - -0.044044785201550f, - 0.001910085673444f, -0.043662767857313f, 0.001876743277535f, - -0.043280724436045f, - 0.001843693898991f, -0.042898654937744f, 0.001810937537812f, - -0.042516563087702f, - 0.001778474310413f, -0.042134445160627f, 0.001746304216795f, - -0.041752301156521f, - 0.001714427140541f, -0.041370131075382f, 0.001682843198068f, - -0.040987938642502f, - 0.001651552389376f, -0.040605723857880f, 0.001620554830879f, - -0.040223482996225f, - 0.001589850406162f, -0.039841219782829f, 0.001559439115226f, - -0.039458930492401f, - 0.001529321074486f, -0.039076622575521f, 0.001499496400356f, - -0.038694288581610f, - 0.001469964860007f, -0.038311932235956f, 0.001440726569854f, - -0.037929553538561f, - 0.001411781646311f, -0.037547148764133f, 0.001383129972965f, - -0.037164725363255f, - 0.001354771666229f, -0.036782283335924f, 0.001326706726104f, - -0.036399815231562f, - 0.001298935036175f, -0.036017324775457f, 0.001271456829272f, - -0.035634815692902f, - 0.001244271872565f, -0.035252287983894f, 0.001217380515300f, - -0.034869734197855f, - 0.001190782408230f, -0.034487165510654f, 0.001164477784187f, - -0.034104570746422f, - 0.001138466643170f, -0.033721961081028f, 0.001112748985179f, - -0.033339329063892f, - 0.001087324810214f, -0.032956674695015f, 0.001062194118276f, - -0.032574005424976f, - 0.001037356909364f, -0.032191313803196f, 0.001012813183479f, - -0.031808607280254f, - 0.000988563057035f, -0.031425878405571f, 0.000964606530033f, - -0.031043132767081f, - 0.000940943544265f, -0.030660368502140f, 0.000917574157938f, - -0.030277585610747f, - 0.000894498312846f, -0.029894785955548f, 0.000871716125403f, - -0.029511967673898f, - 0.000849227537401f, -0.029129132628441f, 0.000827032607049f, - -0.028746278956532f, - 0.000805131276138f, -0.028363410383463f, 0.000783523661084f, - -0.027980525046587f, - 0.000762209703680f, -0.027597622945905f, 0.000741189462133f, - -0.027214704081416f, - 0.000720462878235f, -0.026831768453121f, 0.000700030010194f, - -0.026448817923665f, - 0.000679890916217f, -0.026065852493048f, 0.000660045538098f, - -0.025682870298624f, - 0.000640493875835f, -0.025299875065684f, 0.000621235987637f, - -0.024916863068938f, - 0.000602271873504f, -0.024533838033676f, 0.000583601591643f, - -0.024150796234608f, - 0.000565225025639f, -0.023767741397023f, 0.000547142291907f, - -0.023384673520923f, - 0.000529353390448f, -0.023001590743661f, 0.000511858321261f, - -0.022618494927883f, - 0.000494657084346f, -0.022235386073589f, 0.000477749679703f, - -0.021852264180779f, - 0.000461136136437f, -0.021469129249454f, 0.000444816454547f, - -0.021085981279612f, - 0.000428790634032f, -0.020702820271254f, 0.000413058703998f, - -0.020319648087025f, - 0.000397620693548f, -0.019936462864280f, 0.000382476573577f, - -0.019553268328309f, - 0.000367626344087f, -0.019170060753822f, 0.000353070063284f, - -0.018786842003465f, - 0.000338807702065f, -0.018403612077236f, 0.000324839289533f, - -0.018020370975137f, - 0.000311164796585f, -0.017637118697166f, 0.000297784281429f, - -0.017253857105970f, - 0.000284697714960f, -0.016870586201549f, 0.000271905126283f, - -0.016487304121256f, - 0.000259406515397f, -0.016104012727737f, 0.000247201882303f, - -0.015720712020993f, - 0.000235291256104f, -0.015337402001023f, 0.000223674607696f, - -0.014954082667828f, - 0.000212351980736f, -0.014570754021406f, 0.000201323360670f, - -0.014187417924404f, - 0.000190588747500f, -0.013804072514176f, 0.000180148170330f, - -0.013420719653368f, - 0.000170001629158f, -0.013037359341979f, 0.000160149123985f, - -0.012653990648687f, - 0.000150590654812f, -0.012270614504814f, 0.000141326236189f, - -0.011887230910361f, - 0.000132355868118f, -0.011503840796649f, 0.000123679565149f, - -0.011120444163680f, - 0.000115297327284f, -0.010737040080130f, 0.000107209154521f, - -0.010353630408645f, - 0.000099415054137f, -0.009970214217901f, 0.000091915040684f, - -0.009586792439222f, - 0.000084709099610f, -0.009203365072608f, 0.000077797252743f, - -0.008819932118058f, - 0.000071179500083f, -0.008436493575573f, 0.000064855834353f, - -0.008053051307797f, - 0.000058826273744f, -0.007669602986425f, 0.000053090810979f, - -0.007286150939763f, - 0.000047649456974f, -0.006902694236487f, 0.000042502211727f, - -0.006519233807921f, - 0.000037649078877f, -0.006135769188404f, 0.000033090062061f, - -0.005752300843596f, - 0.000028825161280f, -0.005368829704821f, 0.000024854381991f, - -0.004985354840755f, - 0.000021177724193f, -0.004601877182722f, 0.000017795191525f, - -0.004218397196382f, - 0.000014706784896f, -0.003834914416075f, 0.000011912506125f, - -0.003451429307461f, - 0.000009412358850f, -0.003067942336202f, 0.000007206342616f, - -0.002684453502297f, - 0.000005294459243f, -0.002300963038579f, 0.000003676709639f, - -0.001917471294291f, - 0.000002353095169f, -0.001533978385851f, 0.000001323616516f, - -0.001150484546088f, - 0.000000588274133f, -0.000766990066040f, 0.000000147068562f, - -0.000383495149435f, - 0.000000000000000f, -0.000000000000023f, 0.000000147068562f, - 0.000383495149435f, - 0.000000588274133f, 0.000766990066040f, 0.000001323616516f, - 0.001150484546088f, - 0.000002353095169f, 0.001533978385851f, 0.000003676709639f, - 0.001917471294291f, - 0.000005294459243f, 0.002300963038579f, 0.000007206342616f, - 0.002684453502297f, - 0.000009412358850f, 0.003067942336202f, 0.000011912506125f, - 0.003451429307461f, - 0.000014706784896f, 0.003834914416075f, 0.000017795191525f, - 0.004218397196382f, - 0.000021177724193f, 0.004601877182722f, 0.000024854381991f, - 0.004985354840755f, - 0.000028825161280f, 0.005368829704821f, 0.000033090062061f, - 0.005752300843596f, - 0.000037649078877f, 0.006135769188404f, 0.000042502211727f, - 0.006519233807921f, - 0.000047649456974f, 0.006902694236487f, 0.000053090810979f, - 0.007286150939763f, - 0.000058826273744f, 0.007669602986425f, 0.000064855834353f, - 0.008053051307797f, - 0.000071179500083f, 0.008436493575573f, 0.000077797252743f, - 0.008819932118058f, - 0.000084709099610f, 0.009203365072608f, 0.000091915040684f, - 0.009586792439222f, - 0.000099415054137f, 0.009970214217901f, 0.000107209154521f, - 0.010353630408645f, - 0.000115297327284f, 0.010737040080130f, 0.000123679565149f, - 0.011120444163680f, - 0.000132355868118f, 0.011503840796649f, 0.000141326236189f, - 0.011887230910361f, - 0.000150590654812f, 0.012270614504814f, 0.000160149123985f, - 0.012653990648687f, - 0.000170001629158f, 0.013037359341979f, 0.000180148170330f, - 0.013420719653368f, - 0.000190588747500f, 0.013804072514176f, 0.000201323360670f, - 0.014187417924404f, - 0.000212351980736f, 0.014570754021406f, 0.000223674607696f, - 0.014954082667828f, - 0.000235291256104f, 0.015337402001023f, 0.000247201882303f, - 0.015720712020993f, - 0.000259406515397f, 0.016104012727737f, 0.000271905126283f, - 0.016487304121256f, - 0.000284697714960f, 0.016870586201549f, 0.000297784281429f, - 0.017253857105970f, - 0.000311164796585f, 0.017637118697166f, 0.000324839289533f, - 0.018020370975137f, - 0.000338807702065f, 0.018403612077236f, 0.000353070063284f, - 0.018786842003465f, - 0.000367626344087f, 0.019170060753822f, 0.000382476573577f, - 0.019553268328309f, - 0.000397620693548f, 0.019936462864280f, 0.000413058703998f, - 0.020319648087025f, - 0.000428790634032f, 0.020702820271254f, 0.000444816454547f, - 0.021085981279612f, - 0.000461136136437f, 0.021469129249454f, 0.000477749679703f, - 0.021852264180779f, - 0.000494657084346f, 0.022235386073589f, 0.000511858321261f, - 0.022618494927883f, - 0.000529353390448f, 0.023001590743661f, 0.000547142291907f, - 0.023384673520923f, - 0.000565225025639f, 0.023767741397023f, 0.000583601591643f, - 0.024150796234608f, - 0.000602271873504f, 0.024533838033676f, 0.000621235987637f, - 0.024916863068938f, - 0.000640493875835f, 0.025299875065684f, 0.000660045538098f, - 0.025682870298624f, - 0.000679890916217f, 0.026065852493048f, 0.000700030010194f, - 0.026448817923665f, - 0.000720462878235f, 0.026831768453121f, 0.000741189462133f, - 0.027214704081416f, - 0.000762209703680f, 0.027597622945905f, 0.000783523661084f, - 0.027980525046587f, - 0.000805131276138f, 0.028363410383463f, 0.000827032607049f, - 0.028746278956532f, - 0.000849227537401f, 0.029129132628441f, 0.000871716125403f, - 0.029511967673898f, - 0.000894498312846f, 0.029894785955548f, 0.000917574157938f, - 0.030277585610747f, - 0.000940943544265f, 0.030660368502140f, 0.000964606530033f, - 0.031043132767081f, - 0.000988563057035f, 0.031425878405571f, 0.001012813183479f, - 0.031808607280254f, - 0.001037356909364f, 0.032191313803196f, 0.001062194118276f, - 0.032574005424976f, - 0.001087324810214f, 0.032956674695015f, 0.001112748985179f, - 0.033339329063892f, - 0.001138466643170f, 0.033721961081028f, 0.001164477784187f, - 0.034104570746422f, - 0.001190782408230f, 0.034487165510654f, 0.001217380515300f, - 0.034869734197855f, - 0.001244271872565f, 0.035252287983894f, 0.001271456829272f, - 0.035634815692902f, - 0.001298935036175f, 0.036017324775457f, 0.001326706726104f, - 0.036399815231562f, - 0.001354771666229f, 0.036782283335924f, 0.001383129972965f, - 0.037164725363255f, - 0.001411781646311f, 0.037547148764133f, 0.001440726569854f, - 0.037929553538561f, - 0.001469964860007f, 0.038311932235956f, 0.001499496400356f, - 0.038694288581610f, - 0.001529321074486f, 0.039076622575521f, 0.001559439115226f, - 0.039458930492401f, - 0.001589850406162f, 0.039841219782829f, 0.001620554830879f, - 0.040223482996225f, - 0.001651552389376f, 0.040605723857880f, 0.001682843198068f, - 0.040987938642502f, - 0.001714427140541f, 0.041370131075382f, 0.001746304216795f, - 0.041752301156521f, - 0.001778474310413f, 0.042134445160627f, 0.001810937537812f, - 0.042516563087702f, - 0.001843693898991f, 0.042898654937744f, 0.001876743277535f, - 0.043280724436045f, - 0.001910085673444f, 0.043662767857313f, 0.001943721086718f, - 0.044044785201550f, - 0.001977649517357f, 0.044426776468754f, 0.002011870965362f, - 0.044808741658926f, - 0.002046385314316f, 0.045190680772066f, 0.002081192564219f, - 0.045572593808174f, - 0.002116292715073f, 0.045954477041960f, 0.002151685766876f, - 0.046336337924004f, - 0.002187371719629f, 0.046718169003725f, 0.002223350573331f, - 0.047099970281124f, - 0.002259622327983f, 0.047481749206781f, 0.002296186750755f, - 0.047863494604826f, - 0.002333043841645f, 0.048245213925838f, 0.002370193833485f, - 0.048626907169819f, - 0.002407636726275f, 0.049008570611477f, 0.002445372054353f, - 0.049390204250813f, - 0.002483400283381f, 0.049771808087826f, 0.002521721180528f, - 0.050153385847807f, - 0.002560334512964f, 0.050534930080175f, 0.002599240746349f, - 0.050916448235512f, - 0.002638439415023f, 0.051297932863235f, 0.002677930751815f, - 0.051679391413927f, - 0.002717714523897f, 0.052060816437006f, 0.002757790964097f, - 0.052442211657763f, - 0.002798160072416f, 0.052823577076197f, 0.002838821383193f, - 0.053204908967018f, - 0.002879775362089f, 0.053586211055517f, 0.002921021543443f, - 0.053967483341694f, - 0.002962560392916f, 0.054348722100258f, 0.003004391444847f, - 0.054729927331209f, - 0.003046514932066f, 0.055111102759838f, 0.003088930854574f, - 0.055492244660854f, - 0.003131638979539f, 0.055873356759548f, 0.003174639539793f, - 0.056254431605339f, - 0.003217932302505f, 0.056635476648808f, 0.003261517267674f, - 0.057016488164663f, - 0.003305394435301f, 0.057397462427616f, 0.003349563805386f, - 0.057778406888247f, - 0.003394025377929f, 0.058159314095974f, 0.003438779152930f, - 0.058540191501379f, - 0.003483824897557f, 0.058921031653881f, 0.003529162844643f, - 0.059301838278770f, - 0.003574792761356f, 0.059682607650757f, 0.003620714880526f, - 0.060063343495131f, - 0.003666928736493f, 0.060444042086601f, 0.003713434794918f, - 0.060824707150459f, - 0.003760232590139f, 0.061205338686705f, 0.003807322587818f, - 0.061585929244757f, - 0.003854704322293f, 0.061966486275196f, 0.003902378026396f, - 0.062347009778023f, - 0.003950343467295f, 0.062727488577366f, 0.003998600877821f, - 0.063107937574387f, - 0.004047149792314f, 0.063488349318504f, 0.004095990676433f, - 0.063868723809719f, - 0.004145123064518f, 0.064249053597450f, 0.004194547422230f, - 0.064629353582859f, - 0.004244263283908f, 0.065009608864784f, 0.004294271115214f, - 0.065389834344387f, - 0.004344569984823f, 0.065770015120506f, 0.004395160824060f, - 0.066150158643723f, - 0.004446043167263f, 0.066530264914036f, 0.004497217014432f, - 0.066910326480865f, - 0.004548682365566f, 0.067290350794792f, 0.004600439220667f, - 0.067670337855816f, - 0.004652487114072f, 0.068050287663937f, 0.004704826977104f, - 0.068430192768574f, - 0.004757457878441f, 0.068810060620308f, 0.004810380283743f, - 0.069189883768559f, - 0.004863593727350f, 0.069569669663906f, 0.004917098674923f, - 0.069949418306351f, - 0.004970894660801f, 0.070329122245312f, 0.005024982150644f, - 0.070708781480789f, - 0.005079360678792f, 0.071088403463364f, 0.005134030245245f, - 0.071467980742455f, - 0.005188991315663f, 0.071847513318062f, 0.005244242958724f, - 0.072227008640766f, - 0.005299786105752f, 0.072606459259987f, 0.005355620291084f, - 0.072985872626305f, - 0.005411745049059f, 0.073365233838558f, 0.005468160845339f, - 0.073744557797909f, - 0.005524867679924f, 0.074123837053776f, 0.005581865552813f, - 0.074503071606159f, - 0.005639153998345f, 0.074882268905640f, 0.005696733482182f, - 0.075261414051056f, - 0.005754603538662f, 0.075640521943569f, 0.005812764633447f, - 0.076019577682018f, - 0.005871216300875f, 0.076398596167564f, 0.005929958540946f, - 0.076777562499046f, - 0.005988991353661f, 0.077156484127045f, 0.006048315204680f, - 0.077535368502140f, - 0.006107929162681f, 0.077914200723171f, 0.006167833693326f, - 0.078292988240719f, - 0.006228029262275f, 0.078671731054783f, 0.006288514938205f, - 0.079050421714783f, - 0.006349290721118f, 0.079429075121880f, 0.006410357542336f, - 0.079807676374912f, - 0.006471714470536f, 0.080186225473881f, 0.006533361505717f, - 0.080564737319946f, - 0.006595299113542f, 0.080943197011948f, 0.006657526828349f, - 0.081321612000465f, - 0.006720044650137f, 0.081699974834919f, 0.006782853044569f, - 0.082078292965889f, - 0.006845951545984f, 0.082456558942795f, 0.006909339688718f, - 0.082834780216217f, - 0.006973018404096f, 0.083212949335575f, 0.007036986760795f, - 0.083591073751450f, - 0.007101245224476f, 0.083969146013260f, 0.007165793795139f, - 0.084347173571587f, - 0.007230632472783f, 0.084725148975849f, 0.007295760791749f, - 0.085103072226048f, - 0.007361178752035f, 0.085480943322182f, 0.007426886819303f, - 0.085858769714832f, - 0.007492884527892f, 0.086236543953419f, 0.007559171877801f, - 0.086614266037941f, - 0.007625748869032f, 0.086991935968399f, 0.007692615967244f, - 0.087369553744793f, - 0.007759772241116f, 0.087747126817703f, 0.007827218621969f, - 0.088124647736549f, - 0.007894953712821f, 0.088502109050751f, 0.007962978444993f, - 0.088879525661469f, - 0.008031292818487f, 0.089256882667542f, 0.008099896833301f, - 0.089634194970131f, - 0.008168790489435f, 0.090011447668076f, 0.008237972855568f, - 0.090388655662537f, - 0.008307444863021f, 0.090765804052353f, 0.008377205580473f, - 0.091142900288105f, - 0.008447255939245f, 0.091519944369793f, 0.008517595939338f, - 0.091896936297417f, - 0.008588224649429f, 0.092273868620396f, 0.008659142069519f, - 0.092650748789310f, - 0.008730349130929f, 0.093027576804161f, 0.008801844902337f, - 0.093404345214367f, - 0.008873629383743f, 0.093781061470509f, 0.008945702575147f, - 0.094157725572586f, - 0.009018065407872f, 0.094534330070019f, 0.009090716950595f, - 0.094910882413387f, - 0.009163657203317f, 0.095287375152111f, 0.009236886166036f, - 0.095663815736771f, - 0.009310402907431f, 0.096040196716785f, 0.009384209290147f, - 0.096416525542736f, - 0.009458304382861f, 0.096792794764042f, 0.009532688185573f, - 0.097169004380703f, - 0.009607359766960f, 0.097545161843300f, 0.009682320058346f, - 0.097921259701252f, - 0.009757569059730f, 0.098297297954559f, 0.009833106771111f, - 0.098673284053802f, - 0.009908932261169f, 0.099049203097820f, 0.009985045529902f, - 0.099425069987774f, - 0.010061448439956f, 0.099800877273083f, 0.010138138197362f, - 0.100176624953747f, - 0.010215117596090f, 0.100552320480347f, 0.010292383842170f, - 0.100927948951721f, - 0.010369938798249f, 0.101303517818451f, 0.010447781533003f, - 0.101679034531116f, - 0.010525912046432f, 0.102054484188557f, 0.010604331269860f, - 0.102429874241352f, - 0.010683037340641f, 0.102805204689503f, 0.010762032121420f, - 0.103180475533009f, - 0.010841314680874f, 0.103555686771870f, 0.010920885019004f, - 0.103930838406086f, - 0.011000742204487f, 0.104305922985077f, 0.011080888099968f, - 0.104680955410004f, - 0.011161320842803f, 0.105055920779705f, 0.011242041364312f, - 0.105430819094181f, - 0.011323049664497f, 0.105805665254593f, 0.011404345743358f, - 0.106180444359779f, - 0.011485928669572f, 0.106555156409740f, 0.011567799374461f, - 0.106929816305637f, - 0.011649956926703f, 0.107304409146309f, 0.011732402257621f, - 0.107678934931755f, - 0.011815134435892f, 0.108053401112556f, 0.011898153461516f, - 0.108427800238132f, - 0.011981460265815f, 0.108802139759064f, 0.012065053917468f, - 0.109176412224770f, - 0.012148935347795f, 0.109550617635250f, 0.012233102694154f, - 0.109924763441086f, - 0.012317557819188f, 0.110298842191696f, 0.012402298860252f, - 0.110672861337662f, - 0.012487327679992f, 0.111046813428402f, 0.012572642415762f, - 0.111420698463917f, - 0.012658244930208f, 0.111794516444206f, 0.012744133360684f, - 0.112168267369270f, - 0.012830308638513f, 0.112541958689690f, 0.012916770763695f, - 0.112915575504303f, - 0.013003518804908f, 0.113289132714272f, 0.013090553693473f, - 0.113662622869015f, - 0.013177875429392f, 0.114036038517952f, 0.013265483081341f, - 0.114409394562244f, - 0.013353376649320f, 0.114782683551311f, 0.013441557064652f, - 0.115155905485153f, - 0.013530024327338f, 0.115529052913189f, 0.013618776574731f, - 0.115902140736580f, - 0.013707815669477f, 0.116275154054165f, 0.013797140680254f, - 0.116648100316525f, - 0.013886751607060f, 0.117020979523659f, 0.013976648449898f, - 0.117393791675568f, - 0.014066831208766f, 0.117766529321671f, 0.014157299883664f, - 0.118139199912548f, - 0.014248054474592f, 0.118511803448200f, 0.014339094981551f, - 0.118884332478046f, - 0.014430420473218f, 0.119256794452667f, 0.014522032812238f, - 0.119629189372063f, - 0.014613929204643f, 0.120001509785652f, 0.014706112444401f, - 0.120373763144016f, - 0.014798580668867f, 0.120745941996574f, 0.014891333878040f, - 0.121118053793907f, - 0.014984373003244f, 0.121490091085434f, 0.015077698044479f, - 0.121862053871155f, - 0.015171307139099f, 0.122233949601650f, 0.015265202149749f, - 0.122605770826340f, - 0.015359382145107f, 0.122977524995804f, 0.015453847125173f, - 0.123349204659462f, - 0.015548598021269f, 0.123720809817314f, 0.015643632039428f, - 0.124092340469360f, - 0.015738952904940f, 0.124463804066181f, 0.015834558755159f, - 0.124835193157196f, - 0.015930447727442f, 0.125206500291824f, 0.016026621684432f, - 0.125577747821808f, - 0.016123080626130f, 0.125948905944824f, 0.016219824552536f, - 0.126320004463196f, - 0.016316853463650f, 0.126691013574600f, 0.016414167359471f, - 0.127061963081360f, - 0.016511764377356f, 0.127432823181152f, 0.016609646379948f, - 0.127803623676300f, - 0.016707813367248f, 0.128174334764481f, 0.016806263476610f, - 0.128544986248016f, - 0.016904998570681f, 0.128915548324585f, 0.017004016786814f, - 0.129286035895348f, - 0.017103319987655f, 0.129656463861465f, 0.017202908173203f, - 0.130026802420616f, - 0.017302779480815f, 0.130397051572800f, 0.017402933910489f, - 0.130767241120338f, - 0.017503373324871f, 0.131137356162071f, 0.017604095861316f, - 0.131507381796837f, - 0.017705103382468f, 0.131877332925797f, 0.017806394025683f, - 0.132247209548950f, - 0.017907967790961f, 0.132617011666298f, 0.018009826540947f, - 0.132986739277840f, - 0.018111966550350f, 0.133356377482414f, 0.018214391544461f, - 0.133725941181183f, - 0.018317099660635f, 0.134095430374146f, 0.018420090898871f, - 0.134464830160141f, - 0.018523367121816f, 0.134834155440331f, 0.018626924604177f, - 0.135203406214714f, - 0.018730765208602f, 0.135572582483292f, 0.018834890797734f, - 0.135941669344902f, - 0.018939297646284f, 0.136310681700706f, 0.019043987616897f, - 0.136679604649544f, - 0.019148962572217f, 0.137048453092575f, 0.019254218786955f, - 0.137417227029800f, - 0.019359756261110f, 0.137785911560059f, 0.019465578719974f, - 0.138154521584511f, - 0.019571684300900f, 0.138523042201996f, 0.019678071141243f, - 0.138891488313675f, - 0.019784741103649f, 0.139259845018387f, 0.019891692325473f, - 0.139628127217293f, - 0.019998926669359f, 0.139996320009232f, 0.020106444135308f, - 0.140364438295364f, - 0.020214242860675f, 0.140732467174530f, 0.020322324708104f, - 0.141100421547890f, - 0.020430689677596f, 0.141468286514282f, 0.020539334043860f, - 0.141836062073708f, - 0.020648263394833f, 0.142203763127327f, 0.020757472142577f, - 0.142571389675140f, - 0.020866964012384f, 0.142938911914825f, 0.020976737141609f, - 0.143306359648705f, - 0.021086793392897f, 0.143673732876778f, 0.021197130903602f, - 0.144041016697884f, - 0.021307749673724f, 0.144408211112022f, 0.021418649703264f, - 0.144775316119194f, - 0.021529832854867f, 0.145142331719399f, 0.021641295403242f, - 0.145509272813797f, - 0.021753041073680f, 0.145876124501228f, 0.021865066140890f, - 0.146242901682854f, - 0.021977374330163f, 0.146609574556351f, 0.022089963778853f, - 0.146976172924042f, - 0.022202832624316f, 0.147342681884766f, 0.022315984591842f, - 0.147709101438522f, - 0.022429415956140f, 0.148075446486473f, 0.022543128579855f, - 0.148441687226295f, - 0.022657122462988f, 0.148807853460312f, 0.022771397605538f, - 0.149173930287361f, - 0.022885952144861f, 0.149539917707443f, 0.023000787943602f, - 0.149905815720558f, - 0.023115905001760f, 0.150271624326706f, 0.023231301456690f, - 0.150637343525887f, - 0.023346979171038f, 0.151002973318100f, 0.023462938144803f, - 0.151368513703346f, - 0.023579176515341f, 0.151733979582787f, 0.023695694282651f, - 0.152099341154099f, - 0.023812493309379f, 0.152464613318443f, 0.023929571732879f, - 0.152829796075821f, - 0.024046931415796f, 0.153194904327393f, 0.024164570495486f, - 0.153559908270836f, - 0.024282488971949f, 0.153924822807312f, 0.024400688707829f, - 0.154289647936821f, - 0.024519165977836f, 0.154654383659363f, 0.024637924507260f, - 0.155019029974937f, - 0.024756962433457f, 0.155383571982384f, 0.024876279756427f, - 0.155748039484024f, - 0.024995878338814f, 0.156112402677536f, 0.025115754455328f, - 0.156476691365242f, - 0.025235909968615f, 0.156840875744820f, 0.025356344878674f, - 0.157204970717430f, - 0.025477059185505f, 0.157568961381912f, 0.025598052889109f, - 0.157932877540588f, - 0.025719324126840f, 0.158296689391136f, 0.025840876623988f, - 0.158660411834717f, - 0.025962706655264f, 0.159024044871330f, 0.026084816083312f, - 0.159387573599815f, - 0.026207204908133f, 0.159751012921333f, 0.026329871267080f, - 0.160114362835884f, - 0.026452817022800f, 0.160477623343468f, 0.026576040312648f, - 0.160840779542923f, - 0.026699542999268f, 0.161203846335411f, 0.026823325082660f, - 0.161566808819771f, - 0.026947384700179f, 0.161929681897163f, 0.027071721851826f, - 0.162292465567589f, - 0.027196336537600f, 0.162655144929886f, 0.027321230620146f, - 0.163017734885216f, - 0.027446404099464f, 0.163380220532417f, 0.027571853250265f, - 0.163742616772652f, - 0.027697581797838f, 0.164104923605919f, 0.027823587879539f, - 0.164467126131058f, - 0.027949871495366f, 0.164829224348068f, 0.028076432645321f, - 0.165191248059273f, - 0.028203271329403f, 0.165553152561188f, 0.028330387547612f, - 0.165914967656136f, - 0.028457781299949f, 0.166276678442955f, 0.028585452586412f, - 0.166638299822807f, - 0.028713401407003f, 0.166999831795692f, 0.028841627761722f, - 0.167361244559288f, - 0.028970129787922f, 0.167722567915916f, 0.029098909348249f, - 0.168083801865578f, - 0.029227968305349f, 0.168444931507111f, 0.029357301071286f, - 0.168805956840515f, - 0.029486913233995f, 0.169166877865791f, 0.029616801068187f, - 0.169527709484100f, - 0.029746964573860f, 0.169888436794281f, 0.029877405613661f, - 0.170249074697495f, - 0.030008124187589f, 0.170609608292580f, 0.030139118432999f, - 0.170970037579536f, - 0.030270388349891f, 0.171330362558365f, 0.030401935800910f, - 0.171690583229065f, - 0.030533758923411f, 0.172050714492798f, 0.030665857717395f, - 0.172410741448402f, - 0.030798232182860f, 0.172770664095879f, 0.030930884182453f, - 0.173130482435226f, - 0.031063811853528f, 0.173490211367607f, 0.031197015196085f, - 0.173849821090698f, - 0.031330492347479f, 0.174209341406822f, 0.031464248895645f, - 0.174568757414818f, - 0.031598277390003f, 0.174928069114685f, 0.031732585281134f, - 0.175287276506424f, - 0.031867165118456f, 0.175646379590034f, 0.032002024352551f, - 0.176005378365517f, - 0.032137155532837f, 0.176364272832870f, 0.032272562384605f, - 0.176723077893257f, - 0.032408244907856f, 0.177081763744354f, 0.032544203102589f, - 0.177440345287323f, - 0.032680433243513f, 0.177798837423325f, 0.032816942781210f, - 0.178157210350037f, - 0.032953724265099f, 0.178515478968620f, 0.033090781420469f, - 0.178873643279076f, - 0.033228114247322f, 0.179231703281403f, 0.033365719020367f, - 0.179589673876762f, - 0.033503599464893f, 0.179947525262833f, 0.033641755580902f, - 0.180305257439613f, - 0.033780183643103f, 0.180662900209427f, 0.033918887376785f, - 0.181020438671112f, - 0.034057866781950f, 0.181377857923508f, 0.034197118133307f, - 0.181735187768936f, - 0.034336645156145f, 0.182092398405075f, 0.034476444125175f, - 0.182449504733086f, - 0.034616518765688f, 0.182806491851807f, 0.034756865352392f, - 0.183163389563560f, - 0.034897487610579f, 0.183520168066025f, 0.035038381814957f, - 0.183876842260361f, - 0.035179551690817f, 0.184233412146568f, 0.035320993512869f, - 0.184589877724648f, - 0.035462711006403f, 0.184946224093437f, 0.035604696720839f, - 0.185302466154099f, - 0.035746958106756f, 0.185658603906631f, 0.035889495164156f, - 0.186014622449875f, - 0.036032304167747f, 0.186370536684990f, 0.036175385117531f, - 0.186726331710815f, - 0.036318738013506f, 0.187082037329674f, 0.036462362855673f, - 0.187437608838081f, - 0.036606263369322f, 0.187793090939522f, 0.036750435829163f, - 0.188148453831673f, - 0.036894880235195f, 0.188503712415695f, 0.037039596587420f, - 0.188858851790428f, - 0.037184584885836f, 0.189213871955872f, 0.037329845130444f, - 0.189568802714348f, - 0.037475381046534f, 0.189923599362373f, 0.037621185183525f, - 0.190278306603432f, - 0.037767261266708f, 0.190632879734039f, 0.037913613021374f, - 0.190987363457680f, - 0.038060232996941f, 0.191341713070869f, 0.038207128643990f, - 0.191695958375931f, - 0.038354292511940f, 0.192050099372864f, 0.038501728326082f, - 0.192404121160507f, - 0.038649436086416f, 0.192758023738861f, 0.038797415792942f, - 0.193111822009087f, - 0.038945667445660f, 0.193465501070023f, 0.039094187319279f, - 0.193819075822830f, - 0.039242979139090f, 0.194172516465187f, 0.039392042905092f, - 0.194525867700577f, - 0.039541378617287f, 0.194879084825516f, 0.039690986275673f, - 0.195232197642326f, - 0.039840862154961f, 0.195585191249847f, 0.039991009980440f, - 0.195938065648079f, - 0.040141426026821f, 0.196290835738182f, 0.040292114019394f, - 0.196643486618996f, - 0.040443073958158f, 0.196996018290520f, 0.040594302117825f, - 0.197348430752754f, - 0.040745802223682f, 0.197700738906860f, 0.040897574275732f, - 0.198052927851677f, - 0.041049610823393f, 0.198404997587204f, 0.041201923042536f, - 0.198756948113441f, - 0.041354499757290f, 0.199108779430389f, 0.041507352143526f, - 0.199460506439209f, - 0.041660469025373f, 0.199812099337578f, 0.041813857853413f, - 0.200163587927818f, - 0.041967518627644f, 0.200514942407608f, 0.042121443897486f, - 0.200866192579269f, - 0.042275641113520f, 0.201217323541641f, 0.042430106550455f, - 0.201568335294724f, - 0.042584843933582f, 0.201919227838516f, 0.042739849537611f, - 0.202270001173019f, - 0.042895123362541f, 0.202620655298233f, 0.043050665408373f, - 0.202971190214157f, - 0.043206475675106f, 0.203321605920792f, 0.043362557888031f, - 0.203671902418137f, - 0.043518904596567f, 0.204022079706192f, 0.043675523251295f, - 0.204372137784958f, - 0.043832406401634f, 0.204722076654434f, 0.043989561498165f, - 0.205071896314621f, - 0.044146984815598f, 0.205421581864357f, 0.044304672628641f, - 0.205771163105965f, - 0.044462632387877f, 0.206120610237122f, 0.044620860368013f, - 0.206469938158989f, - 0.044779352843761f, 0.206819161772728f, 0.044938117265701f, - 0.207168251276016f, - 0.045097146183252f, 0.207517206668854f, 0.045256443321705f, - 0.207866057753563f, - 0.045416008681059f, 0.208214774727821f, 0.045575842261314f, - 0.208563387393951f, - 0.045735940337181f, 0.208911851048470f, 0.045896306633949f, - 0.209260210394859f, - 0.046056941151619f, 0.209608450531960f, 0.046217843890190f, - 0.209956556558609f, - 0.046379011124372f, 0.210304543375969f, 0.046540446579456f, - 0.210652396082878f, - 0.046702146530151f, 0.211000129580498f, 0.046864114701748f, - 0.211347743868828f, - 0.047026351094246f, 0.211695238947868f, 0.047188851982355f, - 0.212042599916458f, - 0.047351621091366f, 0.212389841675758f, 0.047514654695988f, - 0.212736949324608f, - 0.047677956521511f, 0.213083937764168f, 0.047841522842646f, - 0.213430806994438f, - 0.048005353659391f, 0.213777542114258f, 0.048169452697039f, - 0.214124158024788f, - 0.048333816230297f, 0.214470639824867f, 0.048498444259167f, - 0.214817002415657f, - 0.048663340508938f, 0.215163245797157f, 0.048828501254320f, - 0.215509355068207f, - 0.048993926495314f, 0.215855330228806f, 0.049159619957209f, - 0.216201186180115f, - 0.049325577914715f, 0.216546908020973f, 0.049491796642542f, - 0.216892510652542f, - 0.049658283591270f, 0.217237979173660f, 0.049825038760900f, - 0.217583328485489f, - 0.049992054700851f, 0.217928543686867f, 0.050159335136414f, - 0.218273624777794f, - 0.050326880067587f, 0.218618586659431f, 0.050494693219662f, - 0.218963414430618f, - 0.050662767142057f, 0.219308122992516f, 0.050831105560064f, - 0.219652697443962f, - 0.050999708473682f, 0.219997137784958f, 0.051168579608202f, - 0.220341444015503f, - 0.051337707787752f, 0.220685631036758f, 0.051507104188204f, - 0.221029683947563f, - 0.051676765084267f, 0.221373617649078f, 0.051846686750650f, - 0.221717402338982f, - 0.052016876637936f, 0.222061067819595f, 0.052187327295542f, - 0.222404599189758f, - 0.052358038723469f, 0.222748011350632f, 0.052529018372297f, - 0.223091274499893f, - 0.052700258791447f, 0.223434418439865f, 0.052871759980917f, - 0.223777428269386f, - 0.053043525665998f, 0.224120303988457f, 0.053215555846691f, - 0.224463045597076f, - 0.053387850522995f, 0.224805667996407f, 0.053560405969620f, - 0.225148141384125f, - 0.053733222186565f, 0.225490495562553f, 0.053906302899122f, - 0.225832715630531f, - 0.054079644382000f, 0.226174786686897f, 0.054253250360489f, - 0.226516738533974f, - 0.054427117109299f, 0.226858556270599f, 0.054601248353720f, - 0.227200239896774f, - 0.054775636643171f, 0.227541789412498f, 0.054950293153524f, - 0.227883204817772f, - 0.055125206708908f, 0.228224486112595f, 0.055300384759903f, - 0.228565633296967f, - 0.055475823581219f, 0.228906646370888f, 0.055651523172855f, - 0.229247525334358f, - 0.055827483534813f, 0.229588270187378f, 0.056003704667091f, - 0.229928880929947f, - 0.056180190294981f, 0.230269357562065f, 0.056356932967901f, - 0.230609700083733f, - 0.056533940136433f, 0.230949893593788f, 0.056711208075285f, - 0.231289967894554f, - 0.056888736784458f, 0.231629893183708f, 0.057066522538662f, - 0.231969684362412f, - 0.057244572788477f, 0.232309341430664f, 0.057422880083323f, - 0.232648864388466f, - 0.057601451873779f, 0.232988253235817f, 0.057780280709267f, - 0.233327493071556f, - 0.057959370315075f, 0.233666598796844f, 0.058138720691204f, - 0.234005570411682f, - 0.058318331837654f, 0.234344407916069f, 0.058498200029135f, - 0.234683111310005f, - 0.058678328990936f, 0.235021665692329f, 0.058858718723059f, - 0.235360085964203f, - 0.059039369225502f, 0.235698372125626f, 0.059220276772976f, - 0.236036509275436f, - 0.059401445090771f, 0.236374512314796f, 0.059582870453596f, - 0.236712381243706f, - 0.059764556586742f, 0.237050101161003f, 0.059946499764919f, - 0.237387686967850f, - 0.060128703713417f, 0.237725138664246f, 0.060311164706945f, - 0.238062441349030f, - 0.060493886470795f, 0.238399609923363f, 0.060676865279675f, - 0.238736644387245f, - 0.060860104858875f, 0.239073529839516f, 0.061043601483107f, - 0.239410281181335f, - 0.061227355152369f, 0.239746883511543f, 0.061411365866661f, - 0.240083336830139f, - 0.061595637351274f, 0.240419670939446f, 0.061780165880919f, - 0.240755841135979f, - 0.061964951455593f, 0.241091892123222f, 0.062149997800589f, - 0.241427779197693f, - 0.062335297465324f, 0.241763532161713f, 0.062520854175091f, - 0.242099151015282f, - 0.062706671655178f, 0.242434620857239f, 0.062892749905586f, - 0.242769956588745f, - 0.063079081475735f, 0.243105143308640f, 0.063265666365623f, - 0.243440181016922f, - 0.063452512025833f, 0.243775084614754f, 0.063639611005783f, - 0.244109839200974f, - 0.063826970756054f, 0.244444444775581f, 0.064014583826065f, - 0.244778916239738f, - 0.064202457666397f, 0.245113238692284f, 0.064390584826469f, - 0.245447427034378f, - 0.064578965306282f, 0.245781451463699f, 0.064767606556416f, - 0.246115356683731f, - 0.064956501126289f, 0.246449097990990f, 0.065145656466484f, - 0.246782705187798f, - 0.065335065126419f, 0.247116148471832f, 0.065524727106094f, - 0.247449472546577f, - 0.065714649856091f, 0.247782632708550f, 0.065904818475246f, - 0.248115643858910f, - 0.066095255315304f, 0.248448520898819f, 0.066285938024521f, - 0.248781248927116f, - 0.066476874053478f, 0.249113827943802f, 0.066668070852757f, - 0.249446272850037f, - 0.066859520971775f, 0.249778553843498f, 0.067051224410534f, - 0.250110685825348f, - 0.067243188619614f, 0.250442683696747f, 0.067435398697853f, - 0.250774532556534f, - 0.067627869546413f, 0.251106232404709f, 0.067820593714714f, - 0.251437783241272f, - 0.068013571202755f, 0.251769185066223f, 0.068206802010536f, - 0.252100437879562f, - 0.068400286138058f, 0.252431541681290f, 0.068594031035900f, - 0.252762526273727f, - 0.068788021802902f, 0.253093332052231f, 0.068982265889645f, - 0.253423988819122f, - 0.069176770746708f, 0.253754496574402f, 0.069371521472931f, - 0.254084855318069f, - 0.069566532969475f, 0.254415065050125f, 0.069761790335178f, - 0.254745125770569f, - 0.069957308471203f, 0.255075037479401f, 0.070153072476387f, - 0.255404800176620f, - 0.070349089801311f, 0.255734413862228f, 0.070545360445976f, - 0.256063878536224f, - 0.070741884410381f, 0.256393194198608f, 0.070938661694527f, - 0.256722360849380f, - 0.071135692298412f, 0.257051378488541f, 0.071332976222038f, - 0.257380217313766f, - 0.071530513465405f, 0.257708936929703f, 0.071728296577930f, - 0.258037507534027f, - 0.071926333010197f, 0.258365899324417f, 0.072124622762203f, - 0.258694142103195f, - 0.072323165833950f, 0.259022265672684f, 0.072521962225437f, - 0.259350210428238f, - 0.072721004486084f, 0.259678006172180f, 0.072920300066471f, - 0.260005623102188f, - 0.073119848966599f, 0.260333120822906f, 0.073319651186466f, - 0.260660469532013f, - 0.073519699275494f, 0.260987639427185f, 0.073720000684261f, - 0.261314690113068f, - 0.073920547962189f, 0.261641561985016f, 0.074121348559856f, - 0.261968284845352f, - 0.074322402477264f, 0.262294828891754f, 0.074523709714413f, - 0.262621253728867f, - 0.074725262820721f, 0.262947499752045f, 0.074927061796188f, - 0.263273626565933f, - 0.075129114091396f, 0.263599574565887f, 0.075331419706345f, - 0.263925373554230f, - 0.075533971190453f, 0.264250993728638f, 0.075736775994301f, - 0.264576494693756f, - 0.075939826667309f, 0.264901816844940f, 0.076143130660057f, - 0.265226989984512f, - 0.076346680521965f, 0.265552014112473f, 0.076550483703613f, - 0.265876859426498f, - 0.076754532754421f, 0.266201555728912f, 0.076958827674389f, - 0.266526103019714f, - 0.077163375914097f, 0.266850501298904f, 0.077368170022964f, - 0.267174720764160f, - 0.077573217451572f, 0.267498821020126f, 0.077778510749340f, - 0.267822742462158f, - 0.077984049916267f, 0.268146485090256f, 0.078189842402935f, - 0.268470078706741f, - 0.078395880758762f, 0.268793523311615f, 0.078602164983749f, - 0.269116818904877f, - 0.078808702528477f, 0.269439965486526f, 0.079015478491783f, - 0.269762933254242f, - 0.079222507774830f, 0.270085722208023f, 0.079429790377617f, - 0.270408391952515f, - 0.079637311398983f, 0.270730882883072f, 0.079845085740089f, - 0.271053224802017f, - 0.080053105950356f, 0.271375387907028f, 0.080261372029781f, - 0.271697402000427f, - 0.080469883978367f, 0.272019267082214f, 0.080678641796112f, - 0.272340953350067f, - 0.080887645483017f, 0.272662490606308f, 0.081096902489662f, - 0.272983878850937f, - 0.081306397914886f, 0.273305088281631f, 0.081516146659851f, - 0.273626148700714f, - 0.081726133823395f, 0.273947030305862f, 0.081936374306679f, - 0.274267762899399f, - 0.082146860659122f, 0.274588316679001f, 0.082357585430145f, - 0.274908751249313f, - 0.082568563520908f, 0.275228977203369f, 0.082779780030251f, - 0.275549083948135f, - 0.082991249859333f, 0.275868982076645f, 0.083202958106995f, - 0.276188760995865f, - 0.083414919674397f, 0.276508361101151f, 0.083627119660378f, - 0.276827782392502f, - 0.083839565515518f, 0.277147054672241f, 0.084052257239819f, - 0.277466177940369f, - 0.084265194833279f, 0.277785122394562f, 0.084478378295898f, - 0.278103888034821f, - 0.084691800177097f, 0.278422504663467f, 0.084905467927456f, - 0.278740972280502f, - 0.085119381546974f, 0.279059261083603f, 0.085333541035652f, - 0.279377400875092f, - 0.085547938942909f, 0.279695361852646f, 0.085762590169907f, - 0.280013144016266f, - 0.085977479815483f, 0.280330777168274f, 0.086192607879639f, - 0.280648261308670f, - 0.086407989263535f, 0.280965566635132f, 0.086623609066010f, - 0.281282693147659f, - 0.086839467287064f, 0.281599670648575f, 0.087055571377277f, - 0.281916469335556f, - 0.087271921336651f, 0.282233119010925f, 0.087488517165184f, - 0.282549589872360f, - 0.087705351412296f, 0.282865911722183f, 0.087922424077988f, - 0.283182054758072f, - 0.088139742612839f, 0.283498018980026f, 0.088357307016850f, - 0.283813834190369f, - 0.088575109839439f, 0.284129470586777f, 0.088793158531189f, - 0.284444957971573f, - 0.089011445641518f, 0.284760266542435f, 0.089229971170425f, - 0.285075396299362f, - 0.089448742568493f, 0.285390377044678f, 0.089667752385139f, - 0.285705178976059f, - 0.089887008070946f, 0.286019802093506f, 0.090106502175331f, - 0.286334276199341f, - 0.090326242148876f, 0.286648571491241f, 0.090546220541000f, - 0.286962717771530f, - 0.090766437351704f, 0.287276685237885f, 0.090986892580986f, - 0.287590473890305f, - 0.091207593679428f, 0.287904083728790f, 0.091428533196449f, - 0.288217544555664f, - 0.091649711132050f, 0.288530826568604f, 0.091871134936810f, - 0.288843959569931f, - 0.092092797160149f, 0.289156883955002f, 0.092314697802067f, - 0.289469659328461f, - 0.092536836862564f, 0.289782285690308f, 0.092759214341640f, - 0.290094703435898f, - 0.092981837689877f, 0.290406972169876f, 0.093204692006111f, - 0.290719062089920f, - 0.093427792191505f, 0.291031002998352f, 0.093651130795479f, - 0.291342735290527f, - 0.093874707818031f, 0.291654318571091f, 0.094098523259163f, - 0.291965723037720f, - 0.094322577118874f, 0.292276978492737f, 0.094546869397163f, - 0.292588025331497f, - 0.094771400094032f, 0.292898923158646f, 0.094996169209480f, - 0.293209642171860f, - 0.095221176743507f, 0.293520182371140f, 0.095446422696114f, - 0.293830573558807f, - 0.095671907067299f, 0.294140785932541f, 0.095897629857063f, - 0.294450789690018f, - 0.096123591065407f, 0.294760644435883f, 0.096349790692329f, - 0.295070350170136f, - 0.096576221287251f, 0.295379847288132f, 0.096802897751331f, - 0.295689195394516f, - 0.097029805183411f, 0.295998334884644f, 0.097256951034069f, - 0.296307325363159f, - 0.097484335303307f, 0.296616137027740f, 0.097711957991123f, - 0.296924799680710f, - 0.097939811646938f, 0.297233253717422f, 0.098167903721333f, - 0.297541528940201f, - 0.098396234214306f, 0.297849655151367f, 0.098624803125858f, - 0.298157602548599f, - 0.098853603005409f, 0.298465341329575f, 0.099082641303539f, - 0.298772931098938f, - 0.099311910569668f, 0.299080342054367f, 0.099541425704956f, - 0.299387603998184f, - 0.099771171808243f, 0.299694657325745f, 0.100001148879528f, - 0.300001531839371f, - 0.100231364369392f, 0.300308227539063f, 0.100461818277836f, - 0.300614774227142f, - 0.100692503154278f, 0.300921112298965f, 0.100923426449299f, - 0.301227301359177f, - 0.101154580712318f, 0.301533311605453f, 0.101385973393917f, - 0.301839113235474f, - 0.101617597043514f, 0.302144765853882f, 0.101849451661110f, - 0.302450239658356f, - 0.102081544697285f, 0.302755534648895f, 0.102313876152039f, - 0.303060621023178f, - 0.102546438574791f, 0.303365558385849f, 0.102779231965542f, - 0.303670316934586f, - 0.103012263774872f, 0.303974896669388f, 0.103245526552200f, - 0.304279297590256f, - 0.103479020297527f, 0.304583519697189f, 0.103712752461433f, - 0.304887533187866f, - 0.103946708142757f, 0.305191397666931f, 0.104180909693241f, - 0.305495083332062f, - 0.104415334761143f, 0.305798590183258f, 0.104649998247623f, - 0.306101888418198f, - 0.104884892702103f, 0.306405037641525f, 0.105120018124580f, - 0.306708008050919f, - 0.105355374515057f, 0.307010769844055f, 0.105590961873531f, - 0.307313382625580f, - 0.105826787650585f, 0.307615786790848f, 0.106062836945057f, - 0.307918041944504f, - 0.106299124658108f, 0.308220088481903f, 0.106535643339157f, - 0.308521956205368f, - 0.106772392988205f, 0.308823645114899f, 0.107009373605251f, - 0.309125155210495f, - 0.107246585190296f, 0.309426486492157f, 0.107484027743340f, - 0.309727638959885f, - 0.107721701264381f, 0.310028612613678f, 0.107959605753422f, - 0.310329377651215f, - 0.108197741210461f, 0.310629993677139f, 0.108436107635498f, - 0.310930401086807f, - 0.108674705028534f, 0.311230629682541f, 0.108913525938988f, - 0.311530679464340f, - 0.109152585268021f, 0.311830550432205f, 0.109391868114471f, - 0.312130242586136f, - 0.109631389379501f, 0.312429755926132f, 0.109871134161949f, - 0.312729060649872f, - 0.110111102461815f, 0.313028186559677f, 0.110351309180260f, - 0.313327133655548f, - 0.110591746866703f, 0.313625901937485f, 0.110832408070564f, - 0.313924491405487f, - 0.111073300242424f, 0.314222872257233f, 0.111314415931702f, - 0.314521104097366f, - 0.111555770039558f, 0.314819127321243f, 0.111797347664833f, - 0.315116971731186f, - 0.112039148807526f, 0.315414607524872f, 0.112281180918217f, - 0.315712094306946f, - 0.112523443996906f, 0.316009372472763f, 0.112765938043594f, - 0.316306471824646f, - 0.113008655607700f, 0.316603392362595f, 0.113251596689224f, - 0.316900104284287f, - 0.113494776189327f, 0.317196637392044f, 0.113738171756268f, - 0.317492991685867f, - 0.113981798291206f, 0.317789167165756f, 0.114225655794144f, - 0.318085134029388f, - 0.114469736814499f, 0.318380922079086f, 0.114714048802853f, - 0.318676531314850f, - 0.114958584308624f, 0.318971961736679f, 0.115203343331814f, - 0.319267183542252f, - 0.115448333323002f, 0.319562226533890f, 0.115693546831608f, - 0.319857090711594f, - 0.115938983857632f, 0.320151746273041f, 0.116184651851654f, - 0.320446223020554f, - 0.116430543363094f, 0.320740520954132f, 0.116676658391953f, - 0.321034610271454f, - 0.116923004388809f, 0.321328520774841f, 0.117169573903084f, - 0.321622252464294f, - 0.117416366934776f, 0.321915775537491f, 0.117663383483887f, - 0.322209119796753f, - 0.117910631000996f, 0.322502255439758f, 0.118158094584942f, - 0.322795242071152f, - 0.118405789136887f, 0.323088020086288f, 0.118653707206249f, - 0.323380589485168f, - 0.118901848793030f, 0.323672980070114f, 0.119150213897228f, - 0.323965191841125f, - 0.119398809969425f, 0.324257194995880f, 0.119647622108459f, - 0.324549019336700f, - 0.119896657764912f, 0.324840664863586f, 0.120145916938782f, - 0.325132101774216f, - 0.120395407080650f, 0.325423330068588f, 0.120645113289356f, - 0.325714409351349f, - 0.120895043015480f, 0.326005280017853f, 0.121145196259022f, - 0.326295942068100f, - 0.121395580470562f, 0.326586425304413f, 0.121646173298359f, - 0.326876699924469f, - 0.121896997094154f, 0.327166795730591f, 0.122148044407368f, - 0.327456712722778f, - 0.122399315237999f, 0.327746421098709f, 0.122650802135468f, - 0.328035950660706f, - 0.122902512550354f, 0.328325271606445f, 0.123154446482658f, - 0.328614413738251f, - 0.123406603932381f, 0.328903347253799f, 0.123658977448940f, - 0.329192101955414f, - 0.123911574482918f, 0.329480648040771f, 0.124164395034313f, - 0.329769015312195f, - 0.124417431652546f, 0.330057173967361f, 0.124670691788197f, - 0.330345153808594f, - 0.124924175441265f, 0.330632925033569f, 0.125177875161171f, - 0.330920487642288f, - 0.125431805849075f, 0.331207901239395f, 0.125685945153236f, - 0.331495076417923f, - 0.125940307974815f, 0.331782072782516f, 0.126194894313812f, - 0.332068890333176f, - 0.126449704170227f, 0.332355499267578f, 0.126704722642899f, - 0.332641899585724f, - 0.126959964632988f, 0.332928121089935f, 0.127215430140495f, - 0.333214133977890f, - 0.127471104264259f, 0.333499968051910f, 0.127727001905441f, - 0.333785593509674f, - 0.127983123064041f, 0.334071010351181f, 0.128239467740059f, - 0.334356248378754f, - 0.128496021032333f, 0.334641307592392f, 0.128752797842026f, - 0.334926128387451f, - 0.129009798169136f, 0.335210770368576f, 0.129267007112503f, - 0.335495233535767f, - 0.129524439573288f, 0.335779488086700f, 0.129782080650330f, - 0.336063534021378f, - 0.130039945244789f, 0.336347371339798f, 0.130298033356667f, - 0.336631029844284f, - 0.130556344985962f, 0.336914509534836f, 0.130814850330353f, - 0.337197750806808f, - 0.131073594093323f, 0.337480813264847f, 0.131332546472549f, - 0.337763696908951f, - 0.131591722369194f, 0.338046342134476f, 0.131851106882095f, - 0.338328808546066f, - 0.132110700011253f, 0.338611096143723f, 0.132370531558990f, - 0.338893145322800f, - 0.132630556821823f, 0.339175015687943f, 0.132890805602074f, - 0.339456677436829f, - 0.133151277899742f, 0.339738160371780f, 0.133411958813667f, - 0.340019434690475f, - 0.133672863245010f, 0.340300500392914f, 0.133933976292610f, - 0.340581357479095f, - 0.134195312857628f, 0.340862035751343f, 0.134456858038902f, - 0.341142505407333f, - 0.134718611836433f, 0.341422766447067f, 0.134980589151382f, - 0.341702848672867f, - 0.135242775082588f, 0.341982692480087f, 0.135505184531212f, - 0.342262357473373f, - 0.135767802596092f, 0.342541843652725f, 0.136030644178391f, - 0.342821091413498f, - 0.136293679475784f, 0.343100160360336f, 0.136556953191757f, - 0.343379020690918f, - 0.136820420622826f, 0.343657672405243f, 0.137084111571312f, - 0.343936115503311f, - 0.137348011136055f, 0.344214379787445f, 0.137612134218216f, - 0.344492435455322f, - 0.137876465916634f, 0.344770282506943f, 0.138141006231308f, - 0.345047920942307f, - 0.138405755162239f, 0.345325350761414f, 0.138670727610588f, - 0.345602601766586f, - 0.138935908675194f, 0.345879614353180f, 0.139201298356056f, - 0.346156448125839f, - 0.139466896653175f, 0.346433073282242f, 0.139732718467712f, - 0.346709519624710f, - 0.139998748898506f, 0.346985727548599f, 0.140264987945557f, - 0.347261756658554f, - 0.140531435608864f, 0.347537547349930f, 0.140798106789589f, - 0.347813159227371f, - 0.141064971685410f, 0.348088562488556f, 0.141332060098648f, - 0.348363757133484f, - 0.141599357128143f, 0.348638743162155f, 0.141866862773895f, - 0.348913550376892f, - 0.142134591937065f, 0.349188119173050f, 0.142402514815331f, - 0.349462509155273f, - 0.142670661211014f, 0.349736660718918f, 0.142939001321793f, - 0.350010633468628f, - 0.143207564949989f, 0.350284397602081f, 0.143476337194443f, - 0.350557953119278f, - 0.143745318055153f, 0.350831300020218f, 0.144014507532120f, - 0.351104438304901f, - 0.144283905625343f, 0.351377367973328f, 0.144553512334824f, - 0.351650089025497f, - 0.144823327660561f, 0.351922631263733f, 0.145093351602554f, - 0.352194935083389f, - 0.145363584160805f, 0.352467030286789f, 0.145634025335312f, - 0.352738946676254f, - 0.145904675126076f, 0.353010624647141f, 0.146175548434258f, - 0.353282123804092f, - 0.146446615457535f, 0.353553384542465f, 0.146717891097069f, - 0.353824466466904f, - 0.146989375352860f, 0.354095309972763f, 0.147261068224907f, - 0.354365974664688f, - 0.147532954812050f, 0.354636400938034f, 0.147805064916611f, - 0.354906648397446f, - 0.148077383637428f, 0.355176687240601f, 0.148349896073341f, - 0.355446487665176f, - 0.148622632026672f, 0.355716109275818f, 0.148895561695099f, - 0.355985492467880f, - 0.149168699979782f, 0.356254696846008f, 0.149442046880722f, - 0.356523662805557f, - 0.149715602397919f, 0.356792420148849f, 0.149989366531372f, - 0.357060998678207f, - 0.150263324379921f, 0.357329338788986f, 0.150537505745888f, - 0.357597470283508f, - 0.150811880826950f, 0.357865422964096f, 0.151086464524269f, - 0.358133137226105f, - 0.151361241936684f, 0.358400642871857f, 0.151636242866516f, - 0.358667939901352f, - 0.151911437511444f, 0.358935028314590f, 0.152186840772629f, - 0.359201908111572f, - 0.152462437748909f, 0.359468549489975f, 0.152738258242607f, - 0.359735012054443f, - 0.153014272451401f, 0.360001266002655f, 0.153290495276451f, - 0.360267281532288f, - 0.153566911816597f, 0.360533088445663f, 0.153843536973000f, - 0.360798716545105f, - 0.154120370745659f, 0.361064106225967f, 0.154397398233414f, - 0.361329287290573f, - 0.154674649238586f, 0.361594229936600f, 0.154952079057693f, - 0.361858993768692f, - 0.155229732394218f, 0.362123548984528f, 0.155507579445839f, - 0.362387865781784f, - 0.155785620212555f, 0.362651973962784f, 0.156063869595528f, - 0.362915903329849f, - 0.156342327594757f, 0.363179564476013f, 0.156620979309082f, - 0.363443046808243f, - 0.156899839639664f, 0.363706320524216f, 0.157178908586502f, - 0.363969355821610f, - 0.157458171248436f, 0.364232182502747f, 0.157737627625465f, - 0.364494800567627f, - 0.158017292618752f, 0.364757210016251f, 0.158297166228294f, - 0.365019410848618f, - 0.158577233552933f, 0.365281373262405f, 0.158857494592667f, - 0.365543156862259f, - 0.159137964248657f, 0.365804702043533f, 0.159418627619743f, - 0.366066008806229f, - 0.159699499607086f, 0.366327136754990f, 0.159980565309525f, - 0.366588026285172f, - 0.160261839628220f, 0.366848707199097f, 0.160543307662010f, - 0.367109179496765f, - 0.160824984312058f, 0.367369443178177f, 0.161106839776039f, - 0.367629468441010f, - 0.161388918757439f, 0.367889285087585f, 0.161671176552773f, - 0.368148893117905f, - 0.161953642964363f, 0.368408292531967f, 0.162236317992210f, - 0.368667453527451f, - 0.162519171833992f, 0.368926405906677f, 0.162802234292030f, - 0.369185149669647f, - 0.163085505366325f, 0.369443655014038f, 0.163368955254555f, - 0.369701951742172f, - 0.163652613759041f, 0.369960039854050f, 0.163936465978622f, - 0.370217919349670f, - 0.164220526814461f, 0.370475560426712f, 0.164504766464233f, - 0.370732992887497f, - 0.164789214730263f, 0.370990216732025f, 0.165073871612549f, - 0.371247202157974f, - 0.165358707308769f, 0.371503978967667f, 0.165643751621246f, - 0.371760547161102f, - 0.165928974747658f, 0.372016876935959f, 0.166214406490326f, - 0.372272998094559f, - 0.166500031948090f, 0.372528880834579f, 0.166785866022110f, - 0.372784584760666f, - 0.167071878910065f, 0.373040050268173f, 0.167358100414276f, - 0.373295277357101f, - 0.167644515633583f, 0.373550295829773f, 0.167931124567986f, - 0.373805105686188f, - 0.168217927217484f, 0.374059677124023f, 0.168504923582077f, - 0.374314039945602f, - 0.168792113661766f, 0.374568194150925f, 0.169079497456551f, - 0.374822109937668f, - 0.169367074966431f, 0.375075817108154f, 0.169654861092567f, - 0.375329315662384f, - 0.169942826032639f, 0.375582575798035f, 0.170230999588966f, - 0.375835597515106f, - 0.170519351959229f, 0.376088410615921f, 0.170807912945747f, - 0.376341015100479f, - 0.171096652746201f, 0.376593410968781f, 0.171385586261749f, - 0.376845568418503f, - 0.171674728393555f, 0.377097487449646f, 0.171964049339294f, - 0.377349197864532f, - 0.172253578901291f, 0.377600699663162f, 0.172543287277222f, - 0.377851963043213f, - 0.172833189368248f, 0.378102988004684f, 0.173123285174370f, - 0.378353834152222f, - 0.173413574695587f, 0.378604412078857f, 0.173704057931900f, - 0.378854811191559f, - 0.173994734883308f, 0.379104942083359f, 0.174285605549812f, - 0.379354894161224f, - 0.174576655030251f, 0.379604607820511f, 0.174867913126946f, - 0.379854083061218f, - 0.175159350037575f, 0.380103349685669f, 0.175450980663300f, - 0.380352377891541f, - 0.175742805004120f, 0.380601197481155f, 0.176034808158875f, - 0.380849778652191f, - 0.176327019929886f, 0.381098151206970f, 0.176619410514832f, - 0.381346285343170f, - 0.176911994814873f, 0.381594210863113f, 0.177204772830009f, - 0.381841897964478f, - 0.177497729659081f, 0.382089376449585f, 0.177790880203247f, - 0.382336616516113f, - 0.178084224462509f, 0.382583618164063f, 0.178377762436867f, - 0.382830440998077f, - 0.178671479225159f, 0.383076995611191f, 0.178965389728546f, - 0.383323341608047f, - 0.179259493947029f, 0.383569449186325f, 0.179553776979446f, - 0.383815348148346f, - 0.179848253726959f, 0.384061008691788f, 0.180142924189568f, - 0.384306460618973f, - 0.180437773466110f, 0.384551674127579f, 0.180732816457748f, - 0.384796649217606f, - 0.181028053164482f, 0.385041415691376f, 0.181323468685150f, - 0.385285943746567f, - 0.181619063019753f, 0.385530263185501f, 0.181914865970612f, - 0.385774344205856f, - 0.182210832834244f, 0.386018186807632f, 0.182507008314133f, - 0.386261820793152f, - 0.182803362607956f, 0.386505216360092f, 0.183099895715714f, - 0.386748403310776f, - 0.183396622538567f, 0.386991351842880f, 0.183693528175354f, - 0.387234061956406f, - 0.183990627527237f, 0.387476563453674f, 0.184287920594215f, - 0.387718826532364f, - 0.184585392475128f, 0.387960851192474f, 0.184883043169975f, - 0.388202667236328f, - 0.185180887579918f, 0.388444244861603f, 0.185478910803795f, - 0.388685584068298f, - 0.185777112841606f, 0.388926714658737f, 0.186075508594513f, - 0.389167606830597f, - 0.186374098062515f, 0.389408260583878f, 0.186672851443291f, - 0.389648675918579f, - 0.186971798539162f, 0.389888882637024f, 0.187270939350128f, - 0.390128880739212f, - 0.187570258975029f, 0.390368610620499f, 0.187869757413864f, - 0.390608131885529f, - 0.188169434666634f, 0.390847414731979f, 0.188469305634499f, - 0.391086459159851f, - 0.188769355416298f, 0.391325294971466f, 0.189069598913193f, - 0.391563892364502f, - 0.189370006322861f, 0.391802251338959f, 0.189670607447624f, - 0.392040401697159f, - 0.189971387386322f, 0.392278283834457f, 0.190272361040115f, - 0.392515957355499f, - 0.190573498606682f, 0.392753422260284f, 0.190874829888344f, - 0.392990618944168f, - 0.191176339983940f, 0.393227607011795f, 0.191478043794632f, - 0.393464356660843f, - 0.191779911518097f, 0.393700867891312f, 0.192081972956657f, - 0.393937170505524f, - 0.192384198307991f, 0.394173204898834f, 0.192686617374420f, - 0.394409030675888f, - 0.192989215254784f, 0.394644618034363f, 0.193292006850243f, - 0.394879996776581f, - 0.193594962358475f, 0.395115107297897f, 0.193898096680641f, - 0.395350009202957f, - 0.194201424717903f, 0.395584672689438f, 0.194504916667938f, - 0.395819097757339f, - 0.194808602333069f, 0.396053284406662f, 0.195112451910973f, - 0.396287262439728f, - 0.195416495203972f, 0.396520972251892f, 0.195720717310905f, - 0.396754473447800f, - 0.196025103330612f, 0.396987736225128f, 0.196329683065414f, - 0.397220760583878f, - 0.196634441614151f, 0.397453576326370f, 0.196939364075661f, - 0.397686123847961f, - 0.197244480252266f, 0.397918462753296f, 0.197549775242805f, - 0.398150533437729f, - 0.197855234146118f, 0.398382395505905f, 0.198160871863365f, - 0.398614019155502f, - 0.198466703295708f, 0.398845434188843f, 0.198772698640823f, - 0.399076581001282f, - 0.199078872799873f, 0.399307489395142f, 0.199385225772858f, - 0.399538189172745f, - 0.199691757559776f, 0.399768620729446f, 0.199998468160629f, - 0.399998843669891f, - 0.200305357575417f, 0.400228828191757f, 0.200612410902977f, - 0.400458574295044f, - 0.200919643044472f, 0.400688081979752f, 0.201227053999901f, - 0.400917351245880f, - 0.201534643769264f, 0.401146411895752f, 0.201842412352562f, - 0.401375204324722f, - 0.202150344848633f, 0.401603758335114f, 0.202458456158638f, - 0.401832103729248f, - 0.202766746282578f, 0.402060180902481f, 0.203075215220451f, - 0.402288049459457f, - 0.203383848071098f, 0.402515679597855f, 0.203692659735680f, - 0.402743041515350f, - 0.204001650214195f, 0.402970194816589f, 0.204310819506645f, - 0.403197109699249f, - 0.204620152711868f, 0.403423786163330f, 0.204929664731026f, - 0.403650224208832f, - 0.205239340662956f, 0.403876423835754f, 0.205549195408821f, - 0.404102355241776f, - 0.205859228968620f, 0.404328078031540f, 0.206169426441193f, - 0.404553562402725f, - 0.206479802727699f, 0.404778808355331f, 0.206790357828140f, - 0.405003815889359f, - 0.207101076841354f, 0.405228585004807f, 0.207411959767342f, - 0.405453115701675f, - 0.207723021507263f, 0.405677437782288f, 0.208034262061119f, - 0.405901491641998f, - 0.208345666527748f, 0.406125307083130f, 0.208657249808311f, - 0.406348884105682f, - 0.208969011902809f, 0.406572192907333f, 0.209280923008919f, - 0.406795293092728f, - 0.209593027830124f, 0.407018154859543f, 0.209905281662941f, - 0.407240778207779f, - 0.210217714309692f, 0.407463163137436f, 0.210530325770378f, - 0.407685309648514f, - 0.210843101143837f, 0.407907217741013f, 0.211156040430069f, - 0.408128857612610f, - 0.211469158530235f, 0.408350288867950f, 0.211782455444336f, - 0.408571451902390f, - 0.212095901370049f, 0.408792406320572f, 0.212409526109695f, - 0.409013092517853f, - 0.212723329663277f, 0.409233570098877f, 0.213037282228470f, - 0.409453779459000f, - 0.213351413607597f, 0.409673750400543f, 0.213665723800659f, - 0.409893482923508f, - 0.213980183005333f, 0.410112977027893f, 0.214294821023941f, - 0.410332232713699f, - 0.214609622955322f, 0.410551249980927f, 0.214924603700638f, - 0.410770028829575f, - 0.215239733457565f, 0.410988569259644f, 0.215555042028427f, - 0.411206841468811f, - 0.215870529413223f, 0.411424905061722f, 0.216186165809631f, - 0.411642700433731f, - 0.216501981019974f, 0.411860257387161f, 0.216817945241928f, - 0.412077575922012f, - 0.217134088277817f, 0.412294656038284f, 0.217450410127640f, - 0.412511497735977f, - 0.217766880989075f, 0.412728071212769f, 0.218083515763283f, - 0.412944436073303f, - 0.218400329351425f, 0.413160532712936f, 0.218717306852341f, - 0.413376390933990f, - 0.219034433364868f, 0.413592010736465f, 0.219351738691330f, - 0.413807392120361f, - 0.219669207930565f, 0.414022535085678f, 0.219986841082573f, - 0.414237409830093f, - 0.220304638147354f, 0.414452046155930f, 0.220622614026070f, - 0.414666473865509f, - 0.220940738916397f, 0.414880603551865f, 0.221259027719498f, - 0.415094524621964f, - 0.221577480435371f, 0.415308207273483f, 0.221896097064018f, - 0.415521621704102f, - 0.222214877605438f, 0.415734797716141f, 0.222533836960793f, - 0.415947735309601f, - 0.222852945327759f, 0.416160434484482f, 0.223172217607498f, - 0.416372895240784f, - 0.223491653800011f, 0.416585087776184f, 0.223811239004135f, - 0.416797041893005f, - 0.224131003022194f, 0.417008757591248f, 0.224450930953026f, - 0.417220205068588f, - 0.224771007895470f, 0.417431443929672f, 0.225091263651848f, - 0.417642414569855f, - 0.225411668419838f, 0.417853146791458f, 0.225732237100601f, - 0.418063640594482f, - 0.226052969694138f, 0.418273866176605f, 0.226373866200447f, - 0.418483853340149f, - 0.226694911718369f, 0.418693602085114f, 0.227016136050224f, - 0.418903112411499f, - 0.227337509393692f, 0.419112354516983f, 0.227659046649933f, - 0.419321358203888f, - 0.227980732917786f, 0.419530123472214f, 0.228302597999573f, - 0.419738620519638f, - 0.228624612092972f, 0.419946908950806f, 0.228946775197983f, - 0.420154929161072f, - 0.229269117116928f, 0.420362681150436f, 0.229591608047485f, - 0.420570224523544f, - 0.229914262890816f, 0.420777499675751f, 0.230237081646919f, - 0.420984506607056f, - 0.230560049414635f, 0.421191304922104f, 0.230883181095123f, - 0.421397835016251f, - 0.231206461787224f, 0.421604126691818f, 0.231529906392097f, - 0.421810150146484f, - 0.231853514909744f, 0.422015935182571f, 0.232177272439003f, - 0.422221481800079f, - 0.232501193881035f, 0.422426789999008f, 0.232825264334679f, - 0.422631829977036f, - 0.233149498701096f, 0.422836631536484f, 0.233473882079124f, - 0.423041164875031f, - 0.233798429369926f, 0.423245459794998f, 0.234123140573502f, - 0.423449516296387f, - 0.234448000788689f, 0.423653304576874f, 0.234773010015488f, - 0.423856884241104f, - 0.235098183155060f, 0.424060165882111f, 0.235423520207405f, - 0.424263238906860f, - 0.235749006271362f, 0.424466013908386f, 0.236074641346931f, - 0.424668580293655f, - 0.236400425434113f, 0.424870878458023f, 0.236726388335228f, - 0.425072938203812f, - 0.237052485346794f, 0.425274729728699f, 0.237378746271133f, - 0.425476282835007f, - 0.237705156207085f, 0.425677597522736f, 0.238031730055809f, - 0.425878643989563f, - 0.238358452916145f, 0.426079452037811f, 0.238685324788094f, - 0.426279991865158f, - 0.239012360572815f, 0.426480293273926f, 0.239339530467987f, - 0.426680356264114f, - 0.239666879177094f, 0.426880151033401f, 0.239994361996651f, - 0.427079707384110f, - 0.240322008728981f, 0.427278995513916f, 0.240649804472923f, - 0.427478045225143f, - 0.240977749228477f, 0.427676826715469f, 0.241305842995644f, - 0.427875369787216f, - 0.241634100675583f, 0.428073674440384f, 0.241962507367134f, - 0.428271710872650f, - 0.242291063070297f, 0.428469479084015f, 0.242619767785072f, - 0.428667008876801f, - 0.242948621511459f, 0.428864300251007f, 0.243277639150620f, - 0.429061323404312f, - 0.243606805801392f, 0.429258108139038f, 0.243936106562614f, - 0.429454624652863f, - 0.244265571236610f, 0.429650902748108f, 0.244595184922218f, - 0.429846942424774f, - 0.244924947619438f, 0.430042684078217f, 0.245254859328270f, - 0.430238217115402f, - 0.245584934949875f, 0.430433481931686f, 0.245915144681931f, - 0.430628478527069f, - 0.246245503425598f, 0.430823236703873f, 0.246576011180878f, - 0.431017726659775f, - 0.246906682848930f, 0.431211978197098f, 0.247237488627434f, - 0.431405961513519f, - 0.247568443417549f, 0.431599706411362f, 0.247899547219276f, - 0.431793183088303f, - 0.248230814933777f, 0.431986421346664f, 0.248562216758728f, - 0.432179391384125f, - 0.248893767595291f, 0.432372123003006f, 0.249225467443466f, - 0.432564586400986f, - 0.249557301402092f, 0.432756811380386f, 0.249889299273491f, - 0.432948768138886f, - 0.250221431255341f, 0.433140486478806f, 0.250553727149963f, - 0.433331936597824f, - 0.250886172056198f, 0.433523118495941f, 0.251218736171722f, - 0.433714061975479f, - 0.251551479101181f, 0.433904737234116f, 0.251884341239929f, - 0.434095174074173f, - 0.252217382192612f, 0.434285342693329f, 0.252550542354584f, - 0.434475272893906f, - 0.252883851528168f, 0.434664934873581f, 0.253217309713364f, - 0.434854328632355f, - 0.253550916910172f, 0.435043483972549f, 0.253884643316269f, - 0.435232400894165f, - 0.254218548536301f, 0.435421019792557f, 0.254552572965622f, - 0.435609430074692f, - 0.254886746406555f, 0.435797542333603f, 0.255221068859100f, - 0.435985416173935f, - 0.255555540323257f, 0.436173021793365f, 0.255890160799026f, - 0.436360388994217f, - 0.256224930286407f, 0.436547487974167f, 0.256559818983078f, - 0.436734348535538f, - 0.256894856691360f, 0.436920911073685f, 0.257230043411255f, - 0.437107264995575f, - 0.257565379142761f, 0.437293320894241f, 0.257900834083557f, - 0.437479138374329f, - 0.258236467838287f, 0.437664687633514f, 0.258572220802307f, - 0.437849998474121f, - 0.258908122777939f, 0.438035041093826f, 0.259244143962860f, - 0.438219845294952f, - 0.259580343961716f, 0.438404351472855f, 0.259916663169861f, - 0.438588619232178f, - 0.260253131389618f, 0.438772648572922f, 0.260589718818665f, - 0.438956409692764f, - 0.260926485061646f, 0.439139902591705f, 0.261263370513916f, - 0.439323127269745f, - 0.261600375175476f, 0.439506113529205f, 0.261937558650970f, - 0.439688831567764f, - 0.262274861335754f, 0.439871311187744f, 0.262612313032150f, - 0.440053492784500f, - 0.262949883937836f, 0.440235435962677f, 0.263287603855133f, - 0.440417140722275f, - 0.263625472784042f, 0.440598547458649f, 0.263963490724564f, - 0.440779715776443f, - 0.264301627874374f, 0.440960645675659f, 0.264639914035797f, - 0.441141277551651f, - 0.264978319406509f, 0.441321671009064f, 0.265316903591156f, - 0.441501796245575f, - 0.265655577182770f, 0.441681683063507f, 0.265994429588318f, - 0.441861271858215f, - 0.266333401203156f, 0.442040622234344f, 0.266672492027283f, - 0.442219734191895f, - 0.267011761665344f, 0.442398548126221f, 0.267351150512695f, - 0.442577123641968f, - 0.267690658569336f, 0.442755430936813f, 0.268030315637589f, - 0.442933470010757f, - 0.268370121717453f, 0.443111270666122f, 0.268710047006607f, - 0.443288803100586f, - 0.269050091505051f, 0.443466067314148f, 0.269390314817429f, - 0.443643063306808f, - 0.269730657339096f, 0.443819820880890f, 0.270071119070053f, - 0.443996280431747f, - 0.270411729812622f, 0.444172531366348f, 0.270752459764481f, - 0.444348484277725f, - 0.271093338727951f, 0.444524168968201f, 0.271434366703033f, - 0.444699615240097f, - 0.271775513887405f, 0.444874793291092f, 0.272116780281067f, - 0.445049703121185f, - 0.272458195686340f, 0.445224374532700f, 0.272799760103226f, - 0.445398747920990f, - 0.273141443729401f, 0.445572882890701f, 0.273483246564865f, - 0.445746749639511f, - 0.273825198411942f, 0.445920348167419f, 0.274167299270630f, - 0.446093708276749f, - 0.274509519338608f, 0.446266770362854f, 0.274851858615875f, - 0.446439594030380f, - 0.275194346904755f, 0.446612149477005f, 0.275536954402924f, - 0.446784436702728f, - 0.275879681110382f, 0.446956485509872f, 0.276222556829453f, - 0.447128236293793f, - 0.276565581560135f, 0.447299748659134f, 0.276908725500107f, - 0.447470992803574f, - 0.277251988649368f, 0.447641968727112f, 0.277595400810242f, - 0.447812676429749f, - 0.277938932180405f, 0.447983115911484f, 0.278282582759857f, - 0.448153316974640f, - 0.278626382350922f, 0.448323249816895f, 0.278970301151276f, - 0.448492884635925f, - 0.279314368963242f, 0.448662281036377f, 0.279658555984497f, - 0.448831409215927f, - 0.280002862215042f, 0.449000298976898f, 0.280347317457199f, - 0.449168890714645f, - 0.280691891908646f, 0.449337244033813f, 0.281036585569382f, - 0.449505299329758f, - 0.281381398439407f, 0.449673116207123f, 0.281726360321045f, - 0.449840664863586f, - 0.282071471214294f, 0.450007945299149f, 0.282416671514511f, - 0.450174957513809f, - 0.282762020826340f, 0.450341701507568f, 0.283107489347458f, - 0.450508207082748f, - 0.283453077077866f, 0.450674414634705f, 0.283798813819885f, - 0.450840383768082f, - 0.284144669771194f, 0.451006084680557f, 0.284490644931793f, - 0.451171487569809f, - 0.284836769104004f, 0.451336652040482f, 0.285182982683182f, - 0.451501548290253f, - 0.285529345273972f, 0.451666176319122f, 0.285875827074051f, - 0.451830536127090f, - 0.286222457885742f, 0.451994657516479f, 0.286569178104401f, - 0.452158480882645f, - 0.286916047334671f, 0.452322036027908f, 0.287263035774231f, - 0.452485352754593f, - 0.287610173225403f, 0.452648371458054f, 0.287957400083542f, - 0.452811151742935f, - 0.288304775953293f, 0.452973634004593f, 0.288652241230011f, - 0.453135877847672f, - 0.288999855518341f, 0.453297853469849f, 0.289347589015961f, - 0.453459560871124f, - 0.289695471525192f, 0.453621000051498f, 0.290043443441391f, - 0.453782171010971f, - 0.290391564369202f, 0.453943043947220f, 0.290739774703979f, - 0.454103678464890f, - 0.291088134050369f, 0.454264044761658f, 0.291436612606049f, - 0.454424172639847f, - 0.291785210371017f, 0.454584002494812f, 0.292133957147598f, - 0.454743564128876f, - 0.292482793331146f, 0.454902857542038f, 0.292831748723984f, - 0.455061882734299f, - 0.293180853128433f, 0.455220639705658f, 0.293530046939850f, - 0.455379128456116f, - 0.293879389762878f, 0.455537378787994f, 0.294228851795197f, - 0.455695331096649f, - 0.294578403234482f, 0.455853015184402f, 0.294928103685379f, - 0.456010431051254f, - 0.295277923345566f, 0.456167578697205f, 0.295627862215042f, - 0.456324487924576f, - 0.295977920293808f, 0.456481099128723f, 0.296328097581863f, - 0.456637442111969f, - 0.296678394079208f, 0.456793516874313f, 0.297028809785843f, - 0.456949323415756f, - 0.297379344701767f, 0.457104891538620f, 0.297729998826981f, - 0.457260161638260f, - 0.298080772161484f, 0.457415163516998f, 0.298431664705276f, - 0.457569897174835f, - 0.298782676458359f, 0.457724362611771f, 0.299133807420731f, - 0.457878559827805f, - 0.299485057592392f, 0.458032488822937f, 0.299836426973343f, - 0.458186149597168f, - 0.300187885761261f, 0.458339542150497f, 0.300539493560791f, - 0.458492636680603f, - 0.300891220569611f, 0.458645492792130f, 0.301243066787720f, - 0.458798080682755f, - 0.301595002412796f, 0.458950400352478f, 0.301947087049484f, - 0.459102421998978f, - 0.302299261093140f, 0.459254205226898f, 0.302651554346085f, - 0.459405690431595f, - 0.303003966808319f, 0.459556937217712f, 0.303356528282166f, - 0.459707885980606f, - 0.303709149360657f, 0.459858566522598f, 0.304061919450760f, - 0.460008978843689f, - 0.304414808750153f, 0.460159152746201f, 0.304767817258835f, - 0.460309028625488f, - 0.305120915174484f, 0.460458606481552f, 0.305474132299423f, - 0.460607945919037f, - 0.305827468633652f, 0.460757017135620f, 0.306180924177170f, - 0.460905820131302f, - 0.306534498929977f, 0.461054325103760f, 0.306888192892075f, - 0.461202591657639f, - 0.307241976261139f, 0.461350560188293f, 0.307595878839493f, - 0.461498260498047f, - 0.307949900627136f, 0.461645722389221f, 0.308304041624069f, - 0.461792886257172f, - 0.308658272027969f, 0.461939752101898f, 0.309012651443481f, - 0.462086379528046f, - 0.309367120265961f, 0.462232738733292f, 0.309721708297729f, - 0.462378799915314f, - 0.310076385736465f, 0.462524622678757f, 0.310431212186813f, - 0.462670147418976f, - 0.310786128044128f, 0.462815403938293f, 0.311141163110733f, - 0.462960392236710f, - 0.311496287584305f, 0.463105112314224f, 0.311851561069489f, - 0.463249564170837f, - 0.312206923961639f, 0.463393747806549f, 0.312562376260757f, - 0.463537633419037f, - 0.312917977571487f, 0.463681250810623f, 0.313273668289185f, - 0.463824629783630f, - 0.313629478216171f, 0.463967710733414f, 0.313985377550125f, - 0.464110493659973f, - 0.314341396093369f, 0.464253038167953f, 0.314697533845901f, - 0.464395314455032f, - 0.315053790807724f, 0.464537292718887f, 0.315410137176514f, - 0.464679002761841f, - 0.315766572952271f, 0.464820444583893f, 0.316123157739639f, - 0.464961618185043f, - 0.316479831933975f, 0.465102523565292f, 0.316836595535278f, - 0.465243130922318f, - 0.317193508148193f, 0.465383470058441f, 0.317550510168076f, - 0.465523540973663f, - 0.317907601594925f, 0.465663343667984f, 0.318264812231064f, - 0.465802878141403f, - 0.318622142076492f, 0.465942144393921f, 0.318979561328888f, - 0.466081112623215f, - 0.319337099790573f, 0.466219812631607f, 0.319694727659225f, - 0.466358244419098f, - 0.320052474737167f, 0.466496407985687f, 0.320410341024399f, - 0.466634273529053f, - 0.320768296718597f, 0.466771900653839f, 0.321126341819763f, - 0.466909229755402f, - 0.321484506130219f, 0.467046260833740f, 0.321842789649963f, - 0.467183053493500f, - 0.322201162576675f, 0.467319577932358f, 0.322559654712677f, - 0.467455804347992f, - 0.322918236255646f, 0.467591762542725f, 0.323276937007904f, - 0.467727422714233f, - 0.323635727167130f, 0.467862844467163f, 0.323994606733322f, - 0.467997968196869f, - 0.324353635311127f, 0.468132823705673f, 0.324712723493576f, - 0.468267410993576f, - 0.325071930885315f, 0.468401730060577f, 0.325431257486343f, - 0.468535751104355f, - 0.325790673494339f, 0.468669503927231f, 0.326150178909302f, - 0.468802988529205f, - 0.326509803533554f, 0.468936175107956f, 0.326869517564774f, - 0.469069123268127f, - 0.327229350805283f, 0.469201773405075f, 0.327589273452759f, - 0.469334155321121f, - 0.327949285507202f, 0.469466239213943f, 0.328309416770935f, - 0.469598054885864f, - 0.328669637441635f, 0.469729602336884f, 0.329029977321625f, - 0.469860881567001f, - 0.329390406608582f, 0.469991862773895f, 0.329750925302505f, - 0.470122605562210f, - 0.330111563205719f, 0.470253020524979f, 0.330472290515900f, - 0.470383197069168f, - 0.330833107233047f, 0.470513075590134f, 0.331194043159485f, - 0.470642685890198f, - 0.331555068492889f, 0.470772027969360f, 0.331916213035584f, - 0.470901101827621f, - 0.332277417182922f, 0.471029877662659f, 0.332638740539551f, - 0.471158385276794f, - 0.333000183105469f, 0.471286594867706f, 0.333361685276031f, - 0.471414536237717f, - 0.333723306655884f, 0.471542209386826f, 0.334085017442703f, - 0.471669614315033f, - 0.334446847438812f, 0.471796721220016f, 0.334808766841888f, - 0.471923559904099f, - 0.335170775651932f, 0.472050130367279f, 0.335532873868942f, - 0.472176402807236f, - 0.335895091295242f, 0.472302407026291f, 0.336257368326187f, - 0.472428143024445f, - 0.336619764566422f, 0.472553610801697f, 0.336982280015945f, - 0.472678780555725f, - 0.337344855070114f, 0.472803652286530f, 0.337707549333572f, - 0.472928285598755f, - 0.338070303201675f, 0.473052620887756f, 0.338433176279068f, - 0.473176687955856f, - 0.338796168565750f, 0.473300457000732f, 0.339159220457077f, - 0.473423957824707f, - 0.339522391557693f, 0.473547190427780f, 0.339885622262955f, - 0.473670125007629f, - 0.340248972177505f, 0.473792791366577f, 0.340612411499023f, - 0.473915189504623f, - 0.340975970029831f, 0.474037289619446f, 0.341339588165283f, - 0.474159121513367f, - 0.341703325510025f, 0.474280685186386f, 0.342067122459412f, - 0.474401950836182f, - 0.342431038618088f, 0.474522948265076f, 0.342795044183731f, - 0.474643647670746f, - 0.343159139156342f, 0.474764078855515f, 0.343523323535919f, - 0.474884241819382f, - 0.343887597322464f, 0.475004136562347f, 0.344251960515976f, - 0.475123733282089f, - 0.344616413116455f, 0.475243031978607f, 0.344980984926224f, - 0.475362062454224f, - 0.345345616340637f, 0.475480824708939f, 0.345710366964340f, - 0.475599318742752f, - 0.346075177192688f, 0.475717514753342f, 0.346440106630325f, - 0.475835442543030f, - 0.346805095672607f, 0.475953072309494f, 0.347170203924179f, - 0.476070433855057f, - 0.347535371780396f, 0.476187497377396f, 0.347900658845901f, - 0.476304292678833f, - 0.348266035318375f, 0.476420819759369f, 0.348631471395493f, - 0.476537048816681f, - 0.348997026681900f, 0.476653009653091f, 0.349362671375275f, - 0.476768702268600f, - 0.349728375673294f, 0.476884096860886f, 0.350094199180603f, - 0.476999223232269f, - 0.350460082292557f, 0.477114051580429f, 0.350826084613800f, - 0.477228611707687f, - 0.351192146539688f, 0.477342873811722f, 0.351558297872543f, - 0.477456867694855f, - 0.351924568414688f, 0.477570593357086f, 0.352290898561478f, - 0.477684020996094f, - 0.352657318115234f, 0.477797180414200f, 0.353023827075958f, - 0.477910041809082f, - 0.353390425443649f, 0.478022634983063f, 0.353757113218308f, - 0.478134930133820f, - 0.354123860597610f, 0.478246957063675f, 0.354490727186203f, - 0.478358715772629f, - 0.354857653379440f, 0.478470176458359f, 0.355224698781967f, - 0.478581339120865f, - 0.355591803789139f, 0.478692263364792f, 0.355958998203278f, - 0.478802859783173f, - 0.356326282024384f, 0.478913217782974f, 0.356693625450134f, - 0.479023247957230f, - 0.357061088085175f, 0.479133039712906f, 0.357428610324860f, - 0.479242533445358f, - 0.357796221971512f, 0.479351729154587f, 0.358163923025131f, - 0.479460656642914f, - 0.358531713485718f, 0.479569315910339f, 0.358899593353271f, - 0.479677677154541f, - 0.359267532825470f, 0.479785770177841f, 0.359635561704636f, - 0.479893565177917f, - 0.360003679990768f, 0.480001062154770f, 0.360371887683868f, - 0.480108320713043f, - 0.360740154981613f, 0.480215251445770f, 0.361108511686325f, - 0.480321943759918f, - 0.361476957798004f, 0.480428308248520f, 0.361845493316650f, - 0.480534434318542f, - 0.362214088439941f, 0.480640232563019f, 0.362582772970200f, - 0.480745792388916f, - 0.362951546907425f, 0.480851024389267f, 0.363320380449295f, - 0.480956017971039f, - 0.363689333200455f, 0.481060713529587f, 0.364058345556259f, - 0.481165111064911f, - 0.364427417516708f, 0.481269240379334f, 0.364796578884125f, - 0.481373071670532f, - 0.365165829658508f, 0.481476634740829f, 0.365535169839859f, - 0.481579899787903f, - 0.365904569625854f, 0.481682896614075f, 0.366274058818817f, - 0.481785595417023f, - 0.366643607616425f, 0.481888025999069f, 0.367013275623322f, - 0.481990188360214f, - 0.367382973432541f, 0.482092022895813f, 0.367752790451050f, - 0.482193619012833f, - 0.368122667074203f, 0.482294887304306f, 0.368492603302002f, - 0.482395917177200f, - 0.368862658739090f, 0.482496619224548f, 0.369232743978500f, - 0.482597053050995f, - 0.369602948427200f, 0.482697218656540f, 0.369973212480545f, - 0.482797086238861f, - 0.370343536138535f, 0.482896685600281f, 0.370713949203491f, - 0.482995986938477f, - 0.371084451675415f, 0.483094990253448f, 0.371455013751984f, - 0.483193725347519f, - 0.371825665235519f, 0.483292192220688f, 0.372196376323700f, - 0.483390361070633f, - 0.372567176818848f, 0.483488231897354f, 0.372938036918640f, - 0.483585834503174f, - 0.373308986425400f, 0.483683139085770f, 0.373679995536804f, - 0.483780175447464f, - 0.374051094055176f, 0.483876913785934f, 0.374422252178192f, - 0.483973383903503f, - 0.374793499708176f, 0.484069555997849f, 0.375164806842804f, - 0.484165430068970f, - 0.375536203384399f, 0.484261035919189f, 0.375907659530640f, - 0.484356373548508f, - 0.376279205083847f, 0.484451413154602f, 0.376650810241699f, - 0.484546154737473f, - 0.377022475004196f, 0.484640628099442f, 0.377394229173660f, - 0.484734803438187f, - 0.377766042947769f, 0.484828680753708f, 0.378137946128845f, - 0.484922289848328f, - 0.378509908914566f, 0.485015630722046f, 0.378881961107254f, - 0.485108673572540f, - 0.379254043102264f, 0.485201418399811f, 0.379626244306564f, - 0.485293895006180f, - 0.379998475313187f, 0.485386073589325f, 0.380370795726776f, - 0.485477954149246f, - 0.380743205547333f, 0.485569566488266f, 0.381115674972534f, - 0.485660910606384f, - 0.381488204002380f, 0.485751956701279f, 0.381860792636871f, - 0.485842704772949f, - 0.382233470678329f, 0.485933154821396f, 0.382606208324432f, - 0.486023366451263f, - 0.382979035377502f, 0.486113250255585f, 0.383351892232895f, - 0.486202865839005f, - 0.383724838495255f, 0.486292183399200f, 0.384097874164581f, - 0.486381232738495f, - 0.384470939636230f, 0.486469984054565f, 0.384844094514847f, - 0.486558437347412f, - 0.385217308998108f, 0.486646622419357f, 0.385590612888336f, - 0.486734509468079f, - 0.385963946580887f, 0.486822128295898f, 0.386337369680405f, - 0.486909449100494f, - 0.386710882186890f, 0.486996471881866f, 0.387084424495697f, - 0.487083226442337f, - 0.387458056211472f, 0.487169682979584f, 0.387831717729568f, - 0.487255871295929f, - 0.388205498456955f, 0.487341761589050f, 0.388579308986664f, - 0.487427353858948f, - 0.388953179121017f, 0.487512677907944f, 0.389327138662338f, - 0.487597703933716f, - 0.389701157808304f, 0.487682431936264f, 0.390075236558914f, - 0.487766891717911f, - 0.390449374914169f, 0.487851053476334f, 0.390823602676392f, - 0.487934947013855f, - 0.391197860240936f, 0.488018542528152f, 0.391572207212448f, - 0.488101840019226f, - 0.391946613788605f, 0.488184869289398f, 0.392321079969406f, - 0.488267600536346f, - 0.392695605754852f, 0.488350033760071f, 0.393070191144943f, - 0.488432198762894f, - 0.393444836139679f, 0.488514065742493f, 0.393819570541382f, - 0.488595664501190f, - 0.394194334745407f, 0.488676935434341f, 0.394569188356400f, - 0.488757967948914f, - 0.394944071769714f, 0.488838672637939f, 0.395319044589996f, - 0.488919109106064f, - 0.395694077014923f, 0.488999247550964f, 0.396069169044495f, - 0.489079117774963f, - 0.396444320678711f, 0.489158689975739f, 0.396819531917572f, - 0.489237964153290f, - 0.397194802761078f, 0.489316970109940f, 0.397570133209229f, - 0.489395678043365f, - 0.397945523262024f, 0.489474087953568f, 0.398320972919464f, - 0.489552229642868f, - 0.398696482181549f, 0.489630073308945f, 0.399072051048279f, - 0.489707618951797f, - 0.399447679519653f, 0.489784896373749f, 0.399823367595673f, - 0.489861875772476f, - 0.400199115276337f, 0.489938557147980f, 0.400574922561646f, - 0.490014940500259f, - 0.400950789451599f, 0.490091055631638f, 0.401326715946198f, - 0.490166902542114f, - 0.401702702045441f, 0.490242421627045f, 0.402078747749329f, - 0.490317672491074f, - 0.402454853057861f, 0.490392625331879f, 0.402830988168716f, - 0.490467309951782f, - 0.403207212686539f, 0.490541696548462f, 0.403583467006683f, - 0.490615785121918f, - 0.403959810733795f, 0.490689605474472f, 0.404336184263229f, - 0.490763127803802f, - 0.404712617397308f, 0.490836352109909f, 0.405089110136032f, - 0.490909278392792f, - 0.405465662479401f, 0.490981936454773f, 0.405842274427414f, - 0.491054296493530f, - 0.406218945980072f, 0.491126358509064f, 0.406595647335052f, - 0.491198152303696f, - 0.406972438097000f, 0.491269648075104f, 0.407349258661270f, - 0.491340845823288f, - 0.407726138830185f, 0.491411775350571f, 0.408103078603745f, - 0.491482406854630f, - 0.408480048179626f, 0.491552740335464f, 0.408857107162476f, - 0.491622805595398f, - 0.409234195947647f, 0.491692543029785f, 0.409611344337463f, - 0.491762012243271f, - 0.409988552331924f, 0.491831213235855f, 0.410365819931030f, - 0.491900116205215f, - 0.410743117332459f, 0.491968721151352f, 0.411120474338531f, - 0.492037028074265f, - 0.411497890949249f, 0.492105036973953f, 0.411875367164612f, - 0.492172777652740f, - 0.412252873182297f, 0.492240220308304f, 0.412630438804626f, - 0.492307394742966f, - 0.413008064031601f, 0.492374241352081f, 0.413385748863220f, - 0.492440819740295f, - 0.413763463497162f, 0.492507129907608f, 0.414141237735748f, - 0.492573112249374f, - 0.414519041776657f, 0.492638826370239f, 0.414896935224533f, - 0.492704242467880f, - 0.415274858474731f, 0.492769360542297f, 0.415652841329575f, - 0.492834210395813f, - 0.416030853986740f, 0.492898762226105f, 0.416408926248550f, - 0.492963016033173f, - 0.416787058115005f, 0.493026971817017f, 0.417165219783783f, - 0.493090659379959f, - 0.417543441057205f, 0.493154048919678f, 0.417921721935272f, - 0.493217140436172f, - 0.418300032615662f, 0.493279963731766f, 0.418678402900696f, - 0.493342459201813f, - 0.419056802988052f, 0.493404686450958f, 0.419435262680054f, - 0.493466645479202f, - 0.419813781976700f, 0.493528276681900f, 0.420192331075668f, - 0.493589639663696f, - 0.420570939779282f, 0.493650704622269f, 0.420949578285217f, - 0.493711471557617f, - 0.421328276395798f, 0.493771970272064f, 0.421707004308701f, - 0.493832170963287f, - 0.422085791826248f, 0.493892073631287f, 0.422464638948441f, - 0.493951678276062f, - 0.422843515872955f, 0.494011014699936f, 0.423222452402115f, - 0.494070053100586f, - 0.423601418733597f, 0.494128793478012f, 0.423980414867401f, - 0.494187235832214f, - 0.424359470605850f, 0.494245409965515f, 0.424738585948944f, - 0.494303256273270f, - 0.425117731094360f, 0.494360834360123f, 0.425496935844421f, - 0.494418144226074f, - 0.425876170396805f, 0.494475126266479f, 0.426255434751511f, - 0.494531840085983f, - 0.426634758710861f, 0.494588255882263f, 0.427014142274857f, - 0.494644373655319f, - 0.427393525838852f, 0.494700223207474f, 0.427772998809814f, - 0.494755744934082f, - 0.428152471780777f, 0.494810998439789f, 0.428532034158707f, - 0.494865983724594f, - 0.428911596536636f, 0.494920641183853f, 0.429291218519211f, - 0.494975030422211f, - 0.429670870304108f, 0.495029091835022f, 0.430050581693649f, - 0.495082914829254f, - 0.430430322885513f, 0.495136409997940f, 0.430810123682022f, - 0.495189607143402f, - 0.431189924478531f, 0.495242536067963f, 0.431569814682007f, - 0.495295166969299f, - 0.431949704885483f, 0.495347499847412f, 0.432329654693604f, - 0.495399564504623f, - 0.432709634304047f, 0.495451331138611f, 0.433089673519135f, - 0.495502769947052f, - 0.433469742536545f, 0.495553970336914f, 0.433849841356277f, - 0.495604842901230f, - 0.434229999780655f, 0.495655417442322f, 0.434610158205032f, - 0.495705723762512f, - 0.434990376234055f, 0.495755732059479f, 0.435370653867722f, - 0.495805442333221f, - 0.435750931501389f, 0.495854884386063f, 0.436131268739700f, - 0.495903998613358f, - 0.436511665582657f, 0.495952844619751f, 0.436892062425613f, - 0.496001392602921f, - 0.437272518873215f, 0.496049642562866f, 0.437653005123138f, - 0.496097624301910f, - 0.438033521175385f, 0.496145308017731f, 0.438414067029953f, - 0.496192663908005f, - 0.438794672489166f, 0.496239781379700f, 0.439175277948380f, - 0.496286571025848f, - 0.439555943012238f, 0.496333062648773f, 0.439936667680740f, - 0.496379286050797f, - 0.440317392349243f, 0.496425211429596f, 0.440698176622391f, - 0.496470838785172f, - 0.441078960895538f, 0.496516168117523f, 0.441459804773331f, - 0.496561229228973f, - 0.441840678453445f, 0.496605962514877f, 0.442221581935883f, - 0.496650427579880f, - 0.442602545022964f, 0.496694594621658f, 0.442983508110046f, - 0.496738493442535f, - 0.443364530801773f, 0.496782064437866f, 0.443745553493500f, - 0.496825367212296f, - 0.444126635789871f, 0.496868371963501f, 0.444507747888565f, - 0.496911078691483f, - 0.444888889789581f, 0.496953487396240f, 0.445270061492920f, - 0.496995598077774f, - 0.445651292800903f, 0.497037440538406f, 0.446032524108887f, - 0.497078984975815f, - 0.446413785219193f, 0.497120231389999f, 0.446795076131821f, - 0.497161179780960f, - 0.447176426649094f, 0.497201830148697f, 0.447557777166367f, - 0.497242212295532f, - 0.447939187288284f, 0.497282296419144f, 0.448320597410202f, - 0.497322082519531f, - 0.448702067136765f, 0.497361570596695f, 0.449083566665649f, - 0.497400760650635f, - 0.449465066194534f, 0.497439652681351f, 0.449846625328064f, - 0.497478276491165f, - 0.450228184461594f, 0.497516602277756f, 0.450609803199768f, - 0.497554630041122f, - 0.450991421937943f, 0.497592359781265f, 0.451373100280762f, - 0.497629791498184f, - 0.451754778623581f, 0.497666954994202f, 0.452136516571045f, - 0.497703820466995f, - 0.452518254518509f, 0.497740387916565f, 0.452900022268295f, - 0.497776657342911f, - 0.453281819820404f, 0.497812628746033f, 0.453663676977158f, - 0.497848302125931f, - 0.454045534133911f, 0.497883707284927f, 0.454427421092987f, - 0.497918814420700f, - 0.454809308052063f, 0.497953623533249f, 0.455191254615784f, - 0.497988134622574f, - 0.455573230981827f, 0.498022347688675f, 0.455955207347870f, - 0.498056292533875f, - 0.456337243318558f, 0.498089909553528f, 0.456719279289246f, - 0.498123258352280f, - 0.457101345062256f, 0.498156309127808f, 0.457483440637589f, - 0.498189061880112f, - 0.457865566015244f, 0.498221516609192f, 0.458247691392899f, - 0.498253703117371f, - 0.458629876375198f, 0.498285561800003f, 0.459012061357498f, - 0.498317152261734f, - 0.459394276142120f, 0.498348444700241f, 0.459776520729065f, - 0.498379439115524f, - 0.460158795118332f, 0.498410135507584f, 0.460541069507599f, - 0.498440563678741f, - 0.460923373699188f, 0.498470664024353f, 0.461305707693100f, - 0.498500496149063f, - 0.461688071489334f, 0.498530030250549f, 0.462070435285568f, - 0.498559266328812f, - 0.462452858686447f, 0.498588204383850f, 0.462835282087326f, - 0.498616874217987f, - 0.463217705488205f, 0.498645216226578f, 0.463600188493729f, - 0.498673290014267f, - 0.463982671499252f, 0.498701065778732f, 0.464365184307098f, - 0.498728543519974f, - 0.464747726917267f, 0.498755723237991f, 0.465130269527435f, - 0.498782604932785f, - 0.465512841939926f, 0.498809218406677f, 0.465895414352417f, - 0.498835533857346f, - 0.466278046369553f, 0.498861521482468f, 0.466660678386688f, - 0.498887240886688f, - 0.467043310403824f, 0.498912662267685f, 0.467426002025604f, - 0.498937815427780f, - 0.467808693647385f, 0.498962640762329f, 0.468191385269165f, - 0.498987197875977f, - 0.468574106693268f, 0.499011427164078f, 0.468956857919693f, - 0.499035388231277f, - 0.469339638948441f, 0.499059051275253f, 0.469722419977188f, - 0.499082416296005f, - 0.470105201005936f, 0.499105513095856f, 0.470488041639328f, - 0.499128282070160f, - 0.470870882272720f, 0.499150782823563f, 0.471253722906113f, - 0.499172955751419f, - 0.471636593341827f, 0.499194860458374f, 0.472019463777542f, - 0.499216467142105f, - 0.472402364015579f, 0.499237775802612f, 0.472785294055939f, - 0.499258816242218f, - 0.473168224096298f, 0.499279528856277f, 0.473551183938980f, - 0.499299973249435f, - 0.473934143781662f, 0.499320119619370f, 0.474317133426666f, - 0.499339967966080f, - 0.474700123071671f, 0.499359518289566f, 0.475083142518997f, - 0.499378770589828f, - 0.475466161966324f, 0.499397724866867f, 0.475849211215973f, - 0.499416410923004f, - 0.476232260465622f, 0.499434769153595f, 0.476615339517593f, - 0.499452859163284f, - 0.476998418569565f, 0.499470651149750f, 0.477381497621536f, - 0.499488145112991f, - 0.477764606475830f, 0.499505341053009f, 0.478147745132446f, - 0.499522238969803f, - 0.478530883789063f, 0.499538868665695f, 0.478914022445679f, - 0.499555170536041f, - 0.479297190904617f, 0.499571204185486f, 0.479680359363556f, - 0.499586939811707f, - 0.480063527822495f, 0.499602377414703f, 0.480446726083755f, - 0.499617516994476f, - 0.480829954147339f, 0.499632388353348f, 0.481213152408600f, - 0.499646931886673f, - 0.481596380472183f, 0.499661177396774f, 0.481979638338089f, - 0.499675154685974f, - 0.482362866401672f, 0.499688833951950f, 0.482746154069901f, - 0.499702215194702f, - 0.483129411935806f, 0.499715298414230f, 0.483512699604034f, - 0.499728083610535f, - 0.483895987272263f, 0.499740600585938f, 0.484279274940491f, - 0.499752789735794f, - 0.484662592411041f, 0.499764710664749f, 0.485045909881592f, - 0.499776333570480f, - 0.485429257154465f, 0.499787658452988f, 0.485812574625015f, - 0.499798685312271f, - 0.486195921897888f, 0.499809414148331f, 0.486579269170761f, - 0.499819844961166f, - 0.486962646245956f, 0.499830007553101f, 0.487346023321152f, - 0.499839842319489f, - 0.487729400396347f, 0.499849408864975f, 0.488112777471542f, - 0.499858677387238f, - 0.488496154546738f, 0.499867647886276f, 0.488879561424255f, - 0.499876320362091f, - 0.489262968301773f, 0.499884694814682f, 0.489646375179291f, - 0.499892801046371f, - 0.490029782056808f, 0.499900579452515f, 0.490413218736649f, - 0.499908089637756f, - 0.490796625614166f, 0.499915301799774f, 0.491180062294006f, - 0.499922215938568f, - 0.491563498973846f, 0.499928832054138f, 0.491946935653687f, - 0.499935150146484f, - 0.492330402135849f, 0.499941170215607f, 0.492713838815689f, - 0.499946922063828f, - 0.493097305297852f, 0.499952346086502f, 0.493480771780014f, - 0.499957501888275f, - 0.493864238262177f, 0.499962359666824f, 0.494247704744339f, - 0.499966919422150f, - 0.494631171226501f, 0.499971181154251f, 0.495014637708664f, - 0.499975144863129f, - 0.495398133993149f, 0.499978810548782f, 0.495781600475311f, - 0.499982208013535f, - 0.496165096759796f, 0.499985307455063f, 0.496548563241959f, - 0.499988079071045f, - 0.496932059526443f, 0.499990582466125f, 0.497315555810928f, - 0.499992787837982f, - 0.497699022293091f, 0.499994695186615f, 0.498082518577576f, - 0.499996334314346f, - 0.498466014862061f, 0.499997645616531f, 0.498849511146545f, - 0.499998688697815f, - 0.499233007431030f, 0.499999403953552f, 0.499616503715515f, - 0.499999850988388f, -}; - - -/** -* \par -* Generation of realCoefB array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-* {    
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-*  } 
-* -*/ -static const float32_t realCoefB[8192] = { - 0.500000000000000f, 0.500000000000000f, 0.500383496284485f, - 0.499999850988388f, - 0.500766992568970f, 0.499999403953552f, 0.501150488853455f, - 0.499998688697815f, - 0.501533985137939f, 0.499997645616531f, 0.501917481422424f, - 0.499996334314346f, - 0.502300977706909f, 0.499994695186615f, 0.502684473991394f, - 0.499992787837982f, - 0.503067970275879f, 0.499990582466125f, 0.503451406955719f, - 0.499988079071045f, - 0.503834903240204f, 0.499985307455063f, 0.504218399524689f, - 0.499982208013535f, - 0.504601895809174f, 0.499978810548782f, 0.504985332489014f, - 0.499975144863129f, - 0.505368828773499f, 0.499971181154251f, 0.505752325057983f, - 0.499966919422150f, - 0.506135761737823f, 0.499962359666824f, 0.506519258022308f, - 0.499957501888275f, - 0.506902694702148f, 0.499952346086502f, 0.507286131381989f, - 0.499946922063828f, - 0.507669627666473f, 0.499941170215607f, 0.508053064346313f, - 0.499935150146484f, - 0.508436501026154f, 0.499928832054138f, 0.508819937705994f, - 0.499922215938568f, - 0.509203374385834f, 0.499915301799774f, 0.509586811065674f, - 0.499908089637756f, - 0.509970188140869f, 0.499900579452515f, 0.510353624820709f, - 0.499892801046371f, - 0.510737061500549f, 0.499884694814682f, 0.511120438575745f, - 0.499876320362091f, - 0.511503815650940f, 0.499867647886276f, 0.511887252330780f, - 0.499858677387238f, - 0.512270629405975f, 0.499849408864975f, 0.512654006481171f, - 0.499839842319489f, - 0.513037383556366f, 0.499830007553101f, 0.513420701026917f, - 0.499819844961166f, - 0.513804078102112f, 0.499809414148331f, 0.514187395572662f, - 0.499798685312271f, - 0.514570772647858f, 0.499787658452988f, 0.514954090118408f, - 0.499776333570480f, - 0.515337407588959f, 0.499764710664749f, 0.515720725059509f, - 0.499752789735794f, - 0.516103982925415f, 0.499740600585938f, 0.516487300395966f, - 0.499728083610535f, - 0.516870558261871f, 0.499715298414230f, 0.517253875732422f, - 0.499702215194702f, - 0.517637133598328f, 0.499688833951950f, 0.518020391464233f, - 0.499675154685974f, - 0.518403589725494f, 0.499661177396774f, 0.518786847591400f, - 0.499646931886673f, - 0.519170045852661f, 0.499632388353348f, 0.519553244113922f, - 0.499617516994476f, - 0.519936442375183f, 0.499602377414703f, 0.520319640636444f, - 0.499586939811707f, - 0.520702838897705f, 0.499571204185486f, 0.521085977554321f, - 0.499555170536041f, - 0.521469116210938f, 0.499538868665695f, 0.521852254867554f, - 0.499522238969803f, - 0.522235393524170f, 0.499505341053009f, 0.522618472576141f, - 0.499488145112991f, - 0.523001611232758f, 0.499470651149750f, 0.523384690284729f, - 0.499452859163284f, - 0.523767769336700f, 0.499434769153595f, 0.524150788784027f, - 0.499416410923004f, - 0.524533808231354f, 0.499397724866867f, 0.524916887283325f, - 0.499378770589828f, - 0.525299847126007f, 0.499359518289566f, 0.525682866573334f, - 0.499339967966080f, - 0.526065826416016f, 0.499320119619370f, 0.526448845863342f, - 0.499299973249435f, - 0.526831746101379f, 0.499279528856277f, 0.527214705944061f, - 0.499258816242218f, - 0.527597606182098f, 0.499237775802612f, 0.527980506420136f, - 0.499216467142105f, - 0.528363406658173f, 0.499194860458374f, 0.528746306896210f, - 0.499172955751419f, - 0.529129147529602f, 0.499150782823563f, 0.529511988162994f, - 0.499128282070160f, - 0.529894769191742f, 0.499105513095856f, 0.530277609825134f, - 0.499082416296005f, - 0.530660390853882f, 0.499059051275253f, 0.531043112277985f, - 0.499035388231277f, - 0.531425893306732f, 0.499011427164078f, 0.531808614730835f, - 0.498987197875977f, - 0.532191336154938f, 0.498962640762329f, 0.532573997974396f, - 0.498937815427780f, - 0.532956659793854f, 0.498912662267685f, 0.533339321613312f, - 0.498887240886688f, - 0.533721983432770f, 0.498861521482468f, 0.534104585647583f, - 0.498835533857346f, - 0.534487187862396f, 0.498809218406677f, 0.534869730472565f, - 0.498782604932785f, - 0.535252273082733f, 0.498755723237991f, 0.535634815692902f, - 0.498728543519974f, - 0.536017298698425f, 0.498701065778732f, 0.536399841308594f, - 0.498673290014267f, - 0.536782264709473f, 0.498645216226578f, 0.537164747714996f, - 0.498616874217987f, - 0.537547171115875f, 0.498588204383850f, 0.537929534912109f, - 0.498559266328812f, - 0.538311958312988f, 0.498530030250549f, 0.538694262504578f, - 0.498500496149063f, - 0.539076626300812f, 0.498470664024353f, 0.539458930492401f, - 0.498440563678741f, - 0.539841234683990f, 0.498410135507584f, 0.540223479270935f, - 0.498379439115524f, - 0.540605723857880f, 0.498348444700241f, 0.540987968444824f, - 0.498317152261734f, - 0.541370153427124f, 0.498285561800003f, 0.541752278804779f, - 0.498253703117371f, - 0.542134463787079f, 0.498221516609192f, 0.542516589164734f, - 0.498189061880112f, - 0.542898654937744f, 0.498156309127808f, 0.543280720710754f, - 0.498123258352280f, - 0.543662786483765f, 0.498089909553528f, 0.544044792652130f, - 0.498056292533875f, - 0.544426798820496f, 0.498022347688675f, 0.544808745384216f, - 0.497988134622574f, - 0.545190691947937f, 0.497953623533249f, 0.545572578907013f, - 0.497918814420700f, - 0.545954465866089f, 0.497883707284927f, 0.546336352825165f, - 0.497848302125931f, - 0.546718180179596f, 0.497812628746033f, 0.547099947929382f, - 0.497776657342911f, - 0.547481775283813f, 0.497740387916565f, 0.547863483428955f, - 0.497703820466995f, - 0.548245191574097f, 0.497666954994202f, 0.548626899719238f, - 0.497629791498184f, - 0.549008548259735f, 0.497592359781265f, 0.549390196800232f, - 0.497554630041122f, - 0.549771785736084f, 0.497516602277756f, 0.550153374671936f, - 0.497478276491165f, - 0.550534904003143f, 0.497439652681351f, 0.550916433334351f, - 0.497400760650635f, - 0.551297962665558f, 0.497361570596695f, 0.551679372787476f, - 0.497322082519531f, - 0.552060842514038f, 0.497282296419144f, 0.552442193031311f, - 0.497242212295532f, - 0.552823603153229f, 0.497201830148697f, 0.553204894065857f, - 0.497161179780960f, - 0.553586184978485f, 0.497120231389999f, 0.553967475891113f, - 0.497078984975815f, - 0.554348707199097f, 0.497037440538406f, 0.554729938507080f, - 0.496995598077774f, - 0.555111110210419f, 0.496953487396240f, 0.555492222309113f, - 0.496911078691483f, - 0.555873334407806f, 0.496868371963501f, 0.556254446506500f, - 0.496825367212296f, - 0.556635499000549f, 0.496782064437866f, 0.557016491889954f, - 0.496738493442535f, - 0.557397484779358f, 0.496694594621658f, 0.557778418064117f, - 0.496650427579880f, - 0.558159291744232f, 0.496605962514877f, 0.558540165424347f, - 0.496561229228973f, - 0.558921039104462f, 0.496516168117523f, 0.559301853179932f, - 0.496470838785172f, - 0.559682607650757f, 0.496425211429596f, 0.560063362121582f, - 0.496379286050797f, - 0.560444056987762f, 0.496333062648773f, 0.560824692249298f, - 0.496286571025848f, - 0.561205327510834f, 0.496239781379700f, 0.561585903167725f, - 0.496192663908005f, - 0.561966478824615f, 0.496145308017731f, 0.562346994876862f, - 0.496097624301910f, - 0.562727510929108f, 0.496049642562866f, 0.563107967376709f, - 0.496001392602921f, - 0.563488364219666f, 0.495952844619751f, 0.563868701457977f, - 0.495903998613358f, - 0.564249038696289f, 0.495854884386063f, 0.564629375934601f, - 0.495805442333221f, - 0.565009593963623f, 0.495755732059479f, 0.565389811992645f, - 0.495705723762512f, - 0.565770030021667f, 0.495655417442322f, 0.566150128841400f, - 0.495604842901230f, - 0.566530287265778f, 0.495553970336914f, 0.566910326480865f, - 0.495502769947052f, - 0.567290365695953f, 0.495451331138611f, 0.567670345306396f, - 0.495399564504623f, - 0.568050265312195f, 0.495347499847412f, 0.568430185317993f, - 0.495295166969299f, - 0.568810045719147f, 0.495242536067963f, 0.569189906120300f, - 0.495189607143402f, - 0.569569647312164f, 0.495136409997940f, 0.569949388504028f, - 0.495082914829254f, - 0.570329129695892f, 0.495029091835022f, 0.570708811283112f, - 0.494975030422211f, - 0.571088373661041f, 0.494920641183853f, 0.571467995643616f, - 0.494865983724594f, - 0.571847498416901f, 0.494810998439789f, 0.572227001190186f, - 0.494755744934082f, - 0.572606444358826f, 0.494700223207474f, 0.572985887527466f, - 0.494644373655319f, - 0.573365211486816f, 0.494588255882263f, 0.573744535446167f, - 0.494531840085983f, - 0.574123859405518f, 0.494475126266479f, 0.574503064155579f, - 0.494418144226074f, - 0.574882268905640f, 0.494360834360123f, 0.575261414051056f, - 0.494303256273270f, - 0.575640499591827f, 0.494245409965515f, 0.576019585132599f, - 0.494187235832214f, - 0.576398611068726f, 0.494128793478012f, 0.576777577400208f, - 0.494070053100586f, - 0.577156484127045f, 0.494011014699936f, 0.577535390853882f, - 0.493951678276062f, - 0.577914178371429f, 0.493892073631287f, 0.578292965888977f, - 0.493832170963287f, - 0.578671753406525f, 0.493771970272064f, 0.579050421714783f, - 0.493711471557617f, - 0.579429090023041f, 0.493650704622269f, 0.579807698726654f, - 0.493589639663696f, - 0.580186247825623f, 0.493528276681900f, 0.580564737319946f, - 0.493466645479202f, - 0.580943167209625f, 0.493404686450958f, 0.581321597099304f, - 0.493342459201813f, - 0.581699967384338f, 0.493279963731766f, 0.582078278064728f, - 0.493217140436172f, - 0.582456588745117f, 0.493154048919678f, 0.582834780216217f, - 0.493090659379959f, - 0.583212971687317f, 0.493026971817017f, 0.583591103553772f, - 0.492963016033173f, - 0.583969175815582f, 0.492898762226105f, 0.584347188472748f, - 0.492834210395813f, - 0.584725141525269f, 0.492769360542297f, 0.585103094577789f, - 0.492704242467880f, - 0.585480928421021f, 0.492638826370239f, 0.585858762264252f, - 0.492573112249374f, - 0.586236536502838f, 0.492507129907608f, 0.586614251136780f, - 0.492440819740295f, - 0.586991965770721f, 0.492374241352081f, 0.587369561195374f, - 0.492307394742966f, - 0.587747097015381f, 0.492240220308304f, 0.588124632835388f, - 0.492172777652740f, - 0.588502109050751f, 0.492105036973953f, 0.588879525661469f, - 0.492037028074265f, - 0.589256882667542f, 0.491968721151352f, 0.589634180068970f, - 0.491900116205215f, - 0.590011477470398f, 0.491831213235855f, 0.590388655662537f, - 0.491762012243271f, - 0.590765833854675f, 0.491692543029785f, 0.591142892837524f, - 0.491622805595398f, - 0.591519951820374f, 0.491552740335464f, 0.591896951198578f, - 0.491482406854630f, - 0.592273890972137f, 0.491411775350571f, 0.592650771141052f, - 0.491340845823288f, - 0.593027591705322f, 0.491269648075104f, 0.593404352664948f, - 0.491198152303696f, - 0.593781054019928f, 0.491126358509064f, 0.594157755374908f, - 0.491054296493530f, - 0.594534337520599f, 0.490981936454773f, 0.594910860061646f, - 0.490909278392792f, - 0.595287382602692f, 0.490836352109909f, 0.595663845539093f, - 0.490763127803802f, - 0.596040189266205f, 0.490689605474472f, 0.596416532993317f, - 0.490615785121918f, - 0.596792817115784f, 0.490541696548462f, 0.597168982028961f, - 0.490467309951782f, - 0.597545146942139f, 0.490392625331879f, 0.597921252250671f, - 0.490317672491074f, - 0.598297297954559f, 0.490242421627045f, 0.598673284053802f, - 0.490166902542114f, - 0.599049210548401f, 0.490091055631638f, 0.599425077438354f, - 0.490014940500259f, - 0.599800884723663f, 0.489938557147980f, 0.600176632404327f, - 0.489861875772476f, - 0.600552320480347f, 0.489784896373749f, 0.600927948951721f, - 0.489707618951797f, - 0.601303517818451f, 0.489630073308945f, 0.601679027080536f, - 0.489552229642868f, - 0.602054476737976f, 0.489474087953568f, 0.602429866790771f, - 0.489395678043365f, - 0.602805197238922f, 0.489316970109940f, 0.603180468082428f, - 0.489237964153290f, - 0.603555679321289f, 0.489158689975739f, 0.603930830955505f, - 0.489079117774963f, - 0.604305922985077f, 0.488999247550964f, 0.604680955410004f, - 0.488919109106064f, - 0.605055928230286f, 0.488838672637939f, 0.605430841445923f, - 0.488757967948914f, - 0.605805635452271f, 0.488676935434341f, 0.606180429458618f, - 0.488595664501190f, - 0.606555163860321f, 0.488514065742493f, 0.606929838657379f, - 0.488432198762894f, - 0.607304394245148f, 0.488350033760071f, 0.607678949832916f, - 0.488267600536346f, - 0.608053386211395f, 0.488184869289398f, 0.608427822589874f, - 0.488101840019226f, - 0.608802139759064f, 0.488018542528152f, 0.609176397323608f, - 0.487934947013855f, - 0.609550595283508f, 0.487851053476334f, 0.609924793243408f, - 0.487766891717911f, - 0.610298871994019f, 0.487682431936264f, 0.610672831535339f, - 0.487597703933716f, - 0.611046791076660f, 0.487512677907944f, 0.611420691013336f, - 0.487427353858948f, - 0.611794531345367f, 0.487341761589050f, 0.612168252468109f, - 0.487255871295929f, - 0.612541973590851f, 0.487169682979584f, 0.612915575504303f, - 0.487083226442337f, - 0.613289117813110f, 0.486996471881866f, 0.613662600517273f, - 0.486909449100494f, - 0.614036023616791f, 0.486822128295898f, 0.614409387111664f, - 0.486734509468079f, - 0.614782691001892f, 0.486646622419357f, 0.615155875682831f, - 0.486558437347412f, - 0.615529060363770f, 0.486469984054565f, 0.615902125835419f, - 0.486381232738495f, - 0.616275131702423f, 0.486292183399200f, 0.616648077964783f, - 0.486202865839005f, - 0.617020964622498f, 0.486113250255585f, 0.617393791675568f, - 0.486023366451263f, - 0.617766559123993f, 0.485933154821396f, 0.618139207363129f, - 0.485842704772949f, - 0.618511795997620f, 0.485751956701279f, 0.618884325027466f, - 0.485660910606384f, - 0.619256794452667f, 0.485569566488266f, 0.619629204273224f, - 0.485477954149246f, - 0.620001494884491f, 0.485386073589325f, 0.620373785495758f, - 0.485293895006180f, - 0.620745956897736f, 0.485201418399811f, 0.621118068695068f, - 0.485108673572540f, - 0.621490061283112f, 0.485015630722046f, 0.621862053871155f, - 0.484922289848328f, - 0.622233927249908f, 0.484828680753708f, 0.622605800628662f, - 0.484734803438187f, - 0.622977554798126f, 0.484640628099442f, 0.623349189758301f, - 0.484546154737473f, - 0.623720824718475f, 0.484451413154602f, 0.624092340469360f, - 0.484356373548508f, - 0.624463796615601f, 0.484261035919189f, 0.624835193157196f, - 0.484165430068970f, - 0.625206530094147f, 0.484069555997849f, 0.625577747821808f, - 0.483973383903503f, - 0.625948905944824f, 0.483876913785934f, 0.626320004463196f, - 0.483780175447464f, - 0.626691043376923f, 0.483683139085770f, 0.627061963081360f, - 0.483585834503174f, - 0.627432823181152f, 0.483488231897354f, 0.627803623676300f, - 0.483390361070633f, - 0.628174364566803f, 0.483292192220688f, 0.628544986248016f, - 0.483193725347519f, - 0.628915548324585f, 0.483094990253448f, 0.629286050796509f, - 0.482995986938477f, - 0.629656434059143f, 0.482896685600281f, 0.630026817321777f, - 0.482797086238861f, - 0.630397081375122f, 0.482697218656540f, 0.630767226219177f, - 0.482597053050995f, - 0.631137371063232f, 0.482496619224548f, 0.631507396697998f, - 0.482395917177200f, - 0.631877362728119f, 0.482294887304306f, 0.632247209548950f, - 0.482193619012833f, - 0.632616996765137f, 0.482092022895813f, 0.632986724376678f, - 0.481990188360214f, - 0.633356392383575f, 0.481888025999069f, 0.633725941181183f, - 0.481785595417023f, - 0.634095430374146f, 0.481682896614075f, 0.634464859962463f, - 0.481579899787903f, - 0.634834170341492f, 0.481476634740829f, 0.635203421115875f, - 0.481373071670532f, - 0.635572552680969f, 0.481269240379334f, 0.635941684246063f, - 0.481165111064911f, - 0.636310696601868f, 0.481060713529587f, 0.636679589748383f, - 0.480956017971039f, - 0.637048482894897f, 0.480851024389267f, 0.637417197227478f, - 0.480745792388916f, - 0.637785911560059f, 0.480640232563019f, 0.638154506683350f, - 0.480534434318542f, - 0.638523042201996f, 0.480428308248520f, 0.638891458511353f, - 0.480321943759918f, - 0.639259815216064f, 0.480215251445770f, 0.639628112316132f, - 0.480108320713043f, - 0.639996349811554f, 0.480001062154770f, 0.640364408493042f, - 0.479893565177917f, - 0.640732467174530f, 0.479785770177841f, 0.641100406646729f, - 0.479677677154541f, - 0.641468286514282f, 0.479569315910339f, 0.641836047172546f, - 0.479460656642914f, - 0.642203748226166f, 0.479351729154587f, 0.642571389675140f, - 0.479242533445358f, - 0.642938911914825f, 0.479133039712906f, 0.643306374549866f, - 0.479023247957230f, - 0.643673717975616f, 0.478913217782974f, 0.644041001796722f, - 0.478802859783173f, - 0.644408226013184f, 0.478692263364792f, 0.644775331020355f, - 0.478581339120865f, - 0.645142316818237f, 0.478470176458359f, 0.645509302616119f, - 0.478358715772629f, - 0.645876109600067f, 0.478246957063675f, 0.646242916584015f, - 0.478134930133820f, - 0.646609604358673f, 0.478022634983063f, 0.646976172924042f, - 0.477910041809082f, - 0.647342681884766f, 0.477797180414200f, 0.647709131240845f, - 0.477684020996094f, - 0.648075461387634f, 0.477570593357086f, 0.648441672325134f, - 0.477456867694855f, - 0.648807883262634f, 0.477342873811722f, 0.649173915386200f, - 0.477228611707687f, - 0.649539887905121f, 0.477114051580429f, 0.649905800819397f, - 0.476999223232269f, - 0.650271594524384f, 0.476884096860886f, 0.650637328624725f, - 0.476768702268600f, - 0.651003003120422f, 0.476653009653091f, 0.651368498802185f, - 0.476537048816681f, - 0.651733994483948f, 0.476420819759369f, 0.652099311351776f, - 0.476304292678833f, - 0.652464628219604f, 0.476187497377396f, 0.652829825878143f, - 0.476070433855057f, - 0.653194904327393f, 0.475953072309494f, 0.653559923171997f, - 0.475835442543030f, - 0.653924822807312f, 0.475717514753342f, 0.654289662837982f, - 0.475599318742752f, - 0.654654383659363f, 0.475480824708939f, 0.655019044876099f, - 0.475362062454224f, - 0.655383586883545f, 0.475243031978607f, 0.655748009681702f, - 0.475123733282089f, - 0.656112432479858f, 0.475004136562347f, 0.656476676464081f, - 0.474884241819382f, - 0.656840860843658f, 0.474764078855515f, 0.657204985618591f, - 0.474643647670746f, - 0.657568991184235f, 0.474522948265076f, 0.657932877540588f, - 0.474401950836182f, - 0.658296704292297f, 0.474280685186386f, 0.658660411834717f, - 0.474159121513367f, - 0.659024059772491f, 0.474037289619446f, 0.659387588500977f, - 0.473915189504623f, - 0.659750998020172f, 0.473792791366577f, 0.660114347934723f, - 0.473670125007629f, - 0.660477638244629f, 0.473547190427780f, 0.660840749740601f, - 0.473423957824707f, - 0.661203861236572f, 0.473300457000732f, 0.661566793918610f, - 0.473176687955856f, - 0.661929666996002f, 0.473052620887756f, 0.662292480468750f, - 0.472928285598755f, - 0.662655174732208f, 0.472803652286530f, 0.663017749786377f, - 0.472678780555725f, - 0.663380205631256f, 0.472553610801697f, 0.663742601871490f, - 0.472428143024445f, - 0.664104938507080f, 0.472302407026291f, 0.664467096328735f, - 0.472176402807236f, - 0.664829254150391f, 0.472050130367279f, 0.665191233158112f, - 0.471923559904099f, - 0.665553152561188f, 0.471796721220016f, 0.665914952754974f, - 0.471669614315033f, - 0.666276693344116f, 0.471542209386826f, 0.666638314723969f, - 0.471414536237717f, - 0.666999816894531f, 0.471286594867706f, 0.667361259460449f, - 0.471158385276794f, - 0.667722582817078f, 0.471029877662659f, 0.668083786964417f, - 0.470901101827621f, - 0.668444931507111f, 0.470772027969360f, 0.668805956840515f, - 0.470642685890198f, - 0.669166862964630f, 0.470513075590134f, 0.669527709484100f, - 0.470383197069168f, - 0.669888436794281f, 0.470253020524979f, 0.670249044895172f, - 0.470122605562210f, - 0.670609593391418f, 0.469991862773895f, 0.670970022678375f, - 0.469860881567001f, - 0.671330332756042f, 0.469729602336884f, 0.671690583229065f, - 0.469598054885864f, - 0.672050714492798f, 0.469466239213943f, 0.672410726547241f, - 0.469334155321121f, - 0.672770678997040f, 0.469201773405075f, 0.673130512237549f, - 0.469069123268127f, - 0.673490226268768f, 0.468936175107956f, 0.673849821090698f, - 0.468802988529205f, - 0.674209356307983f, 0.468669503927231f, 0.674568772315979f, - 0.468535751104355f, - 0.674928069114685f, 0.468401730060577f, 0.675287246704102f, - 0.468267410993576f, - 0.675646364688873f, 0.468132823705673f, 0.676005363464355f, - 0.467997968196869f, - 0.676364302635193f, 0.467862844467163f, 0.676723062992096f, - 0.467727422714233f, - 0.677081763744354f, 0.467591762542725f, 0.677440345287323f, - 0.467455804347992f, - 0.677798807621002f, 0.467319577932358f, 0.678157210350037f, - 0.467183053493500f, - 0.678515493869781f, 0.467046260833740f, 0.678873658180237f, - 0.466909229755402f, - 0.679231703281403f, 0.466771900653839f, 0.679589688777924f, - 0.466634273529053f, - 0.679947495460510f, 0.466496407985687f, 0.680305242538452f, - 0.466358244419098f, - 0.680662930011749f, 0.466219812631607f, 0.681020438671112f, - 0.466081112623215f, - 0.681377887725830f, 0.465942144393921f, 0.681735157966614f, - 0.465802878141403f, - 0.682092368602753f, 0.465663343667984f, 0.682449519634247f, - 0.465523540973663f, - 0.682806491851807f, 0.465383470058441f, 0.683163404464722f, - 0.465243130922318f, - 0.683520197868347f, 0.465102523565292f, 0.683876872062683f, - 0.464961618185043f, - 0.684233427047729f, 0.464820444583893f, 0.684589862823486f, - 0.464679002761841f, - 0.684946238994598f, 0.464537292718887f, 0.685302436351776f, - 0.464395314455032f, - 0.685658574104309f, 0.464253038167953f, 0.686014592647552f, - 0.464110493659973f, - 0.686370551586151f, 0.463967710733414f, 0.686726331710815f, - 0.463824629783630f, - 0.687082052230835f, 0.463681250810623f, 0.687437593936920f, - 0.463537633419037f, - 0.687793076038361f, 0.463393747806549f, 0.688148438930511f, - 0.463249564170837f, - 0.688503682613373f, 0.463105112314224f, 0.688858866691589f, - 0.462960392236710f, - 0.689213871955872f, 0.462815403938293f, 0.689568817615509f, - 0.462670147418976f, - 0.689923584461212f, 0.462524622678757f, 0.690278291702271f, - 0.462378799915314f, - 0.690632879734039f, 0.462232738733292f, 0.690987348556519f, - 0.462086379528046f, - 0.691341698169708f, 0.461939752101898f, 0.691695988178253f, - 0.461792886257172f, - 0.692050099372864f, 0.461645722389221f, 0.692404091358185f, - 0.461498260498047f, - 0.692758023738861f, 0.461350560188293f, 0.693111836910248f, - 0.461202591657639f, - 0.693465530872345f, 0.461054325103760f, 0.693819046020508f, - 0.460905820131302f, - 0.694172501564026f, 0.460757017135620f, 0.694525837898254f, - 0.460607945919037f, - 0.694879114627838f, 0.460458606481552f, 0.695232212543488f, - 0.460309028625488f, - 0.695585191249847f, 0.460159152746201f, 0.695938050746918f, - 0.460008978843689f, - 0.696290850639343f, 0.459858566522598f, 0.696643471717834f, - 0.459707885980606f, - 0.696996033191681f, 0.459556937217712f, 0.697348415851593f, - 0.459405690431595f, - 0.697700738906860f, 0.459254205226898f, 0.698052942752838f, - 0.459102421998978f, - 0.698404967784882f, 0.458950400352478f, 0.698756933212280f, - 0.458798080682755f, - 0.699108779430389f, 0.458645492792130f, 0.699460506439209f, - 0.458492636680603f, - 0.699812114238739f, 0.458339542150497f, 0.700163602828979f, - 0.458186149597168f, - 0.700514972209930f, 0.458032488822937f, 0.700866222381592f, - 0.457878559827805f, - 0.701217353343964f, 0.457724362611771f, 0.701568365097046f, - 0.457569897174835f, - 0.701919257640839f, 0.457415163516998f, 0.702270030975342f, - 0.457260161638260f, - 0.702620685100555f, 0.457104891538620f, 0.702971220016479f, - 0.456949323415756f, - 0.703321635723114f, 0.456793516874313f, 0.703671932220459f, - 0.456637442111969f, - 0.704022109508514f, 0.456481099128723f, 0.704372167587280f, - 0.456324487924576f, - 0.704722046852112f, 0.456167578697205f, 0.705071866512299f, - 0.456010431051254f, - 0.705421566963196f, 0.455853015184402f, 0.705771148204803f, - 0.455695331096649f, - 0.706120610237122f, 0.455537378787994f, 0.706469953060150f, - 0.455379128456116f, - 0.706819176673889f, 0.455220639705658f, 0.707168221473694f, - 0.455061882734299f, - 0.707517206668854f, 0.454902857542038f, 0.707866072654724f, - 0.454743564128876f, - 0.708214759826660f, 0.454584002494812f, 0.708563387393951f, - 0.454424172639847f, - 0.708911836147308f, 0.454264044761658f, 0.709260225296021f, - 0.454103678464890f, - 0.709608435630798f, 0.453943043947220f, 0.709956526756287f, - 0.453782171010971f, - 0.710304558277130f, 0.453621000051498f, 0.710652410984039f, - 0.453459560871124f, - 0.711000144481659f, 0.453297853469849f, 0.711347758769989f, - 0.453135877847672f, - 0.711695253849030f, 0.452973634004593f, 0.712042629718781f, - 0.452811151742935f, - 0.712389826774597f, 0.452648371458054f, 0.712736964225769f, - 0.452485352754593f, - 0.713083922863007f, 0.452322036027908f, 0.713430821895599f, - 0.452158480882645f, - 0.713777542114258f, 0.451994657516479f, 0.714124143123627f, - 0.451830536127090f, - 0.714470624923706f, 0.451666176319122f, 0.714816987514496f, - 0.451501548290253f, - 0.715163230895996f, 0.451336652040482f, 0.715509355068207f, - 0.451171487569809f, - 0.715855300426483f, 0.451006084680557f, 0.716201186180115f, - 0.450840383768082f, - 0.716546893119812f, 0.450674414634705f, 0.716892480850220f, - 0.450508207082748f, - 0.717238008975983f, 0.450341701507568f, 0.717583298683167f, - 0.450174957513809f, - 0.717928528785706f, 0.450007945299149f, 0.718273639678955f, - 0.449840664863586f, - 0.718618571758270f, 0.449673116207123f, 0.718963444232941f, - 0.449505299329758f, - 0.719308137893677f, 0.449337244033813f, 0.719652712345123f, - 0.449168890714645f, - 0.719997107982636f, 0.449000298976898f, 0.720341444015503f, - 0.448831409215927f, - 0.720685660839081f, 0.448662281036377f, 0.721029698848724f, - 0.448492884635925f, - 0.721373617649078f, 0.448323249816895f, 0.721717417240143f, - 0.448153316974640f, - 0.722061097621918f, 0.447983115911484f, 0.722404599189758f, - 0.447812676429749f, - 0.722747981548309f, 0.447641968727112f, 0.723091304302216f, - 0.447470992803574f, - 0.723434448242188f, 0.447299748659134f, 0.723777413368225f, - 0.447128236293793f, - 0.724120318889618f, 0.446956485509872f, 0.724463045597076f, - 0.446784436702728f, - 0.724805653095245f, 0.446612149477005f, 0.725148141384125f, - 0.446439594030380f, - 0.725490510463715f, 0.446266770362854f, 0.725832700729370f, - 0.446093708276749f, - 0.726174771785736f, 0.445920348167419f, 0.726516723632813f, - 0.445746749639511f, - 0.726858556270599f, 0.445572882890701f, 0.727200269699097f, - 0.445398747920990f, - 0.727541804313660f, 0.445224374532700f, 0.727883219718933f, - 0.445049703121185f, - 0.728224515914917f, 0.444874793291092f, 0.728565633296967f, - 0.444699615240097f, - 0.728906631469727f, 0.444524168968201f, 0.729247510433197f, - 0.444348484277725f, - 0.729588270187378f, 0.444172531366348f, 0.729928910732269f, - 0.443996280431747f, - 0.730269372463226f, 0.443819820880890f, 0.730609714984894f, - 0.443643063306808f, - 0.730949878692627f, 0.443466067314148f, 0.731289982795715f, - 0.443288803100586f, - 0.731629908084869f, 0.443111270666122f, 0.731969714164734f, - 0.442933470010757f, - 0.732309341430664f, 0.442755430936813f, 0.732648849487305f, - 0.442577123641968f, - 0.732988238334656f, 0.442398548126221f, 0.733327507972717f, - 0.442219734191895f, - 0.733666598796844f, 0.442040622234344f, 0.734005570411682f, - 0.441861271858215f, - 0.734344422817230f, 0.441681683063507f, 0.734683096408844f, - 0.441501796245575f, - 0.735021650791168f, 0.441321671009064f, 0.735360085964203f, - 0.441141277551651f, - 0.735698342323303f, 0.440960645675659f, 0.736036539077759f, - 0.440779715776443f, - 0.736374497413635f, 0.440598547458649f, 0.736712396144867f, - 0.440417140722275f, - 0.737050116062164f, 0.440235435962677f, 0.737387716770172f, - 0.440053492784500f, - 0.737725138664246f, 0.439871311187744f, 0.738062441349030f, - 0.439688831567764f, - 0.738399624824524f, 0.439506113529205f, 0.738736629486084f, - 0.439323127269745f, - 0.739073514938354f, 0.439139902591705f, 0.739410281181335f, - 0.438956409692764f, - 0.739746868610382f, 0.438772648572922f, 0.740083336830139f, - 0.438588619232178f, - 0.740419685840607f, 0.438404351472855f, 0.740755856037140f, - 0.438219845294952f, - 0.741091907024384f, 0.438035041093826f, 0.741427779197693f, - 0.437849998474121f, - 0.741763532161713f, 0.437664687633514f, 0.742099165916443f, - 0.437479138374329f, - 0.742434620857239f, 0.437293320894241f, 0.742769956588745f, - 0.437107264995575f, - 0.743105113506317f, 0.436920911073685f, 0.743440151214600f, - 0.436734348535538f, - 0.743775069713593f, 0.436547487974167f, 0.744109809398651f, - 0.436360388994217f, - 0.744444429874420f, 0.436173021793365f, 0.744778931140900f, - 0.435985416173935f, - 0.745113253593445f, 0.435797542333603f, 0.745447397232056f, - 0.435609430074692f, - 0.745781481266022f, 0.435421019792557f, 0.746115326881409f, - 0.435232400894165f, - 0.746449112892151f, 0.435043483972549f, 0.746782720088959f, - 0.434854328632355f, - 0.747116148471832f, 0.434664934873581f, 0.747449457645416f, - 0.434475272893906f, - 0.747782647609711f, 0.434285342693329f, 0.748115658760071f, - 0.434095174074173f, - 0.748448550701141f, 0.433904737234116f, 0.748781263828278f, - 0.433714061975479f, - 0.749113857746124f, 0.433523118495941f, 0.749446272850037f, - 0.433331936597824f, - 0.749778568744659f, 0.433140486478806f, 0.750110685825348f, - 0.432948768138886f, - 0.750442683696747f, 0.432756811380386f, 0.750774562358856f, - 0.432564586400986f, - 0.751106262207031f, 0.432372123003006f, 0.751437783241272f, - 0.432179391384125f, - 0.751769185066223f, 0.431986421346664f, 0.752100467681885f, - 0.431793183088303f, - 0.752431571483612f, 0.431599706411362f, 0.752762496471405f, - 0.431405961513519f, - 0.753093302249908f, 0.431211978197098f, 0.753423988819122f, - 0.431017726659775f, - 0.753754496574402f, 0.430823236703873f, 0.754084885120392f, - 0.430628478527069f, - 0.754415094852448f, 0.430433481931686f, 0.754745125770569f, - 0.430238217115402f, - 0.755075037479401f, 0.430042684078217f, 0.755404829978943f, - 0.429846942424774f, - 0.755734443664551f, 0.429650902748108f, 0.756063878536224f, - 0.429454624652863f, - 0.756393194198608f, 0.429258108139038f, 0.756722390651703f, - 0.429061323404312f, - 0.757051348686218f, 0.428864300251007f, 0.757380247116089f, - 0.428667008876801f, - 0.757708966732025f, 0.428469479084015f, 0.758037507534027f, - 0.428271710872650f, - 0.758365929126740f, 0.428073674440384f, 0.758694171905518f, - 0.427875369787216f, - 0.759022235870361f, 0.427676826715469f, 0.759350180625916f, - 0.427478045225143f, - 0.759678006172180f, 0.427278995513916f, 0.760005652904511f, - 0.427079707384110f, - 0.760333120822906f, 0.426880151033401f, 0.760660469532013f, - 0.426680356264114f, - 0.760987639427185f, 0.426480293273926f, 0.761314690113068f, - 0.426279991865158f, - 0.761641561985016f, 0.426079452037811f, 0.761968255043030f, - 0.425878643989563f, - 0.762294828891754f, 0.425677597522736f, 0.762621283531189f, - 0.425476282835007f, - 0.762947499752045f, 0.425274729728699f, 0.763273596763611f, - 0.425072938203812f, - 0.763599574565887f, 0.424870878458023f, 0.763925373554230f, - 0.424668580293655f, - 0.764250993728638f, 0.424466013908386f, 0.764576494693756f, - 0.424263238906860f, - 0.764901816844940f, 0.424060165882111f, 0.765226960182190f, - 0.423856884241104f, - 0.765551984310150f, 0.423653304576874f, 0.765876889228821f, - 0.423449516296387f, - 0.766201555728912f, 0.423245459794998f, 0.766526103019714f, - 0.423041164875031f, - 0.766850471496582f, 0.422836631536484f, 0.767174720764160f, - 0.422631829977036f, - 0.767498791217804f, 0.422426789999008f, 0.767822742462158f, - 0.422221481800079f, - 0.768146514892578f, 0.422015935182571f, 0.768470108509064f, - 0.421810150146484f, - 0.768793523311615f, 0.421604126691818f, 0.769116818904877f, - 0.421397835016251f, - 0.769439935684204f, 0.421191304922104f, 0.769762933254242f, - 0.420984506607056f, - 0.770085752010345f, 0.420777499675751f, 0.770408391952515f, - 0.420570224523544f, - 0.770730912685394f, 0.420362681150436f, 0.771053194999695f, - 0.420154929161072f, - 0.771375417709351f, 0.419946908950806f, 0.771697402000427f, - 0.419738620519638f, - 0.772019267082214f, 0.419530123472214f, 0.772340953350067f, - 0.419321358203888f, - 0.772662520408630f, 0.419112354516983f, 0.772983849048615f, - 0.418903112411499f, - 0.773305058479309f, 0.418693602085114f, 0.773626148700714f, - 0.418483853340149f, - 0.773947000503540f, 0.418273866176605f, 0.774267733097076f, - 0.418063640594482f, - 0.774588346481323f, 0.417853146791458f, 0.774908721446991f, - 0.417642414569855f, - 0.775228977203369f, 0.417431443929672f, 0.775549054145813f, - 0.417220205068588f, - 0.775869011878967f, 0.417008757591248f, 0.776188731193542f, - 0.416797041893005f, - 0.776508331298828f, 0.416585087776184f, 0.776827812194824f, - 0.416372895240784f, - 0.777147054672241f, 0.416160434484482f, 0.777466177940369f, - 0.415947735309601f, - 0.777785122394562f, 0.415734797716141f, 0.778103888034821f, - 0.415521621704102f, - 0.778422534465790f, 0.415308207273483f, 0.778741002082825f, - 0.415094524621964f, - 0.779059290885925f, 0.414880603551865f, 0.779377400875092f, - 0.414666473865509f, - 0.779695332050323f, 0.414452046155930f, 0.780013144016266f, - 0.414237409830093f, - 0.780330777168274f, 0.414022535085678f, 0.780648231506348f, - 0.413807392120361f, - 0.780965566635132f, 0.413592010736465f, 0.781282722949982f, - 0.413376390933990f, - 0.781599700450897f, 0.413160532712936f, 0.781916499137878f, - 0.412944436073303f, - 0.782233119010925f, 0.412728071212769f, 0.782549619674683f, - 0.412511497735977f, - 0.782865881919861f, 0.412294656038284f, 0.783182024955750f, - 0.412077575922012f, - 0.783498048782349f, 0.411860257387161f, 0.783813834190369f, - 0.411642700433731f, - 0.784129500389099f, 0.411424905061722f, 0.784444928169250f, - 0.411206841468811f, - 0.784760236740112f, 0.410988569259644f, 0.785075426101685f, - 0.410770028829575f, - 0.785390377044678f, 0.410551249980927f, 0.785705149173737f, - 0.410332232713699f, - 0.786019802093506f, 0.410112977027893f, 0.786334276199341f, - 0.409893482923508f, - 0.786648571491241f, 0.409673750400543f, 0.786962687969208f, - 0.409453779459000f, - 0.787276685237885f, 0.409233570098877f, 0.787590444087982f, - 0.409013092517853f, - 0.787904083728790f, 0.408792406320572f, 0.788217544555664f, - 0.408571451902390f, - 0.788530826568604f, 0.408350288867950f, 0.788843929767609f, - 0.408128857612610f, - 0.789156913757324f, 0.407907217741013f, 0.789469659328461f, - 0.407685309648514f, - 0.789782285690308f, 0.407463163137436f, 0.790094733238220f, - 0.407240778207779f, - 0.790407001972198f, 0.407018154859543f, 0.790719091892242f, - 0.406795293092728f, - 0.791031002998352f, 0.406572192907333f, 0.791342735290527f, - 0.406348884105682f, - 0.791654348373413f, 0.406125307083130f, 0.791965723037720f, - 0.405901491641998f, - 0.792276978492737f, 0.405677437782288f, 0.792588055133820f, - 0.405453115701675f, - 0.792898952960968f, 0.405228585004807f, 0.793209671974182f, - 0.405003815889359f, - 0.793520212173462f, 0.404778808355331f, 0.793830573558807f, - 0.404553562402725f, - 0.794140756130219f, 0.404328078031540f, 0.794450819492340f, - 0.404102355241776f, - 0.794760644435883f, 0.403876423835754f, 0.795070350170136f, - 0.403650224208832f, - 0.795379877090454f, 0.403423786163330f, 0.795689165592194f, - 0.403197109699249f, - 0.795998334884644f, 0.402970194816589f, 0.796307325363159f, - 0.402743041515350f, - 0.796616137027740f, 0.402515679597855f, 0.796924769878387f, - 0.402288049459457f, - 0.797233223915100f, 0.402060180902481f, 0.797541558742523f, - 0.401832103729248f, - 0.797849655151367f, 0.401603758335114f, 0.798157572746277f, - 0.401375204324722f, - 0.798465371131897f, 0.401146411895752f, 0.798772931098938f, - 0.400917351245880f, - 0.799080371856689f, 0.400688081979752f, 0.799387574195862f, - 0.400458574295044f, - 0.799694657325745f, 0.400228828191757f, 0.800001561641693f, - 0.399998843669891f, - 0.800308227539063f, 0.399768620729446f, 0.800614774227142f, - 0.399538189172745f, - 0.800921142101288f, 0.399307489395142f, 0.801227271556854f, - 0.399076581001282f, - 0.801533281803131f, 0.398845434188843f, 0.801839113235474f, - 0.398614019155502f, - 0.802144765853882f, 0.398382395505905f, 0.802450239658356f, - 0.398150533437729f, - 0.802755534648895f, 0.397918462753296f, 0.803060650825500f, - 0.397686123847961f, - 0.803365588188171f, 0.397453576326370f, 0.803670346736908f, - 0.397220760583878f, - 0.803974866867065f, 0.396987736225128f, 0.804279267787933f, - 0.396754473447800f, - 0.804583489894867f, 0.396520972251892f, 0.804887533187866f, - 0.396287262439728f, - 0.805191397666931f, 0.396053284406662f, 0.805495083332062f, - 0.395819097757339f, - 0.805798590183258f, 0.395584672689438f, 0.806101918220520f, - 0.395350009202957f, - 0.806405067443848f, 0.395115107297897f, 0.806707978248596f, - 0.394879996776581f, - 0.807010769844055f, 0.394644618034363f, 0.807313382625580f, - 0.394409030675888f, - 0.807615816593170f, 0.394173204898834f, 0.807918012142181f, - 0.393937170505524f, - 0.808220088481903f, 0.393700867891312f, 0.808521986007690f, - 0.393464356660843f, - 0.808823645114899f, 0.393227607011795f, 0.809125185012817f, - 0.392990618944168f, - 0.809426486492157f, 0.392753422260284f, 0.809727668762207f, - 0.392515957355499f, - 0.810028612613678f, 0.392278283834457f, 0.810329377651215f, - 0.392040401697159f, - 0.810629963874817f, 0.391802251338959f, 0.810930430889130f, - 0.391563892364502f, - 0.811230659484863f, 0.391325294971466f, 0.811530709266663f, - 0.391086459159851f, - 0.811830580234528f, 0.390847414731979f, 0.812130272388458f, - 0.390608131885529f, - 0.812429726123810f, 0.390368610620499f, 0.812729060649872f, - 0.390128880739212f, - 0.813028216362000f, 0.389888882637024f, 0.813327133655548f, - 0.389648675918579f, - 0.813625931739807f, 0.389408260583878f, 0.813924491405487f, - 0.389167606830597f, - 0.814222872257233f, 0.388926714658737f, 0.814521074295044f, - 0.388685584068298f, - 0.814819097518921f, 0.388444244861603f, 0.815116941928864f, - 0.388202667236328f, - 0.815414607524872f, 0.387960851192474f, 0.815712094306946f, - 0.387718826532364f, - 0.816009342670441f, 0.387476563453674f, 0.816306471824646f, - 0.387234061956406f, - 0.816603362560272f, 0.386991351842880f, 0.816900074481964f, - 0.386748403310776f, - 0.817196667194366f, 0.386505216360092f, 0.817493021488190f, - 0.386261820793152f, - 0.817789137363434f, 0.386018186807632f, 0.818085134029388f, - 0.385774344205856f, - 0.818380951881409f, 0.385530263185501f, 0.818676531314850f, - 0.385285943746567f, - 0.818971931934357f, 0.385041415691376f, 0.819267153739929f, - 0.384796649217606f, - 0.819562196731567f, 0.384551674127579f, 0.819857060909271f, - 0.384306460618973f, - 0.820151746273041f, 0.384061008691788f, 0.820446193218231f, - 0.383815348148346f, - 0.820740520954132f, 0.383569449186325f, 0.821034610271454f, - 0.383323341608047f, - 0.821328520774841f, 0.383076995611191f, 0.821622252464294f, - 0.382830440998077f, - 0.821915745735168f, 0.382583618164063f, 0.822209119796753f, - 0.382336616516113f, - 0.822502255439758f, 0.382089376449585f, 0.822795212268829f, - 0.381841897964478f, - 0.823087990283966f, 0.381594210863113f, 0.823380589485168f, - 0.381346285343170f, - 0.823673009872437f, 0.381098151206970f, 0.823965191841125f, - 0.380849778652191f, - 0.824257194995880f, 0.380601197481155f, 0.824549019336700f, - 0.380352377891541f, - 0.824840664863586f, 0.380103349685669f, 0.825132071971893f, - 0.379854083061218f, - 0.825423359870911f, 0.379604607820511f, 0.825714409351349f, - 0.379354894161224f, - 0.826005280017853f, 0.379104942083359f, 0.826295912265778f, - 0.378854811191559f, - 0.826586425304413f, 0.378604412078857f, 0.826876699924469f, - 0.378353834152222f, - 0.827166795730591f, 0.378102988004684f, 0.827456712722778f, - 0.377851963043213f, - 0.827746450901031f, 0.377600699663162f, 0.828035950660706f, - 0.377349197864532f, - 0.828325271606445f, 0.377097487449646f, 0.828614413738251f, - 0.376845568418503f, - 0.828903317451477f, 0.376593410968781f, 0.829192101955414f, - 0.376341015100479f, - 0.829480648040771f, 0.376088410615921f, 0.829769015312195f, - 0.375835597515106f, - 0.830057144165039f, 0.375582575798035f, 0.830345153808594f, - 0.375329315662384f, - 0.830632925033569f, 0.375075817108154f, 0.830920517444611f, - 0.374822109937668f, - 0.831207871437073f, 0.374568194150925f, 0.831495106220245f, - 0.374314039945602f, - 0.831782102584839f, 0.374059677124023f, 0.832068860530853f, - 0.373805105686188f, - 0.832355499267578f, 0.373550295829773f, 0.832641899585724f, - 0.373295277357101f, - 0.832928121089935f, 0.373040050268173f, 0.833214163780212f, - 0.372784584760666f, - 0.833499968051910f, 0.372528880834579f, 0.833785593509674f, - 0.372272998094559f, - 0.834071040153503f, 0.372016876935959f, 0.834356248378754f, - 0.371760547161102f, - 0.834641277790070f, 0.371503978967667f, 0.834926128387451f, - 0.371247202157974f, - 0.835210800170898f, 0.370990216732025f, 0.835495233535767f, - 0.370732992887497f, - 0.835779488086700f, 0.370475560426712f, 0.836063504219055f, - 0.370217919349670f, - 0.836347401142120f, 0.369960039854050f, 0.836631059646606f, - 0.369701951742172f, - 0.836914479732513f, 0.369443655014038f, 0.837197780609131f, - 0.369185149669647f, - 0.837480843067169f, 0.368926405906677f, 0.837763667106628f, - 0.368667453527451f, - 0.838046371936798f, 0.368408292531967f, 0.838328838348389f, - 0.368148893117905f, - 0.838611066341400f, 0.367889285087585f, 0.838893175125122f, - 0.367629468441010f, - 0.839175045490265f, 0.367369443178177f, 0.839456677436829f, - 0.367109179496765f, - 0.839738130569458f, 0.366848707199097f, 0.840019404888153f, - 0.366588026285172f, - 0.840300500392914f, 0.366327136754990f, 0.840581357479095f, - 0.366066008806229f, - 0.840862035751343f, 0.365804702043533f, 0.841142535209656f, - 0.365543156862259f, - 0.841422796249390f, 0.365281373262405f, 0.841702818870544f, - 0.365019410848618f, - 0.841982722282410f, 0.364757210016251f, 0.842262387275696f, - 0.364494800567627f, - 0.842541813850403f, 0.364232182502747f, 0.842821121215820f, - 0.363969355821610f, - 0.843100130558014f, 0.363706320524216f, 0.843379020690918f, - 0.363443046808243f, - 0.843657672405243f, 0.363179564476013f, 0.843936145305634f, - 0.362915903329849f, - 0.844214379787445f, 0.362651973962784f, 0.844492435455322f, - 0.362387865781784f, - 0.844770252704620f, 0.362123548984528f, 0.845047891139984f, - 0.361858993768692f, - 0.845325350761414f, 0.361594229936600f, 0.845602571964264f, - 0.361329287290573f, - 0.845879614353180f, 0.361064106225967f, 0.846156477928162f, - 0.360798716545105f, - 0.846433103084564f, 0.360533088445663f, 0.846709489822388f, - 0.360267281532288f, - 0.846985757350922f, 0.360001266002655f, 0.847261726856232f, - 0.359735012054443f, - 0.847537577152252f, 0.359468549489975f, 0.847813189029694f, - 0.359201908111572f, - 0.848088562488556f, 0.358935028314590f, 0.848363757133484f, - 0.358667939901352f, - 0.848638772964478f, 0.358400642871857f, 0.848913550376892f, - 0.358133137226105f, - 0.849188148975372f, 0.357865422964096f, 0.849462509155273f, - 0.357597470283508f, - 0.849736690521240f, 0.357329338788986f, 0.850010633468628f, - 0.357060998678207f, - 0.850284397602081f, 0.356792420148849f, 0.850557923316956f, - 0.356523662805557f, - 0.850831270217896f, 0.356254696846008f, 0.851104438304901f, - 0.355985492467880f, - 0.851377367973328f, 0.355716109275818f, 0.851650118827820f, - 0.355446487665176f, - 0.851922631263733f, 0.355176687240601f, 0.852194905281067f, - 0.354906648397446f, - 0.852467060089111f, 0.354636400938034f, 0.852738916873932f, - 0.354365974664688f, - 0.853010654449463f, 0.354095309972763f, 0.853282094001770f, - 0.353824466466904f, - 0.853553414344788f, 0.353553384542465f, 0.853824436664581f, - 0.353282123804092f, - 0.854095339775085f, 0.353010624647141f, 0.854365944862366f, - 0.352738946676254f, - 0.854636430740356f, 0.352467030286789f, 0.854906618595123f, - 0.352194935083389f, - 0.855176687240601f, 0.351922631263733f, 0.855446517467499f, - 0.351650089025497f, - 0.855716109275818f, 0.351377367973328f, 0.855985522270203f, - 0.351104438304901f, - 0.856254696846008f, 0.350831300020218f, 0.856523692607880f, - 0.350557953119278f, - 0.856792449951172f, 0.350284397602081f, 0.857060968875885f, - 0.350010633468628f, - 0.857329368591309f, 0.349736660718918f, 0.857597470283508f, - 0.349462509155273f, - 0.857865393161774f, 0.349188119173050f, 0.858133137226105f, - 0.348913550376892f, - 0.858400642871857f, 0.348638743162155f, 0.858667910099030f, - 0.348363757133484f, - 0.858934998512268f, 0.348088562488556f, 0.859201908111572f, - 0.347813159227371f, - 0.859468579292297f, 0.347537547349930f, 0.859735012054443f, - 0.347261756658554f, - 0.860001266002655f, 0.346985727548599f, 0.860267281532288f, - 0.346709519624710f, - 0.860533118247986f, 0.346433073282242f, 0.860798716545105f, - 0.346156448125839f, - 0.861064076423645f, 0.345879614353180f, 0.861329257488251f, - 0.345602601766586f, - 0.861594259738922f, 0.345325350761414f, 0.861859023571014f, - 0.345047920942307f, - 0.862123548984528f, 0.344770282506943f, 0.862387895584106f, - 0.344492435455322f, - 0.862652003765106f, 0.344214379787445f, 0.862915873527527f, - 0.343936115503311f, - 0.863179564476013f, 0.343657672405243f, 0.863443076610565f, - 0.343379020690918f, - 0.863706290721893f, 0.343100160360336f, 0.863969385623932f, - 0.342821091413498f, - 0.864232182502747f, 0.342541843652725f, 0.864494800567627f, - 0.342262357473373f, - 0.864757239818573f, 0.341982692480087f, 0.865019381046295f, - 0.341702848672867f, - 0.865281403064728f, 0.341422766447067f, 0.865543127059937f, - 0.341142505407333f, - 0.865804672241211f, 0.340862035751343f, 0.866066038608551f, - 0.340581357479095f, - 0.866327106952667f, 0.340300500392914f, 0.866588056087494f, - 0.340019434690475f, - 0.866848707199097f, 0.339738160371780f, 0.867109179496765f, - 0.339456677436829f, - 0.867369413375854f, 0.339175015687943f, 0.867629468441010f, - 0.338893145322800f, - 0.867889285087585f, 0.338611096143723f, 0.868148922920227f, - 0.338328808546066f, - 0.868408262729645f, 0.338046342134476f, 0.868667483329773f, - 0.337763696908951f, - 0.868926405906677f, 0.337480813264847f, 0.869185149669647f, - 0.337197750806808f, - 0.869443655014038f, 0.336914509534836f, 0.869701981544495f, - 0.336631029844284f, - 0.869960069656372f, 0.336347371339798f, 0.870217919349670f, - 0.336063534021378f, - 0.870475590229034f, 0.335779488086700f, 0.870733022689819f, - 0.335495233535767f, - 0.870990216732025f, 0.335210770368576f, 0.871247172355652f, - 0.334926128387451f, - 0.871503949165344f, 0.334641307592392f, 0.871760547161102f, - 0.334356248378754f, - 0.872016847133636f, 0.334071010351181f, 0.872272968292236f, - 0.333785593509674f, - 0.872528910636902f, 0.333499968051910f, 0.872784554958344f, - 0.333214133977890f, - 0.873040020465851f, 0.332928121089935f, 0.873295307159424f, - 0.332641899585724f, - 0.873550295829773f, 0.332355499267578f, 0.873805105686188f, - 0.332068890333176f, - 0.874059677124023f, 0.331782072782516f, 0.874314069747925f, - 0.331495076417923f, - 0.874568223953247f, 0.331207901239395f, 0.874822139739990f, - 0.330920487642288f, - 0.875075817108154f, 0.330632925033569f, 0.875329315662384f, - 0.330345153808594f, - 0.875582575798035f, 0.330057173967361f, 0.875835597515106f, - 0.329769015312195f, - 0.876088440418243f, 0.329480648040771f, 0.876341044902802f, - 0.329192101955414f, - 0.876593410968781f, 0.328903347253799f, 0.876845538616180f, - 0.328614413738251f, - 0.877097487449646f, 0.328325271606445f, 0.877349197864532f, - 0.328035950660706f, - 0.877600669860840f, 0.327746421098709f, 0.877851963043213f, - 0.327456712722778f, - 0.878103017807007f, 0.327166795730591f, 0.878353834152222f, - 0.326876699924469f, - 0.878604412078857f, 0.326586425304413f, 0.878854811191559f, - 0.326295942068100f, - 0.879104971885681f, 0.326005280017853f, 0.879354894161224f, - 0.325714409351349f, - 0.879604578018188f, 0.325423330068588f, 0.879854083061218f, - 0.325132101774216f, - 0.880103349685669f, 0.324840664863586f, 0.880352377891541f, - 0.324549019336700f, - 0.880601167678833f, 0.324257194995880f, 0.880849778652191f, - 0.323965191841125f, - 0.881098151206970f, 0.323672980070114f, 0.881346285343170f, - 0.323380589485168f, - 0.881594181060791f, 0.323088020086288f, 0.881841897964478f, - 0.322795242071152f, - 0.882089376449585f, 0.322502255439758f, 0.882336616516113f, - 0.322209119796753f, - 0.882583618164063f, 0.321915775537491f, 0.882830440998077f, - 0.321622252464294f, - 0.883076965808868f, 0.321328520774841f, 0.883323311805725f, - 0.321034610271454f, - 0.883569478988647f, 0.320740520954132f, 0.883815348148346f, - 0.320446223020554f, - 0.884061038494110f, 0.320151746273041f, 0.884306430816650f, - 0.319857090711594f, - 0.884551644325256f, 0.319562226533890f, 0.884796679019928f, - 0.319267183542252f, - 0.885041415691376f, 0.318971961736679f, 0.885285973548889f, - 0.318676531314850f, - 0.885530233383179f, 0.318380922079086f, 0.885774314403534f, - 0.318085134029388f, - 0.886018216609955f, 0.317789167165756f, 0.886261820793152f, - 0.317492991685867f, - 0.886505246162415f, 0.317196637392044f, 0.886748373508453f, - 0.316900104284287f, - 0.886991322040558f, 0.316603392362595f, 0.887234091758728f, - 0.316306471824646f, - 0.887476563453674f, 0.316009372472763f, 0.887718796730042f, - 0.315712094306946f, - 0.887960851192474f, 0.315414607524872f, 0.888202667236328f, - 0.315116971731186f, - 0.888444244861603f, 0.314819127321243f, 0.888685584068298f, - 0.314521104097366f, - 0.888926684856415f, 0.314222872257233f, 0.889167606830597f, - 0.313924491405487f, - 0.889408230781555f, 0.313625901937485f, 0.889648675918579f, - 0.313327133655548f, - 0.889888882637024f, 0.313028186559677f, 0.890128850936890f, - 0.312729060649872f, - 0.890368640422821f, 0.312429755926132f, 0.890608131885529f, - 0.312130242586136f, - 0.890847444534302f, 0.311830550432205f, 0.891086459159851f, - 0.311530679464340f, - 0.891325294971466f, 0.311230629682541f, 0.891563892364502f, - 0.310930401086807f, - 0.891802251338959f, 0.310629993677139f, 0.892040371894836f, - 0.310329377651215f, - 0.892278313636780f, 0.310028612613678f, 0.892515957355499f, - 0.309727638959885f, - 0.892753422260284f, 0.309426486492157f, 0.892990648746490f, - 0.309125155210495f, - 0.893227577209473f, 0.308823645114899f, 0.893464326858521f, - 0.308521956205368f, - 0.893700897693634f, 0.308220088481903f, 0.893937170505524f, - 0.307918041944504f, - 0.894173204898834f, 0.307615786790848f, 0.894409060478210f, - 0.307313382625580f, - 0.894644618034363f, 0.307010769844055f, 0.894879996776581f, - 0.306708008050919f, - 0.895115137100220f, 0.306405037641525f, 0.895349979400635f, - 0.306101888418198f, - 0.895584642887115f, 0.305798590183258f, 0.895819067955017f, - 0.305495083332062f, - 0.896053314208984f, 0.305191397666931f, 0.896287262439728f, - 0.304887533187866f, - 0.896520972251892f, 0.304583519697189f, 0.896754503250122f, - 0.304279297590256f, - 0.896987736225128f, 0.303974896669388f, 0.897220790386200f, - 0.303670316934586f, - 0.897453546524048f, 0.303365558385849f, 0.897686123847961f, - 0.303060621023178f, - 0.897918462753296f, 0.302755534648895f, 0.898150563240051f, - 0.302450239658356f, - 0.898382425308228f, 0.302144765853882f, 0.898614048957825f, - 0.301839113235474f, - 0.898845434188843f, 0.301533311605453f, 0.899076581001282f, - 0.301227301359177f, - 0.899307489395142f, 0.300921112298965f, 0.899538159370422f, - 0.300614774227142f, - 0.899768650531769f, 0.300308227539063f, 0.899998843669891f, - 0.300001531839371f, - 0.900228857994080f, 0.299694657325745f, 0.900458574295044f, - 0.299387603998184f, - 0.900688111782074f, 0.299080342054367f, 0.900917351245880f, - 0.298772931098938f, - 0.901146411895752f, 0.298465341329575f, 0.901375174522400f, - 0.298157602548599f, - 0.901603758335114f, 0.297849655151367f, 0.901832103729248f, - 0.297541528940201f, - 0.902060210704803f, 0.297233253717422f, 0.902288019657135f, - 0.296924799680710f, - 0.902515649795532f, 0.296616137027740f, 0.902743041515350f, - 0.296307325363159f, - 0.902970194816589f, 0.295998334884644f, 0.903197109699249f, - 0.295689195394516f, - 0.903423786163330f, 0.295379847288132f, 0.903650224208832f, - 0.295070350170136f, - 0.903876423835754f, 0.294760644435883f, 0.904102385044098f, - 0.294450789690018f, - 0.904328107833862f, 0.294140785932541f, 0.904553592205048f, - 0.293830573558807f, - 0.904778838157654f, 0.293520182371140f, 0.905003845691681f, - 0.293209642171860f, - 0.905228614807129f, 0.292898923158646f, 0.905453145503998f, - 0.292588025331497f, - 0.905677437782288f, 0.292276978492737f, 0.905901491641998f, - 0.291965723037720f, - 0.906125307083130f, 0.291654318571091f, 0.906348884105682f, - 0.291342735290527f, - 0.906572222709656f, 0.291031002998352f, 0.906795322895050f, - 0.290719062089920f, - 0.907018184661865f, 0.290406972169876f, 0.907240808010101f, - 0.290094703435898f, - 0.907463192939758f, 0.289782285690308f, 0.907685279846191f, - 0.289469659328461f, - 0.907907187938690f, 0.289156883955002f, 0.908128857612610f, - 0.288843959569931f, - 0.908350288867950f, 0.288530826568604f, 0.908571481704712f, - 0.288217544555664f, - 0.908792436122894f, 0.287904083728790f, 0.909013092517853f, - 0.287590473890305f, - 0.909233570098877f, 0.287276685237885f, 0.909453809261322f, - 0.286962717771530f, - 0.909673750400543f, 0.286648571491241f, 0.909893512725830f, - 0.286334276199341f, - 0.910112977027893f, 0.286019802093506f, 0.910332262516022f, - 0.285705178976059f, - 0.910551249980927f, 0.285390377044678f, 0.910769999027252f, - 0.285075396299362f, - 0.910988569259644f, 0.284760266542435f, 0.911206841468811f, - 0.284444957971573f, - 0.911424875259399f, 0.284129470586777f, 0.911642670631409f, - 0.283813834190369f, - 0.911860227584839f, 0.283498018980026f, 0.912077546119690f, - 0.283182054758072f, - 0.912294626235962f, 0.282865911722183f, 0.912511467933655f, - 0.282549589872360f, - 0.912728071212769f, 0.282233119010925f, 0.912944436073303f, - 0.281916469335556f, - 0.913160502910614f, 0.281599670648575f, 0.913376390933990f, - 0.281282693147659f, - 0.913592040538788f, 0.280965566635132f, 0.913807392120361f, - 0.280648261308670f, - 0.914022505283356f, 0.280330777168274f, 0.914237439632416f, - 0.280013144016266f, - 0.914452075958252f, 0.279695361852646f, 0.914666473865509f, - 0.279377400875092f, - 0.914880633354187f, 0.279059261083603f, 0.915094554424286f, - 0.278740972280502f, - 0.915308177471161f, 0.278422504663467f, 0.915521621704102f, - 0.278103888034821f, - 0.915734827518463f, 0.277785122394562f, 0.915947735309601f, - 0.277466177940369f, - 0.916160404682159f, 0.277147054672241f, 0.916372895240784f, - 0.276827782392502f, - 0.916585087776184f, 0.276508361101151f, 0.916797041893005f, - 0.276188760995865f, - 0.917008757591248f, 0.275868982076645f, 0.917220234870911f, - 0.275549083948135f, - 0.917431414127350f, 0.275228977203369f, 0.917642414569855f, - 0.274908751249313f, - 0.917853116989136f, 0.274588316679001f, 0.918063640594482f, - 0.274267762899399f, - 0.918273866176605f, 0.273947030305862f, 0.918483853340149f, - 0.273626148700714f, - 0.918693602085114f, 0.273305088281631f, 0.918903112411499f, - 0.272983878850937f, - 0.919112324714661f, 0.272662490606308f, 0.919321358203888f, - 0.272340953350067f, - 0.919530093669891f, 0.272019267082214f, 0.919738650321960f, - 0.271697402000427f, - 0.919946908950806f, 0.271375387907028f, 0.920154929161072f, - 0.271053224802017f, - 0.920362710952759f, 0.270730882883072f, 0.920570194721222f, - 0.270408391952515f, - 0.920777499675751f, 0.270085722208023f, 0.920984506607056f, - 0.269762933254242f, - 0.921191275119781f, 0.269439965486526f, 0.921397805213928f, - 0.269116818904877f, - 0.921604096889496f, 0.268793523311615f, 0.921810150146484f, - 0.268470078706741f, - 0.922015964984894f, 0.268146485090256f, 0.922221481800079f, - 0.267822742462158f, - 0.922426760196686f, 0.267498821020126f, 0.922631800174713f, - 0.267174720764160f, - 0.922836601734161f, 0.266850501298904f, 0.923041164875031f, - 0.266526103019714f, - 0.923245489597321f, 0.266201555728912f, 0.923449516296387f, - 0.265876859426498f, - 0.923653304576874f, 0.265552014112473f, 0.923856854438782f, - 0.265226989984512f, - 0.924060165882111f, 0.264901816844940f, 0.924263238906860f, - 0.264576494693756f, - 0.924466013908386f, 0.264250993728638f, 0.924668610095978f, - 0.263925373554230f, - 0.924870908260345f, 0.263599574565887f, 0.925072908401489f, - 0.263273626565933f, - 0.925274729728699f, 0.262947499752045f, 0.925476312637329f, - 0.262621253728867f, - 0.925677597522736f, 0.262294828891754f, 0.925878643989563f, - 0.261968284845352f, - 0.926079452037811f, 0.261641561985016f, 0.926280021667480f, - 0.261314690113068f, - 0.926480293273926f, 0.260987639427185f, 0.926680326461792f, - 0.260660469532013f, - 0.926880121231079f, 0.260333120822906f, 0.927079677581787f, - 0.260005623102188f, - 0.927278995513916f, 0.259678006172180f, 0.927478015422821f, - 0.259350210428238f, - 0.927676856517792f, 0.259022265672684f, 0.927875399589539f, - 0.258694142103195f, - 0.928073644638062f, 0.258365899324417f, 0.928271710872650f, - 0.258037507534027f, - 0.928469479084015f, 0.257708936929703f, 0.928667008876801f, - 0.257380217313766f, - 0.928864300251007f, 0.257051378488541f, 0.929061353206635f, - 0.256722360849380f, - 0.929258108139038f, 0.256393194198608f, 0.929454624652863f, - 0.256063878536224f, - 0.929650902748108f, 0.255734413862228f, 0.929846942424774f, - 0.255404800176620f, - 0.930042684078217f, 0.255075037479401f, 0.930238187313080f, - 0.254745125770569f, - 0.930433452129364f, 0.254415065050125f, 0.930628478527069f, - 0.254084855318069f, - 0.930823206901550f, 0.253754496574402f, 0.931017756462097f, - 0.253423988819122f, - 0.931211948394775f, 0.253093332052231f, 0.931405961513519f, - 0.252762526273727f, - 0.931599736213684f, 0.252431541681290f, 0.931793212890625f, - 0.252100437879562f, - 0.931986451148987f, 0.251769185066223f, 0.932179391384125f, - 0.251437783241272f, - 0.932372152805328f, 0.251106232404709f, 0.932564616203308f, - 0.250774532556534f, - 0.932756841182709f, 0.250442683696747f, 0.932948768138886f, - 0.250110685825348f, - 0.933140456676483f, 0.249778553843498f, 0.933331906795502f, - 0.249446272850037f, - 0.933523118495941f, 0.249113827943802f, 0.933714091777802f, - 0.248781248927116f, - 0.933904767036438f, 0.248448520898819f, 0.934095203876495f, - 0.248115643858910f, - 0.934285342693329f, 0.247782632708550f, 0.934475243091583f, - 0.247449472546577f, - 0.934664964675903f, 0.247116148471832f, 0.934854328632355f, - 0.246782705187798f, - 0.935043513774872f, 0.246449097990990f, 0.935232400894165f, - 0.246115356683731f, - 0.935421049594879f, 0.245781451463699f, 0.935609400272369f, - 0.245447427034378f, - 0.935797572135925f, 0.245113238692284f, 0.935985386371613f, - 0.244778916239738f, - 0.936173021793365f, 0.244444444775581f, 0.936360359191895f, - 0.244109839200974f, - 0.936547517776489f, 0.243775084614754f, 0.936734318733215f, - 0.243440181016922f, - 0.936920940876007f, 0.243105143308640f, 0.937107264995575f, - 0.242769956588745f, - 0.937293350696564f, 0.242434620857239f, 0.937479138374329f, - 0.242099151015282f, - 0.937664687633514f, 0.241763532161713f, 0.937849998474121f, - 0.241427779197693f, - 0.938035070896149f, 0.241091892123222f, 0.938219845294952f, - 0.240755841135979f, - 0.938404381275177f, 0.240419670939446f, 0.938588619232178f, - 0.240083336830139f, - 0.938772618770599f, 0.239746883511543f, 0.938956379890442f, - 0.239410281181335f, - 0.939139902591705f, 0.239073529839516f, 0.939323127269745f, - 0.238736644387245f, - 0.939506113529205f, 0.238399609923363f, 0.939688861370087f, - 0.238062441349030f, - 0.939871311187744f, 0.237725138664246f, 0.940053522586823f, - 0.237387686967850f, - 0.940235435962677f, 0.237050101161003f, 0.940417110919952f, - 0.236712381243706f, - 0.940598547458649f, 0.236374512314796f, 0.940779745578766f, - 0.236036509275436f, - 0.940960645675659f, 0.235698372125626f, 0.941141307353973f, - 0.235360085964203f, - 0.941321671009064f, 0.235021665692329f, 0.941501796245575f, - 0.234683111310005f, - 0.941681683063507f, 0.234344407916069f, 0.941861271858215f, - 0.234005570411682f, - 0.942040622234344f, 0.233666598796844f, 0.942219734191895f, - 0.233327493071556f, - 0.942398548126221f, 0.232988253235817f, 0.942577123641968f, - 0.232648864388466f, - 0.942755401134491f, 0.232309341430664f, 0.942933499813080f, - 0.231969684362412f, - 0.943111240863800f, 0.231629893183708f, 0.943288803100586f, - 0.231289967894554f, - 0.943466067314148f, 0.230949893593788f, 0.943643093109131f, - 0.230609700083733f, - 0.943819820880890f, 0.230269357562065f, 0.943996310234070f, - 0.229928880929947f, - 0.944172501564026f, 0.229588270187378f, 0.944348454475403f, - 0.229247525334358f, - 0.944524168968201f, 0.228906646370888f, 0.944699645042419f, - 0.228565633296967f, - 0.944874763488770f, 0.228224486112595f, 0.945049703121185f, - 0.227883204817772f, - 0.945224344730377f, 0.227541789412498f, 0.945398747920990f, - 0.227200239896774f, - 0.945572853088379f, 0.226858556270599f, 0.945746779441834f, - 0.226516738533974f, - 0.945920348167419f, 0.226174786686897f, 0.946093678474426f, - 0.225832715630531f, - 0.946266770362854f, 0.225490495562553f, 0.946439623832703f, - 0.225148141384125f, - 0.946612179279327f, 0.224805667996407f, 0.946784436702728f, - 0.224463045597076f, - 0.946956455707550f, 0.224120303988457f, 0.947128236293793f, - 0.223777428269386f, - 0.947299718856812f, 0.223434418439865f, 0.947470963001251f, - 0.223091274499893f, - 0.947641968727112f, 0.222748011350632f, 0.947812676429749f, - 0.222404599189758f, - 0.947983145713806f, 0.222061067819595f, 0.948153316974640f, - 0.221717402338982f, - 0.948323249816895f, 0.221373617649078f, 0.948492884635925f, - 0.221029683947563f, - 0.948662281036377f, 0.220685631036758f, 0.948831439018250f, - 0.220341444015503f, - 0.949000298976898f, 0.219997137784958f, 0.949168920516968f, - 0.219652697443962f, - 0.949337244033813f, 0.219308122992516f, 0.949505329132080f, - 0.218963414430618f, - 0.949673116207123f, 0.218618586659431f, 0.949840664863586f, - 0.218273624777794f, - 0.950007975101471f, 0.217928543686867f, 0.950174987316132f, - 0.217583328485489f, - 0.950341701507568f, 0.217237979173660f, 0.950508177280426f, - 0.216892510652542f, - 0.950674414634705f, 0.216546908020973f, 0.950840353965759f, - 0.216201186180115f, - 0.951006054878235f, 0.215855330228806f, 0.951171517372131f, - 0.215509355068207f, - 0.951336681842804f, 0.215163245797157f, 0.951501548290253f, - 0.214817002415657f, - 0.951666176319122f, 0.214470639824867f, 0.951830565929413f, - 0.214124158024788f, - 0.951994657516479f, 0.213777542114258f, 0.952158451080322f, - 0.213430806994438f, - 0.952322065830231f, 0.213083937764168f, 0.952485322952271f, - 0.212736949324608f, - 0.952648401260376f, 0.212389841675758f, 0.952811121940613f, - 0.212042599916458f, - 0.952973663806915f, 0.211695238947868f, 0.953135907649994f, - 0.211347743868828f, - 0.953297853469849f, 0.211000129580498f, 0.953459560871124f, - 0.210652396082878f, - 0.953620970249176f, 0.210304543375969f, 0.953782141208649f, - 0.209956556558609f, - 0.953943073749542f, 0.209608450531960f, 0.954103708267212f, - 0.209260210394859f, - 0.954264044761658f, 0.208911851048470f, 0.954424142837524f, - 0.208563387393951f, - 0.954584002494812f, 0.208214774727821f, 0.954743564128876f, - 0.207866057753563f, - 0.954902827739716f, 0.207517206668854f, 0.955061912536621f, - 0.207168251276016f, - 0.955220639705658f, 0.206819161772728f, 0.955379128456116f, - 0.206469938158989f, - 0.955537378787994f, 0.206120610237122f, 0.955695331096649f, - 0.205771163105965f, - 0.955853044986725f, 0.205421581864357f, 0.956010460853577f, - 0.205071896314621f, - 0.956167578697205f, 0.204722076654434f, 0.956324458122253f, - 0.204372137784958f, - 0.956481099128723f, 0.204022079706192f, 0.956637442111969f, - 0.203671902418137f, - 0.956793546676636f, 0.203321605920792f, 0.956949353218079f, - 0.202971190214157f, - 0.957104861736298f, 0.202620655298233f, 0.957260131835938f, - 0.202270001173019f, - 0.957415163516998f, 0.201919227838516f, 0.957569897174835f, - 0.201568335294724f, - 0.957724332809448f, 0.201217323541641f, 0.957878530025482f, - 0.200866192579269f, - 0.958032488822937f, 0.200514942407608f, 0.958186149597168f, - 0.200163587927818f, - 0.958339512348175f, 0.199812099337578f, 0.958492636680603f, - 0.199460506439209f, - 0.958645522594452f, 0.199108779430389f, 0.958798050880432f, - 0.198756948113441f, - 0.958950400352478f, 0.198404997587204f, 0.959102451801300f, - 0.198052927851677f, - 0.959254205226898f, 0.197700738906860f, 0.959405720233917f, - 0.197348430752754f, - 0.959556937217712f, 0.196996018290520f, 0.959707856178284f, - 0.196643486618996f, - 0.959858596324921f, 0.196290835738182f, 0.960008978843689f, - 0.195938065648079f, - 0.960159122943878f, 0.195585191249847f, 0.960309028625488f, - 0.195232197642326f, - 0.960458636283875f, 0.194879084825516f, 0.960607945919037f, - 0.194525867700577f, - 0.960757017135620f, 0.194172516465187f, 0.960905790328979f, - 0.193819075822830f, - 0.961054325103760f, 0.193465501070023f, 0.961202561855316f, - 0.193111822009087f, - 0.961350560188293f, 0.192758023738861f, 0.961498260498047f, - 0.192404121160507f, - 0.961645722389221f, 0.192050099372864f, 0.961792886257172f, - 0.191695958375931f, - 0.961939752101898f, 0.191341713070869f, 0.962086379528046f, - 0.190987363457680f, - 0.962232708930969f, 0.190632879734039f, 0.962378799915314f, - 0.190278306603432f, - 0.962524592876434f, 0.189923599362373f, 0.962670147418976f, - 0.189568802714348f, - 0.962815403938293f, 0.189213871955872f, 0.962960422039032f, - 0.188858851790428f, - 0.963105142116547f, 0.188503712415695f, 0.963249564170837f, - 0.188148453831673f, - 0.963393747806549f, 0.187793090939522f, 0.963537633419037f, - 0.187437608838081f, - 0.963681280612946f, 0.187082037329674f, 0.963824629783630f, - 0.186726331710815f, - 0.963967680931091f, 0.186370536684990f, 0.964110493659973f, - 0.186014622449875f, - 0.964253067970276f, 0.185658603906631f, 0.964395284652710f, - 0.185302466154099f, - 0.964537262916565f, 0.184946224093437f, 0.964679002761841f, - 0.184589877724648f, - 0.964820444583893f, 0.184233412146568f, 0.964961588382721f, - 0.183876842260361f, - 0.965102493762970f, 0.183520168066025f, 0.965243160724640f, - 0.183163389563560f, - 0.965383470058441f, 0.182806491851807f, 0.965523540973663f, - 0.182449504733086f, - 0.965663373470306f, 0.182092398405075f, 0.965802907943726f, - 0.181735187768936f, - 0.965942144393921f, 0.181377857923508f, 0.966081082820892f, - 0.181020438671112f, - 0.966219842433929f, 0.180662900209427f, 0.966358244419098f, - 0.180305257439613f, - 0.966496407985687f, 0.179947525262833f, 0.966634273529053f, - 0.179589673876762f, - 0.966771900653839f, 0.179231703281403f, 0.966909229755402f, - 0.178873643279076f, - 0.967046260833740f, 0.178515478968620f, 0.967183053493500f, - 0.178157210350037f, - 0.967319548130035f, 0.177798837423325f, 0.967455804347992f, - 0.177440345287323f, - 0.967591762542725f, 0.177081763744354f, 0.967727422714233f, - 0.176723077893257f, - 0.967862844467163f, 0.176364272832870f, 0.967997968196869f, - 0.176005378365517f, - 0.968132853507996f, 0.175646379590034f, 0.968267440795898f, - 0.175287276506424f, - 0.968401730060577f, 0.174928069114685f, 0.968535780906677f, - 0.174568757414818f, - 0.968669533729553f, 0.174209341406822f, 0.968802988529205f, - 0.173849821090698f, - 0.968936204910278f, 0.173490211367607f, 0.969069123268127f, - 0.173130482435226f, - 0.969201743602753f, 0.172770664095879f, 0.969334125518799f, - 0.172410741448402f, - 0.969466269016266f, 0.172050714492798f, 0.969598054885864f, - 0.171690583229065f, - 0.969729602336884f, 0.171330362558365f, 0.969860911369324f, - 0.170970037579536f, - 0.969991862773895f, 0.170609608292580f, 0.970122575759888f, - 0.170249074697495f, - 0.970253050327301f, 0.169888436794281f, 0.970383226871490f, - 0.169527709484100f, - 0.970513105392456f, 0.169166877865791f, 0.970642685890198f, - 0.168805956840515f, - 0.970772027969360f, 0.168444931507111f, 0.970901072025299f, - 0.168083801865578f, - 0.971029877662659f, 0.167722567915916f, 0.971158385276794f, - 0.167361244559288f, - 0.971286594867706f, 0.166999831795692f, 0.971414566040039f, - 0.166638299822807f, - 0.971542239189148f, 0.166276678442955f, 0.971669614315033f, - 0.165914967656136f, - 0.971796751022339f, 0.165553152561188f, 0.971923589706421f, - 0.165191248059273f, - 0.972050130367279f, 0.164829224348068f, 0.972176432609558f, - 0.164467126131058f, - 0.972302436828613f, 0.164104923605919f, 0.972428143024445f, - 0.163742616772652f, - 0.972553610801697f, 0.163380220532417f, 0.972678780555725f, - 0.163017734885216f, - 0.972803652286530f, 0.162655144929886f, 0.972928285598755f, - 0.162292465567589f, - 0.973052620887756f, 0.161929681897163f, 0.973176658153534f, - 0.161566808819771f, - 0.973300457000732f, 0.161203846335411f, 0.973423957824707f, - 0.160840779542923f, - 0.973547160625458f, 0.160477623343468f, 0.973670125007629f, - 0.160114362835884f, - 0.973792791366577f, 0.159751012921333f, 0.973915159702301f, - 0.159387573599815f, - 0.974037289619446f, 0.159024044871330f, 0.974159121513367f, - 0.158660411834717f, - 0.974280655384064f, 0.158296689391136f, 0.974401950836182f, - 0.157932877540588f, - 0.974522948265076f, 0.157568961381912f, 0.974643647670746f, - 0.157204970717430f, - 0.974764108657837f, 0.156840875744820f, 0.974884271621704f, - 0.156476691365242f, - 0.975004136562347f, 0.156112402677536f, 0.975123703479767f, - 0.155748039484024f, - 0.975243031978607f, 0.155383571982384f, 0.975362062454224f, - 0.155019029974937f, - 0.975480854511261f, 0.154654383659363f, 0.975599288940430f, - 0.154289647936821f, - 0.975717484951019f, 0.153924822807312f, 0.975835442543030f, - 0.153559908270836f, - 0.975953042507172f, 0.153194904327393f, 0.976070404052734f, - 0.152829796075821f, - 0.976187527179718f, 0.152464613318443f, 0.976304292678833f, - 0.152099341154099f, - 0.976420819759369f, 0.151733979582787f, 0.976537048816681f, - 0.151368513703346f, - 0.976653039455414f, 0.151002973318100f, 0.976768672466278f, - 0.150637343525887f, - 0.976884067058563f, 0.150271624326706f, 0.976999223232269f, - 0.149905815720558f, - 0.977114021778107f, 0.149539917707443f, 0.977228581905365f, - 0.149173930287361f, - 0.977342903614044f, 0.148807853460312f, 0.977456867694855f, - 0.148441687226295f, - 0.977570593357086f, 0.148075446486473f, 0.977684020996094f, - 0.147709101438522f, - 0.977797150611877f, 0.147342681884766f, 0.977910041809082f, - 0.146976172924042f, - 0.978022634983063f, 0.146609574556351f, 0.978134930133820f, - 0.146242901682854f, - 0.978246986865997f, 0.145876124501228f, 0.978358685970306f, - 0.145509272813797f, - 0.978470146656036f, 0.145142331719399f, 0.978581368923187f, - 0.144775316119194f, - 0.978692233562469f, 0.144408211112022f, 0.978802859783173f, - 0.144041016697884f, - 0.978913187980652f, 0.143673732876778f, 0.979023277759552f, - 0.143306359648705f, - 0.979133009910584f, 0.142938911914825f, 0.979242503643036f, - 0.142571389675140f, - 0.979351758956909f, 0.142203763127327f, 0.979460656642914f, - 0.141836062073708f, - 0.979569315910339f, 0.141468286514282f, 0.979677677154541f, - 0.141100421547890f, - 0.979785740375519f, 0.140732467174530f, 0.979893565177917f, - 0.140364438295364f, - 0.980001091957092f, 0.139996320009232f, 0.980108320713043f, - 0.139628127217293f, - 0.980215251445770f, 0.139259845018387f, 0.980321943759918f, - 0.138891488313675f, - 0.980428338050842f, 0.138523042201996f, 0.980534434318542f, - 0.138154521584511f, - 0.980640232563019f, 0.137785911560059f, 0.980745792388916f, - 0.137417227029800f, - 0.980851054191589f, 0.137048453092575f, 0.980956017971039f, - 0.136679604649544f, - 0.981060683727264f, 0.136310681700706f, 0.981165111064911f, - 0.135941669344902f, - 0.981269240379334f, 0.135572582483292f, 0.981373071670532f, - 0.135203406214714f, - 0.981476604938507f, 0.134834155440331f, 0.981579899787903f, - 0.134464830160141f, - 0.981682896614075f, 0.134095430374146f, 0.981785595417023f, - 0.133725941181183f, - 0.981888055801392f, 0.133356377482414f, 0.981990158557892f, - 0.132986739277840f, - 0.982092022895813f, 0.132617011666298f, 0.982193589210510f, - 0.132247209548950f, - 0.982294917106628f, 0.131877332925797f, 0.982395887374878f, - 0.131507381796837f, - 0.982496619224548f, 0.131137356162071f, 0.982597053050995f, - 0.130767241120338f, - 0.982697248458862f, 0.130397051572800f, 0.982797086238861f, - 0.130026802420616f, - 0.982896685600281f, 0.129656463861465f, 0.982995986938477f, - 0.129286035895348f, - 0.983094990253448f, 0.128915548324585f, 0.983193755149841f, - 0.128544986248016f, - 0.983292162418365f, 0.128174334764481f, 0.983390331268311f, - 0.127803623676300f, - 0.983488261699677f, 0.127432823181152f, 0.983585834503174f, - 0.127061963081360f, - 0.983683168888092f, 0.126691013574600f, 0.983780145645142f, - 0.126320004463196f, - 0.983876943588257f, 0.125948905944824f, 0.983973383903503f, - 0.125577747821808f, - 0.984069526195526f, 0.125206500291824f, 0.984165430068970f, - 0.124835193157196f, - 0.984261035919189f, 0.124463804066181f, 0.984356343746185f, - 0.124092340469360f, - 0.984451413154602f, 0.123720809817314f, 0.984546124935150f, - 0.123349204659462f, - 0.984640598297119f, 0.122977524995804f, 0.984734773635864f, - 0.122605770826340f, - 0.984828710556030f, 0.122233949601650f, 0.984922289848328f, - 0.121862053871155f, - 0.985015630722046f, 0.121490091085434f, 0.985108673572540f, - 0.121118053793907f, - 0.985201418399811f, 0.120745941996574f, 0.985293865203857f, - 0.120373763144016f, - 0.985386073589325f, 0.120001509785652f, 0.985477983951569f, - 0.119629189372063f, - 0.985569596290588f, 0.119256794452667f, 0.985660910606384f, - 0.118884332478046f, - 0.985751926898956f, 0.118511803448200f, 0.985842704772949f, - 0.118139199912548f, - 0.985933184623718f, 0.117766529321671f, 0.986023366451263f, - 0.117393791675568f, - 0.986113250255585f, 0.117020979523659f, 0.986202836036682f, - 0.116648100316525f, - 0.986292183399200f, 0.116275154054165f, 0.986381232738495f, - 0.115902140736580f, - 0.986469984054565f, 0.115529052913189f, 0.986558437347412f, - 0.115155905485153f, - 0.986646652221680f, 0.114782683551311f, 0.986734509468079f, - 0.114409394562244f, - 0.986822128295898f, 0.114036038517952f, 0.986909449100494f, - 0.113662622869015f, - 0.986996471881866f, 0.113289132714272f, 0.987083256244659f, - 0.112915575504303f, - 0.987169682979584f, 0.112541958689690f, 0.987255871295929f, - 0.112168267369270f, - 0.987341761589050f, 0.111794516444206f, 0.987427353858948f, - 0.111420698463917f, - 0.987512648105621f, 0.111046813428402f, 0.987597703933716f, - 0.110672861337662f, - 0.987682461738586f, 0.110298842191696f, 0.987766921520233f, - 0.109924763441086f, - 0.987851083278656f, 0.109550617635250f, 0.987934947013855f, - 0.109176412224770f, - 0.988018512725830f, 0.108802139759064f, 0.988101840019226f, - 0.108427800238132f, - 0.988184869289398f, 0.108053401112556f, 0.988267600536346f, - 0.107678934931755f, - 0.988350033760071f, 0.107304409146309f, 0.988432228565216f, - 0.106929816305637f, - 0.988514065742493f, 0.106555156409740f, 0.988595664501190f, - 0.106180444359779f, - 0.988676965236664f, 0.105805665254593f, 0.988757967948914f, - 0.105430819094181f, - 0.988838672637939f, 0.105055920779705f, 0.988919138908386f, - 0.104680955410004f, - 0.988999247550964f, 0.104305922985077f, 0.989079117774963f, - 0.103930838406086f, - 0.989158689975739f, 0.103555686771870f, 0.989237964153290f, - 0.103180475533009f, - 0.989316940307617f, 0.102805204689503f, 0.989395678043365f, - 0.102429874241352f, - 0.989474058151245f, 0.102054484188557f, 0.989552199840546f, - 0.101679034531116f, - 0.989630043506622f, 0.101303517818451f, 0.989707589149475f, - 0.100927948951721f, - 0.989784896373749f, 0.100552320480347f, 0.989861845970154f, - 0.100176624953747f, - 0.989938557147980f, 0.099800877273083f, 0.990014970302582f, - 0.099425069987774f, - 0.990091085433960f, 0.099049203097820f, 0.990166902542114f, - 0.098673284053802f, - 0.990242421627045f, 0.098297297954559f, 0.990317702293396f, - 0.097921259701252f, - 0.990392625331879f, 0.097545161843300f, 0.990467309951782f, - 0.097169004380703f, - 0.990541696548462f, 0.096792794764042f, 0.990615785121918f, - 0.096416525542736f, - 0.990689575672150f, 0.096040196716785f, 0.990763127803802f, - 0.095663815736771f, - 0.990836322307587f, 0.095287375152111f, 0.990909278392792f, - 0.094910882413387f, - 0.990981936454773f, 0.094534330070019f, 0.991054296493530f, - 0.094157725572586f, - 0.991126358509064f, 0.093781061470509f, 0.991198182106018f, - 0.093404345214367f, - 0.991269648075104f, 0.093027576804161f, 0.991340875625610f, - 0.092650748789310f, - 0.991411805152893f, 0.092273868620396f, 0.991482377052307f, - 0.091896936297417f, - 0.991552770137787f, 0.091519944369793f, 0.991622805595398f, - 0.091142900288105f, - 0.991692543029785f, 0.090765804052353f, 0.991762042045593f, - 0.090388655662537f, - 0.991831183433533f, 0.090011447668076f, 0.991900086402893f, - 0.089634194970131f, - 0.991968691349030f, 0.089256882667542f, 0.992036998271942f, - 0.088879525661469f, - 0.992105066776276f, 0.088502109050751f, 0.992172777652740f, - 0.088124647736549f, - 0.992240250110626f, 0.087747126817703f, 0.992307364940643f, - 0.087369553744793f, - 0.992374241352081f, 0.086991935968399f, 0.992440819740295f, - 0.086614266037941f, - 0.992507100105286f, 0.086236543953419f, 0.992573142051697f, - 0.085858769714832f, - 0.992638826370239f, 0.085480943322182f, 0.992704212665558f, - 0.085103072226048f, - 0.992769360542297f, 0.084725148975849f, 0.992834210395813f, - 0.084347173571587f, - 0.992898762226105f, 0.083969146013260f, 0.992963016033173f, - 0.083591073751450f, - 0.993026971817017f, 0.083212949335575f, 0.993090689182281f, - 0.082834780216217f, - 0.993154048919678f, 0.082456558942795f, 0.993217170238495f, - 0.082078292965889f, - 0.993279933929443f, 0.081699974834919f, 0.993342459201813f, - 0.081321612000465f, - 0.993404686450958f, 0.080943197011948f, 0.993466615676880f, - 0.080564737319946f, - 0.993528306484222f, 0.080186225473881f, 0.993589639663696f, - 0.079807676374912f, - 0.993650734424591f, 0.079429075121880f, 0.993711471557617f, - 0.079050421714783f, - 0.993771970272064f, 0.078671731054783f, 0.993832170963287f, - 0.078292988240719f, - 0.993892073631287f, 0.077914200723171f, 0.993951678276062f, - 0.077535368502140f, - 0.994010984897614f, 0.077156484127045f, 0.994070053100586f, - 0.076777562499046f, - 0.994128763675690f, 0.076398596167564f, 0.994187235832214f, - 0.076019577682018f, - 0.994245409965515f, 0.075640521943569f, 0.994303286075592f, - 0.075261414051056f, - 0.994360864162445f, 0.074882268905640f, 0.994418144226074f, - 0.074503071606159f, - 0.994475126266479f, 0.074123837053776f, 0.994531810283661f, - 0.073744557797909f, - 0.994588255882263f, 0.073365233838558f, 0.994644403457642f, - 0.072985872626305f, - 0.994700193405151f, 0.072606459259987f, 0.994755744934082f, - 0.072227008640766f, - 0.994810998439789f, 0.071847513318062f, 0.994865953922272f, - 0.071467980742455f, - 0.994920611381531f, 0.071088403463364f, 0.994975030422211f, - 0.070708781480789f, - 0.995029091835022f, 0.070329122245312f, 0.995082914829254f, - 0.069949418306351f, - 0.995136380195618f, 0.069569669663906f, 0.995189607143402f, - 0.069189883768559f, - 0.995242536067963f, 0.068810060620308f, 0.995295166969299f, - 0.068430192768574f, - 0.995347499847412f, 0.068050287663937f, 0.995399534702301f, - 0.067670337855816f, - 0.995451331138611f, 0.067290350794792f, 0.995502769947052f, - 0.066910326480865f, - 0.995553970336914f, 0.066530264914036f, 0.995604813098907f, - 0.066150158643723f, - 0.995655417442322f, 0.065770015120506f, 0.995705723762512f, - 0.065389834344387f, - 0.995755732059479f, 0.065009608864784f, 0.995805442333221f, - 0.064629353582859f, - 0.995854854583740f, 0.064249053597450f, 0.995904028415680f, - 0.063868723809719f, - 0.995952844619751f, 0.063488349318504f, 0.996001422405243f, - 0.063107937574387f, - 0.996049642562866f, 0.062727488577366f, 0.996097624301910f, - 0.062347009778023f, - 0.996145308017731f, 0.061966486275196f, 0.996192693710327f, - 0.061585929244757f, - 0.996239781379700f, 0.061205338686705f, 0.996286571025848f, - 0.060824707150459f, - 0.996333062648773f, 0.060444042086601f, 0.996379256248474f, - 0.060063343495131f, - 0.996425211429596f, 0.059682607650757f, 0.996470808982849f, - 0.059301838278770f, - 0.996516168117523f, 0.058921031653881f, 0.996561229228973f, - 0.058540191501379f, - 0.996605992317200f, 0.058159314095974f, 0.996650457382202f, - 0.057778406888247f, - 0.996694624423981f, 0.057397462427616f, 0.996738493442535f, - 0.057016488164663f, - 0.996782064437866f, 0.056635476648808f, 0.996825337409973f, - 0.056254431605339f, - 0.996868371963501f, 0.055873356759548f, 0.996911048889160f, - 0.055492244660854f, - 0.996953487396240f, 0.055111102759838f, 0.996995627880096f, - 0.054729927331209f, - 0.997037410736084f, 0.054348722100258f, 0.997078955173492f, - 0.053967483341694f, - 0.997120201587677f, 0.053586211055517f, 0.997161149978638f, - 0.053204908967018f, - 0.997201859951019f, 0.052823577076197f, 0.997242212295532f, - 0.052442211657763f, - 0.997282266616821f, 0.052060816437006f, 0.997322082519531f, - 0.051679391413927f, - 0.997361540794373f, 0.051297932863235f, 0.997400760650635f, - 0.050916448235512f, - 0.997439682483673f, 0.050534930080175f, 0.997478306293488f, - 0.050153385847807f, - 0.997516572475433f, 0.049771808087826f, 0.997554600238800f, - 0.049390204250813f, - 0.997592389583588f, 0.049008570611477f, 0.997629821300507f, - 0.048626907169819f, - 0.997666954994202f, 0.048245213925838f, 0.997703790664673f, - 0.047863494604826f, - 0.997740387916565f, 0.047481749206781f, 0.997776627540588f, - 0.047099970281124f, - 0.997812628746033f, 0.046718169003725f, 0.997848331928253f, - 0.046336337924004f, - 0.997883677482605f, 0.045954477041960f, 0.997918784618378f, - 0.045572593808174f, - 0.997953593730927f, 0.045190680772066f, 0.997988104820251f, - 0.044808741658926f, - 0.998022377490997f, 0.044426776468754f, 0.998056292533875f, - 0.044044785201550f, - 0.998089909553528f, 0.043662767857313f, 0.998123228549957f, - 0.043280724436045f, - 0.998156309127808f, 0.042898654937744f, 0.998189091682434f, - 0.042516563087702f, - 0.998221516609192f, 0.042134445160627f, 0.998253703117371f, - 0.041752301156521f, - 0.998285591602325f, 0.041370131075382f, 0.998317182064056f, - 0.040987938642502f, - 0.998348474502563f, 0.040605723857880f, 0.998379468917847f, - 0.040223482996225f, - 0.998410165309906f, 0.039841219782829f, 0.998440563678741f, - 0.039458930492401f, - 0.998470664024353f, 0.039076622575521f, 0.998500525951386f, - 0.038694288581610f, - 0.998530030250549f, 0.038311932235956f, 0.998559296131134f, - 0.037929553538561f, - 0.998588204383850f, 0.037547148764133f, 0.998616874217987f, - 0.037164725363255f, - 0.998645246028900f, 0.036782283335924f, 0.998673319816589f, - 0.036399815231562f, - 0.998701035976410f, 0.036017324775457f, 0.998728513717651f, - 0.035634815692902f, - 0.998755753040314f, 0.035252287983894f, 0.998782634735107f, - 0.034869734197855f, - 0.998809218406677f, 0.034487165510654f, 0.998835504055023f, - 0.034104570746422f, - 0.998861551284790f, 0.033721961081028f, 0.998887240886688f, - 0.033339329063892f, - 0.998912692070007f, 0.032956674695015f, 0.998937785625458f, - 0.032574005424976f, - 0.998962640762329f, 0.032191313803196f, 0.998987197875977f, - 0.031808607280254f, - 0.999011456966400f, 0.031425878405571f, 0.999035418033600f, - 0.031043132767081f, - 0.999059081077576f, 0.030660368502140f, 0.999082446098328f, - 0.030277585610747f, - 0.999105513095856f, 0.029894785955548f, 0.999128282070160f, - 0.029511967673898f, - 0.999150753021240f, 0.029129132628441f, 0.999172985553741f, - 0.028746278956532f, - 0.999194860458374f, 0.028363410383463f, 0.999216496944427f, - 0.027980525046587f, - 0.999237775802612f, 0.027597622945905f, 0.999258816242218f, - 0.027214704081416f, - 0.999279558658600f, 0.026831768453121f, 0.999299943447113f, - 0.026448817923665f, - 0.999320089817047f, 0.026065852493048f, 0.999339938163757f, - 0.025682870298624f, - 0.999359488487244f, 0.025299875065684f, 0.999378740787506f, - 0.024916863068938f, - 0.999397754669189f, 0.024533838033676f, 0.999416410923004f, - 0.024150796234608f, - 0.999434769153595f, 0.023767741397023f, 0.999452829360962f, - 0.023384673520923f, - 0.999470651149750f, 0.023001590743661f, 0.999488115310669f, - 0.022618494927883f, - 0.999505341053009f, 0.022235386073589f, 0.999522268772125f, - 0.021852264180779f, - 0.999538838863373f, 0.021469129249454f, 0.999555170536041f, - 0.021085981279612f, - 0.999571204185486f, 0.020702820271254f, 0.999586939811707f, - 0.020319648087025f, - 0.999602377414703f, 0.019936462864280f, 0.999617516994476f, - 0.019553268328309f, - 0.999632358551025f, 0.019170060753822f, 0.999646902084351f, - 0.018786842003465f, - 0.999661207199097f, 0.018403612077236f, 0.999675154685974f, - 0.018020370975137f, - 0.999688863754272f, 0.017637118697166f, 0.999702215194702f, - 0.017253857105970f, - 0.999715328216553f, 0.016870586201549f, 0.999728083610535f, - 0.016487304121256f, - 0.999740600585938f, 0.016104012727737f, 0.999752819538116f, - 0.015720712020993f, - 0.999764680862427f, 0.015337402001023f, 0.999776303768158f, - 0.014954082667828f, - 0.999787628650665f, 0.014570754021406f, 0.999798655509949f, - 0.014187417924404f, - 0.999809384346008f, 0.013804072514176f, 0.999819874763489f, - 0.013420719653368f, - 0.999830007553101f, 0.013037359341979f, 0.999839842319489f, - 0.012653990648687f, - 0.999849438667297f, 0.012270614504814f, 0.999858677387238f, - 0.011887230910361f, - 0.999867618083954f, 0.011503840796649f, 0.999876320362091f, - 0.011120444163680f, - 0.999884724617004f, 0.010737040080130f, 0.999892771244049f, - 0.010353630408645f, - 0.999900579452515f, 0.009970214217901f, 0.999908089637756f, - 0.009586792439222f, - 0.999915301799774f, 0.009203365072608f, 0.999922215938568f, - 0.008819932118058f, - 0.999928832054138f, 0.008436493575573f, 0.999935150146484f, - 0.008053051307797f, - 0.999941170215607f, 0.007669602986425f, 0.999946892261505f, - 0.007286150939763f, - 0.999952375888824f, 0.006902694236487f, 0.999957501888275f, - 0.006519233807921f, - 0.999962329864502f, 0.006135769188404f, 0.999966919422150f, - 0.005752300843596f, - 0.999971151351929f, 0.005368829704821f, 0.999975144863129f, - 0.004985354840755f, - 0.999978840351105f, 0.004601877182722f, 0.999982178211212f, - 0.004218397196382f, - 0.999985277652740f, 0.003834914416075f, 0.999988079071045f, - 0.003451429307461f, - 0.999990582466125f, 0.003067942336202f, 0.999992787837982f, - 0.002684453502297f, - 0.999994695186615f, 0.002300963038579f, 0.999996304512024f, - 0.001917471294291f, - 0.999997675418854f, 0.001533978385851f, 0.999998688697815f, - 0.001150484546088f, - 0.999999403953552f, 0.000766990066040f, 0.999999880790710f, - 0.000383495149435f, - 1.000000000000000f, 0.000000000000023f, 0.999999880790710f, - -0.000383495149435f, - 0.999999403953552f, -0.000766990066040f, 0.999998688697815f, - -0.001150484546088f, - 0.999997675418854f, -0.001533978385851f, 0.999996304512024f, - -0.001917471294291f, - 0.999994695186615f, -0.002300963038579f, 0.999992787837982f, - -0.002684453502297f, - 0.999990582466125f, -0.003067942336202f, 0.999988079071045f, - -0.003451429307461f, - 0.999985277652740f, -0.003834914416075f, 0.999982178211212f, - -0.004218397196382f, - 0.999978840351105f, -0.004601877182722f, 0.999975144863129f, - -0.004985354840755f, - 0.999971151351929f, -0.005368829704821f, 0.999966919422150f, - -0.005752300843596f, - 0.999962329864502f, -0.006135769188404f, 0.999957501888275f, - -0.006519233807921f, - 0.999952375888824f, -0.006902694236487f, 0.999946892261505f, - -0.007286150939763f, - 0.999941170215607f, -0.007669602986425f, 0.999935150146484f, - -0.008053051307797f, - 0.999928832054138f, -0.008436493575573f, 0.999922215938568f, - -0.008819932118058f, - 0.999915301799774f, -0.009203365072608f, 0.999908089637756f, - -0.009586792439222f, - 0.999900579452515f, -0.009970214217901f, 0.999892771244049f, - -0.010353630408645f, - 0.999884724617004f, -0.010737040080130f, 0.999876320362091f, - -0.011120444163680f, - 0.999867618083954f, -0.011503840796649f, 0.999858677387238f, - -0.011887230910361f, - 0.999849438667297f, -0.012270614504814f, 0.999839842319489f, - -0.012653990648687f, - 0.999830007553101f, -0.013037359341979f, 0.999819874763489f, - -0.013420719653368f, - 0.999809384346008f, -0.013804072514176f, 0.999798655509949f, - -0.014187417924404f, - 0.999787628650665f, -0.014570754021406f, 0.999776303768158f, - -0.014954082667828f, - 0.999764680862427f, -0.015337402001023f, 0.999752819538116f, - -0.015720712020993f, - 0.999740600585938f, -0.016104012727737f, 0.999728083610535f, - -0.016487304121256f, - 0.999715328216553f, -0.016870586201549f, 0.999702215194702f, - -0.017253857105970f, - 0.999688863754272f, -0.017637118697166f, 0.999675154685974f, - -0.018020370975137f, - 0.999661207199097f, -0.018403612077236f, 0.999646902084351f, - -0.018786842003465f, - 0.999632358551025f, -0.019170060753822f, 0.999617516994476f, - -0.019553268328309f, - 0.999602377414703f, -0.019936462864280f, 0.999586939811707f, - -0.020319648087025f, - 0.999571204185486f, -0.020702820271254f, 0.999555170536041f, - -0.021085981279612f, - 0.999538838863373f, -0.021469129249454f, 0.999522268772125f, - -0.021852264180779f, - 0.999505341053009f, -0.022235386073589f, 0.999488115310669f, - -0.022618494927883f, - 0.999470651149750f, -0.023001590743661f, 0.999452829360962f, - -0.023384673520923f, - 0.999434769153595f, -0.023767741397023f, 0.999416410923004f, - -0.024150796234608f, - 0.999397754669189f, -0.024533838033676f, 0.999378740787506f, - -0.024916863068938f, - 0.999359488487244f, -0.025299875065684f, 0.999339938163757f, - -0.025682870298624f, - 0.999320089817047f, -0.026065852493048f, 0.999299943447113f, - -0.026448817923665f, - 0.999279558658600f, -0.026831768453121f, 0.999258816242218f, - -0.027214704081416f, - 0.999237775802612f, -0.027597622945905f, 0.999216496944427f, - -0.027980525046587f, - 0.999194860458374f, -0.028363410383463f, 0.999172985553741f, - -0.028746278956532f, - 0.999150753021240f, -0.029129132628441f, 0.999128282070160f, - -0.029511967673898f, - 0.999105513095856f, -0.029894785955548f, 0.999082446098328f, - -0.030277585610747f, - 0.999059081077576f, -0.030660368502140f, 0.999035418033600f, - -0.031043132767081f, - 0.999011456966400f, -0.031425878405571f, 0.998987197875977f, - -0.031808607280254f, - 0.998962640762329f, -0.032191313803196f, 0.998937785625458f, - -0.032574005424976f, - 0.998912692070007f, -0.032956674695015f, 0.998887240886688f, - -0.033339329063892f, - 0.998861551284790f, -0.033721961081028f, 0.998835504055023f, - -0.034104570746422f, - 0.998809218406677f, -0.034487165510654f, 0.998782634735107f, - -0.034869734197855f, - 0.998755753040314f, -0.035252287983894f, 0.998728513717651f, - -0.035634815692902f, - 0.998701035976410f, -0.036017324775457f, 0.998673319816589f, - -0.036399815231562f, - 0.998645246028900f, -0.036782283335924f, 0.998616874217987f, - -0.037164725363255f, - 0.998588204383850f, -0.037547148764133f, 0.998559296131134f, - -0.037929553538561f, - 0.998530030250549f, -0.038311932235956f, 0.998500525951386f, - -0.038694288581610f, - 0.998470664024353f, -0.039076622575521f, 0.998440563678741f, - -0.039458930492401f, - 0.998410165309906f, -0.039841219782829f, 0.998379468917847f, - -0.040223482996225f, - 0.998348474502563f, -0.040605723857880f, 0.998317182064056f, - -0.040987938642502f, - 0.998285591602325f, -0.041370131075382f, 0.998253703117371f, - -0.041752301156521f, - 0.998221516609192f, -0.042134445160627f, 0.998189091682434f, - -0.042516563087702f, - 0.998156309127808f, -0.042898654937744f, 0.998123228549957f, - -0.043280724436045f, - 0.998089909553528f, -0.043662767857313f, 0.998056292533875f, - -0.044044785201550f, - 0.998022377490997f, -0.044426776468754f, 0.997988104820251f, - -0.044808741658926f, - 0.997953593730927f, -0.045190680772066f, 0.997918784618378f, - -0.045572593808174f, - 0.997883677482605f, -0.045954477041960f, 0.997848331928253f, - -0.046336337924004f, - 0.997812628746033f, -0.046718169003725f, 0.997776627540588f, - -0.047099970281124f, - 0.997740387916565f, -0.047481749206781f, 0.997703790664673f, - -0.047863494604826f, - 0.997666954994202f, -0.048245213925838f, 0.997629821300507f, - -0.048626907169819f, - 0.997592389583588f, -0.049008570611477f, 0.997554600238800f, - -0.049390204250813f, - 0.997516572475433f, -0.049771808087826f, 0.997478306293488f, - -0.050153385847807f, - 0.997439682483673f, -0.050534930080175f, 0.997400760650635f, - -0.050916448235512f, - 0.997361540794373f, -0.051297932863235f, 0.997322082519531f, - -0.051679391413927f, - 0.997282266616821f, -0.052060816437006f, 0.997242212295532f, - -0.052442211657763f, - 0.997201859951019f, -0.052823577076197f, 0.997161149978638f, - -0.053204908967018f, - 0.997120201587677f, -0.053586211055517f, 0.997078955173492f, - -0.053967483341694f, - 0.997037410736084f, -0.054348722100258f, 0.996995627880096f, - -0.054729927331209f, - 0.996953487396240f, -0.055111102759838f, 0.996911048889160f, - -0.055492244660854f, - 0.996868371963501f, -0.055873356759548f, 0.996825337409973f, - -0.056254431605339f, - 0.996782064437866f, -0.056635476648808f, 0.996738493442535f, - -0.057016488164663f, - 0.996694624423981f, -0.057397462427616f, 0.996650457382202f, - -0.057778406888247f, - 0.996605992317200f, -0.058159314095974f, 0.996561229228973f, - -0.058540191501379f, - 0.996516168117523f, -0.058921031653881f, 0.996470808982849f, - -0.059301838278770f, - 0.996425211429596f, -0.059682607650757f, 0.996379256248474f, - -0.060063343495131f, - 0.996333062648773f, -0.060444042086601f, 0.996286571025848f, - -0.060824707150459f, - 0.996239781379700f, -0.061205338686705f, 0.996192693710327f, - -0.061585929244757f, - 0.996145308017731f, -0.061966486275196f, 0.996097624301910f, - -0.062347009778023f, - 0.996049642562866f, -0.062727488577366f, 0.996001422405243f, - -0.063107937574387f, - 0.995952844619751f, -0.063488349318504f, 0.995904028415680f, - -0.063868723809719f, - 0.995854854583740f, -0.064249053597450f, 0.995805442333221f, - -0.064629353582859f, - 0.995755732059479f, -0.065009608864784f, 0.995705723762512f, - -0.065389834344387f, - 0.995655417442322f, -0.065770015120506f, 0.995604813098907f, - -0.066150158643723f, - 0.995553970336914f, -0.066530264914036f, 0.995502769947052f, - -0.066910326480865f, - 0.995451331138611f, -0.067290350794792f, 0.995399534702301f, - -0.067670337855816f, - 0.995347499847412f, -0.068050287663937f, 0.995295166969299f, - -0.068430192768574f, - 0.995242536067963f, -0.068810060620308f, 0.995189607143402f, - -0.069189883768559f, - 0.995136380195618f, -0.069569669663906f, 0.995082914829254f, - -0.069949418306351f, - 0.995029091835022f, -0.070329122245312f, 0.994975030422211f, - -0.070708781480789f, - 0.994920611381531f, -0.071088403463364f, 0.994865953922272f, - -0.071467980742455f, - 0.994810998439789f, -0.071847513318062f, 0.994755744934082f, - -0.072227008640766f, - 0.994700193405151f, -0.072606459259987f, 0.994644403457642f, - -0.072985872626305f, - 0.994588255882263f, -0.073365233838558f, 0.994531810283661f, - -0.073744557797909f, - 0.994475126266479f, -0.074123837053776f, 0.994418144226074f, - -0.074503071606159f, - 0.994360864162445f, -0.074882268905640f, 0.994303286075592f, - -0.075261414051056f, - 0.994245409965515f, -0.075640521943569f, 0.994187235832214f, - -0.076019577682018f, - 0.994128763675690f, -0.076398596167564f, 0.994070053100586f, - -0.076777562499046f, - 0.994010984897614f, -0.077156484127045f, 0.993951678276062f, - -0.077535368502140f, - 0.993892073631287f, -0.077914200723171f, 0.993832170963287f, - -0.078292988240719f, - 0.993771970272064f, -0.078671731054783f, 0.993711471557617f, - -0.079050421714783f, - 0.993650734424591f, -0.079429075121880f, 0.993589639663696f, - -0.079807676374912f, - 0.993528306484222f, -0.080186225473881f, 0.993466615676880f, - -0.080564737319946f, - 0.993404686450958f, -0.080943197011948f, 0.993342459201813f, - -0.081321612000465f, - 0.993279933929443f, -0.081699974834919f, 0.993217170238495f, - -0.082078292965889f, - 0.993154048919678f, -0.082456558942795f, 0.993090689182281f, - -0.082834780216217f, - 0.993026971817017f, -0.083212949335575f, 0.992963016033173f, - -0.083591073751450f, - 0.992898762226105f, -0.083969146013260f, 0.992834210395813f, - -0.084347173571587f, - 0.992769360542297f, -0.084725148975849f, 0.992704212665558f, - -0.085103072226048f, - 0.992638826370239f, -0.085480943322182f, 0.992573142051697f, - -0.085858769714832f, - 0.992507100105286f, -0.086236543953419f, 0.992440819740295f, - -0.086614266037941f, - 0.992374241352081f, -0.086991935968399f, 0.992307364940643f, - -0.087369553744793f, - 0.992240250110626f, -0.087747126817703f, 0.992172777652740f, - -0.088124647736549f, - 0.992105066776276f, -0.088502109050751f, 0.992036998271942f, - -0.088879525661469f, - 0.991968691349030f, -0.089256882667542f, 0.991900086402893f, - -0.089634194970131f, - 0.991831183433533f, -0.090011447668076f, 0.991762042045593f, - -0.090388655662537f, - 0.991692543029785f, -0.090765804052353f, 0.991622805595398f, - -0.091142900288105f, - 0.991552770137787f, -0.091519944369793f, 0.991482377052307f, - -0.091896936297417f, - 0.991411805152893f, -0.092273868620396f, 0.991340875625610f, - -0.092650748789310f, - 0.991269648075104f, -0.093027576804161f, 0.991198182106018f, - -0.093404345214367f, - 0.991126358509064f, -0.093781061470509f, 0.991054296493530f, - -0.094157725572586f, - 0.990981936454773f, -0.094534330070019f, 0.990909278392792f, - -0.094910882413387f, - 0.990836322307587f, -0.095287375152111f, 0.990763127803802f, - -0.095663815736771f, - 0.990689575672150f, -0.096040196716785f, 0.990615785121918f, - -0.096416525542736f, - 0.990541696548462f, -0.096792794764042f, 0.990467309951782f, - -0.097169004380703f, - 0.990392625331879f, -0.097545161843300f, 0.990317702293396f, - -0.097921259701252f, - 0.990242421627045f, -0.098297297954559f, 0.990166902542114f, - -0.098673284053802f, - 0.990091085433960f, -0.099049203097820f, 0.990014970302582f, - -0.099425069987774f, - 0.989938557147980f, -0.099800877273083f, 0.989861845970154f, - -0.100176624953747f, - 0.989784896373749f, -0.100552320480347f, 0.989707589149475f, - -0.100927948951721f, - 0.989630043506622f, -0.101303517818451f, 0.989552199840546f, - -0.101679034531116f, - 0.989474058151245f, -0.102054484188557f, 0.989395678043365f, - -0.102429874241352f, - 0.989316940307617f, -0.102805204689503f, 0.989237964153290f, - -0.103180475533009f, - 0.989158689975739f, -0.103555686771870f, 0.989079117774963f, - -0.103930838406086f, - 0.988999247550964f, -0.104305922985077f, 0.988919138908386f, - -0.104680955410004f, - 0.988838672637939f, -0.105055920779705f, 0.988757967948914f, - -0.105430819094181f, - 0.988676965236664f, -0.105805665254593f, 0.988595664501190f, - -0.106180444359779f, - 0.988514065742493f, -0.106555156409740f, 0.988432228565216f, - -0.106929816305637f, - 0.988350033760071f, -0.107304409146309f, 0.988267600536346f, - -0.107678934931755f, - 0.988184869289398f, -0.108053401112556f, 0.988101840019226f, - -0.108427800238132f, - 0.988018512725830f, -0.108802139759064f, 0.987934947013855f, - -0.109176412224770f, - 0.987851083278656f, -0.109550617635250f, 0.987766921520233f, - -0.109924763441086f, - 0.987682461738586f, -0.110298842191696f, 0.987597703933716f, - -0.110672861337662f, - 0.987512648105621f, -0.111046813428402f, 0.987427353858948f, - -0.111420698463917f, - 0.987341761589050f, -0.111794516444206f, 0.987255871295929f, - -0.112168267369270f, - 0.987169682979584f, -0.112541958689690f, 0.987083256244659f, - -0.112915575504303f, - 0.986996471881866f, -0.113289132714272f, 0.986909449100494f, - -0.113662622869015f, - 0.986822128295898f, -0.114036038517952f, 0.986734509468079f, - -0.114409394562244f, - 0.986646652221680f, -0.114782683551311f, 0.986558437347412f, - -0.115155905485153f, - 0.986469984054565f, -0.115529052913189f, 0.986381232738495f, - -0.115902140736580f, - 0.986292183399200f, -0.116275154054165f, 0.986202836036682f, - -0.116648100316525f, - 0.986113250255585f, -0.117020979523659f, 0.986023366451263f, - -0.117393791675568f, - 0.985933184623718f, -0.117766529321671f, 0.985842704772949f, - -0.118139199912548f, - 0.985751926898956f, -0.118511803448200f, 0.985660910606384f, - -0.118884332478046f, - 0.985569596290588f, -0.119256794452667f, 0.985477983951569f, - -0.119629189372063f, - 0.985386073589325f, -0.120001509785652f, 0.985293865203857f, - -0.120373763144016f, - 0.985201418399811f, -0.120745941996574f, 0.985108673572540f, - -0.121118053793907f, - 0.985015630722046f, -0.121490091085434f, 0.984922289848328f, - -0.121862053871155f, - 0.984828710556030f, -0.122233949601650f, 0.984734773635864f, - -0.122605770826340f, - 0.984640598297119f, -0.122977524995804f, 0.984546124935150f, - -0.123349204659462f, - 0.984451413154602f, -0.123720809817314f, 0.984356343746185f, - -0.124092340469360f, - 0.984261035919189f, -0.124463804066181f, 0.984165430068970f, - -0.124835193157196f, - 0.984069526195526f, -0.125206500291824f, 0.983973383903503f, - -0.125577747821808f, - 0.983876943588257f, -0.125948905944824f, 0.983780145645142f, - -0.126320004463196f, - 0.983683168888092f, -0.126691013574600f, 0.983585834503174f, - -0.127061963081360f, - 0.983488261699677f, -0.127432823181152f, 0.983390331268311f, - -0.127803623676300f, - 0.983292162418365f, -0.128174334764481f, 0.983193755149841f, - -0.128544986248016f, - 0.983094990253448f, -0.128915548324585f, 0.982995986938477f, - -0.129286035895348f, - 0.982896685600281f, -0.129656463861465f, 0.982797086238861f, - -0.130026802420616f, - 0.982697248458862f, -0.130397051572800f, 0.982597053050995f, - -0.130767241120338f, - 0.982496619224548f, -0.131137356162071f, 0.982395887374878f, - -0.131507381796837f, - 0.982294917106628f, -0.131877332925797f, 0.982193589210510f, - -0.132247209548950f, - 0.982092022895813f, -0.132617011666298f, 0.981990158557892f, - -0.132986739277840f, - 0.981888055801392f, -0.133356377482414f, 0.981785595417023f, - -0.133725941181183f, - 0.981682896614075f, -0.134095430374146f, 0.981579899787903f, - -0.134464830160141f, - 0.981476604938507f, -0.134834155440331f, 0.981373071670532f, - -0.135203406214714f, - 0.981269240379334f, -0.135572582483292f, 0.981165111064911f, - -0.135941669344902f, - 0.981060683727264f, -0.136310681700706f, 0.980956017971039f, - -0.136679604649544f, - 0.980851054191589f, -0.137048453092575f, 0.980745792388916f, - -0.137417227029800f, - 0.980640232563019f, -0.137785911560059f, 0.980534434318542f, - -0.138154521584511f, - 0.980428338050842f, -0.138523042201996f, 0.980321943759918f, - -0.138891488313675f, - 0.980215251445770f, -0.139259845018387f, 0.980108320713043f, - -0.139628127217293f, - 0.980001091957092f, -0.139996320009232f, 0.979893565177917f, - -0.140364438295364f, - 0.979785740375519f, -0.140732467174530f, 0.979677677154541f, - -0.141100421547890f, - 0.979569315910339f, -0.141468286514282f, 0.979460656642914f, - -0.141836062073708f, - 0.979351758956909f, -0.142203763127327f, 0.979242503643036f, - -0.142571389675140f, - 0.979133009910584f, -0.142938911914825f, 0.979023277759552f, - -0.143306359648705f, - 0.978913187980652f, -0.143673732876778f, 0.978802859783173f, - -0.144041016697884f, - 0.978692233562469f, -0.144408211112022f, 0.978581368923187f, - -0.144775316119194f, - 0.978470146656036f, -0.145142331719399f, 0.978358685970306f, - -0.145509272813797f, - 0.978246986865997f, -0.145876124501228f, 0.978134930133820f, - -0.146242901682854f, - 0.978022634983063f, -0.146609574556351f, 0.977910041809082f, - -0.146976172924042f, - 0.977797150611877f, -0.147342681884766f, 0.977684020996094f, - -0.147709101438522f, - 0.977570593357086f, -0.148075446486473f, 0.977456867694855f, - -0.148441687226295f, - 0.977342903614044f, -0.148807853460312f, 0.977228581905365f, - -0.149173930287361f, - 0.977114021778107f, -0.149539917707443f, 0.976999223232269f, - -0.149905815720558f, - 0.976884067058563f, -0.150271624326706f, 0.976768672466278f, - -0.150637343525887f, - 0.976653039455414f, -0.151002973318100f, 0.976537048816681f, - -0.151368513703346f, - 0.976420819759369f, -0.151733979582787f, 0.976304292678833f, - -0.152099341154099f, - 0.976187527179718f, -0.152464613318443f, 0.976070404052734f, - -0.152829796075821f, - 0.975953042507172f, -0.153194904327393f, 0.975835442543030f, - -0.153559908270836f, - 0.975717484951019f, -0.153924822807312f, 0.975599288940430f, - -0.154289647936821f, - 0.975480854511261f, -0.154654383659363f, 0.975362062454224f, - -0.155019029974937f, - 0.975243031978607f, -0.155383571982384f, 0.975123703479767f, - -0.155748039484024f, - 0.975004136562347f, -0.156112402677536f, 0.974884271621704f, - -0.156476691365242f, - 0.974764108657837f, -0.156840875744820f, 0.974643647670746f, - -0.157204970717430f, - 0.974522948265076f, -0.157568961381912f, 0.974401950836182f, - -0.157932877540588f, - 0.974280655384064f, -0.158296689391136f, 0.974159121513367f, - -0.158660411834717f, - 0.974037289619446f, -0.159024044871330f, 0.973915159702301f, - -0.159387573599815f, - 0.973792791366577f, -0.159751012921333f, 0.973670125007629f, - -0.160114362835884f, - 0.973547160625458f, -0.160477623343468f, 0.973423957824707f, - -0.160840779542923f, - 0.973300457000732f, -0.161203846335411f, 0.973176658153534f, - -0.161566808819771f, - 0.973052620887756f, -0.161929681897163f, 0.972928285598755f, - -0.162292465567589f, - 0.972803652286530f, -0.162655144929886f, 0.972678780555725f, - -0.163017734885216f, - 0.972553610801697f, -0.163380220532417f, 0.972428143024445f, - -0.163742616772652f, - 0.972302436828613f, -0.164104923605919f, 0.972176432609558f, - -0.164467126131058f, - 0.972050130367279f, -0.164829224348068f, 0.971923589706421f, - -0.165191248059273f, - 0.971796751022339f, -0.165553152561188f, 0.971669614315033f, - -0.165914967656136f, - 0.971542239189148f, -0.166276678442955f, 0.971414566040039f, - -0.166638299822807f, - 0.971286594867706f, -0.166999831795692f, 0.971158385276794f, - -0.167361244559288f, - 0.971029877662659f, -0.167722567915916f, 0.970901072025299f, - -0.168083801865578f, - 0.970772027969360f, -0.168444931507111f, 0.970642685890198f, - -0.168805956840515f, - 0.970513105392456f, -0.169166877865791f, 0.970383226871490f, - -0.169527709484100f, - 0.970253050327301f, -0.169888436794281f, 0.970122575759888f, - -0.170249074697495f, - 0.969991862773895f, -0.170609608292580f, 0.969860911369324f, - -0.170970037579536f, - 0.969729602336884f, -0.171330362558365f, 0.969598054885864f, - -0.171690583229065f, - 0.969466269016266f, -0.172050714492798f, 0.969334125518799f, - -0.172410741448402f, - 0.969201743602753f, -0.172770664095879f, 0.969069123268127f, - -0.173130482435226f, - 0.968936204910278f, -0.173490211367607f, 0.968802988529205f, - -0.173849821090698f, - 0.968669533729553f, -0.174209341406822f, 0.968535780906677f, - -0.174568757414818f, - 0.968401730060577f, -0.174928069114685f, 0.968267440795898f, - -0.175287276506424f, - 0.968132853507996f, -0.175646379590034f, 0.967997968196869f, - -0.176005378365517f, - 0.967862844467163f, -0.176364272832870f, 0.967727422714233f, - -0.176723077893257f, - 0.967591762542725f, -0.177081763744354f, 0.967455804347992f, - -0.177440345287323f, - 0.967319548130035f, -0.177798837423325f, 0.967183053493500f, - -0.178157210350037f, - 0.967046260833740f, -0.178515478968620f, 0.966909229755402f, - -0.178873643279076f, - 0.966771900653839f, -0.179231703281403f, 0.966634273529053f, - -0.179589673876762f, - 0.966496407985687f, -0.179947525262833f, 0.966358244419098f, - -0.180305257439613f, - 0.966219842433929f, -0.180662900209427f, 0.966081082820892f, - -0.181020438671112f, - 0.965942144393921f, -0.181377857923508f, 0.965802907943726f, - -0.181735187768936f, - 0.965663373470306f, -0.182092398405075f, 0.965523540973663f, - -0.182449504733086f, - 0.965383470058441f, -0.182806491851807f, 0.965243160724640f, - -0.183163389563560f, - 0.965102493762970f, -0.183520168066025f, 0.964961588382721f, - -0.183876842260361f, - 0.964820444583893f, -0.184233412146568f, 0.964679002761841f, - -0.184589877724648f, - 0.964537262916565f, -0.184946224093437f, 0.964395284652710f, - -0.185302466154099f, - 0.964253067970276f, -0.185658603906631f, 0.964110493659973f, - -0.186014622449875f, - 0.963967680931091f, -0.186370536684990f, 0.963824629783630f, - -0.186726331710815f, - 0.963681280612946f, -0.187082037329674f, 0.963537633419037f, - -0.187437608838081f, - 0.963393747806549f, -0.187793090939522f, 0.963249564170837f, - -0.188148453831673f, - 0.963105142116547f, -0.188503712415695f, 0.962960422039032f, - -0.188858851790428f, - 0.962815403938293f, -0.189213871955872f, 0.962670147418976f, - -0.189568802714348f, - 0.962524592876434f, -0.189923599362373f, 0.962378799915314f, - -0.190278306603432f, - 0.962232708930969f, -0.190632879734039f, 0.962086379528046f, - -0.190987363457680f, - 0.961939752101898f, -0.191341713070869f, 0.961792886257172f, - -0.191695958375931f, - 0.961645722389221f, -0.192050099372864f, 0.961498260498047f, - -0.192404121160507f, - 0.961350560188293f, -0.192758023738861f, 0.961202561855316f, - -0.193111822009087f, - 0.961054325103760f, -0.193465501070023f, 0.960905790328979f, - -0.193819075822830f, - 0.960757017135620f, -0.194172516465187f, 0.960607945919037f, - -0.194525867700577f, - 0.960458636283875f, -0.194879084825516f, 0.960309028625488f, - -0.195232197642326f, - 0.960159122943878f, -0.195585191249847f, 0.960008978843689f, - -0.195938065648079f, - 0.959858596324921f, -0.196290835738182f, 0.959707856178284f, - -0.196643486618996f, - 0.959556937217712f, -0.196996018290520f, 0.959405720233917f, - -0.197348430752754f, - 0.959254205226898f, -0.197700738906860f, 0.959102451801300f, - -0.198052927851677f, - 0.958950400352478f, -0.198404997587204f, 0.958798050880432f, - -0.198756948113441f, - 0.958645522594452f, -0.199108779430389f, 0.958492636680603f, - -0.199460506439209f, - 0.958339512348175f, -0.199812099337578f, 0.958186149597168f, - -0.200163587927818f, - 0.958032488822937f, -0.200514942407608f, 0.957878530025482f, - -0.200866192579269f, - 0.957724332809448f, -0.201217323541641f, 0.957569897174835f, - -0.201568335294724f, - 0.957415163516998f, -0.201919227838516f, 0.957260131835938f, - -0.202270001173019f, - 0.957104861736298f, -0.202620655298233f, 0.956949353218079f, - -0.202971190214157f, - 0.956793546676636f, -0.203321605920792f, 0.956637442111969f, - -0.203671902418137f, - 0.956481099128723f, -0.204022079706192f, 0.956324458122253f, - -0.204372137784958f, - 0.956167578697205f, -0.204722076654434f, 0.956010460853577f, - -0.205071896314621f, - 0.955853044986725f, -0.205421581864357f, 0.955695331096649f, - -0.205771163105965f, - 0.955537378787994f, -0.206120610237122f, 0.955379128456116f, - -0.206469938158989f, - 0.955220639705658f, -0.206819161772728f, 0.955061912536621f, - -0.207168251276016f, - 0.954902827739716f, -0.207517206668854f, 0.954743564128876f, - -0.207866057753563f, - 0.954584002494812f, -0.208214774727821f, 0.954424142837524f, - -0.208563387393951f, - 0.954264044761658f, -0.208911851048470f, 0.954103708267212f, - -0.209260210394859f, - 0.953943073749542f, -0.209608450531960f, 0.953782141208649f, - -0.209956556558609f, - 0.953620970249176f, -0.210304543375969f, 0.953459560871124f, - -0.210652396082878f, - 0.953297853469849f, -0.211000129580498f, 0.953135907649994f, - -0.211347743868828f, - 0.952973663806915f, -0.211695238947868f, 0.952811121940613f, - -0.212042599916458f, - 0.952648401260376f, -0.212389841675758f, 0.952485322952271f, - -0.212736949324608f, - 0.952322065830231f, -0.213083937764168f, 0.952158451080322f, - -0.213430806994438f, - 0.951994657516479f, -0.213777542114258f, 0.951830565929413f, - -0.214124158024788f, - 0.951666176319122f, -0.214470639824867f, 0.951501548290253f, - -0.214817002415657f, - 0.951336681842804f, -0.215163245797157f, 0.951171517372131f, - -0.215509355068207f, - 0.951006054878235f, -0.215855330228806f, 0.950840353965759f, - -0.216201186180115f, - 0.950674414634705f, -0.216546908020973f, 0.950508177280426f, - -0.216892510652542f, - 0.950341701507568f, -0.217237979173660f, 0.950174987316132f, - -0.217583328485489f, - 0.950007975101471f, -0.217928543686867f, 0.949840664863586f, - -0.218273624777794f, - 0.949673116207123f, -0.218618586659431f, 0.949505329132080f, - -0.218963414430618f, - 0.949337244033813f, -0.219308122992516f, 0.949168920516968f, - -0.219652697443962f, - 0.949000298976898f, -0.219997137784958f, 0.948831439018250f, - -0.220341444015503f, - 0.948662281036377f, -0.220685631036758f, 0.948492884635925f, - -0.221029683947563f, - 0.948323249816895f, -0.221373617649078f, 0.948153316974640f, - -0.221717402338982f, - 0.947983145713806f, -0.222061067819595f, 0.947812676429749f, - -0.222404599189758f, - 0.947641968727112f, -0.222748011350632f, 0.947470963001251f, - -0.223091274499893f, - 0.947299718856812f, -0.223434418439865f, 0.947128236293793f, - -0.223777428269386f, - 0.946956455707550f, -0.224120303988457f, 0.946784436702728f, - -0.224463045597076f, - 0.946612179279327f, -0.224805667996407f, 0.946439623832703f, - -0.225148141384125f, - 0.946266770362854f, -0.225490495562553f, 0.946093678474426f, - -0.225832715630531f, - 0.945920348167419f, -0.226174786686897f, 0.945746779441834f, - -0.226516738533974f, - 0.945572853088379f, -0.226858556270599f, 0.945398747920990f, - -0.227200239896774f, - 0.945224344730377f, -0.227541789412498f, 0.945049703121185f, - -0.227883204817772f, - 0.944874763488770f, -0.228224486112595f, 0.944699645042419f, - -0.228565633296967f, - 0.944524168968201f, -0.228906646370888f, 0.944348454475403f, - -0.229247525334358f, - 0.944172501564026f, -0.229588270187378f, 0.943996310234070f, - -0.229928880929947f, - 0.943819820880890f, -0.230269357562065f, 0.943643093109131f, - -0.230609700083733f, - 0.943466067314148f, -0.230949893593788f, 0.943288803100586f, - -0.231289967894554f, - 0.943111240863800f, -0.231629893183708f, 0.942933499813080f, - -0.231969684362412f, - 0.942755401134491f, -0.232309341430664f, 0.942577123641968f, - -0.232648864388466f, - 0.942398548126221f, -0.232988253235817f, 0.942219734191895f, - -0.233327493071556f, - 0.942040622234344f, -0.233666598796844f, 0.941861271858215f, - -0.234005570411682f, - 0.941681683063507f, -0.234344407916069f, 0.941501796245575f, - -0.234683111310005f, - 0.941321671009064f, -0.235021665692329f, 0.941141307353973f, - -0.235360085964203f, - 0.940960645675659f, -0.235698372125626f, 0.940779745578766f, - -0.236036509275436f, - 0.940598547458649f, -0.236374512314796f, 0.940417110919952f, - -0.236712381243706f, - 0.940235435962677f, -0.237050101161003f, 0.940053522586823f, - -0.237387686967850f, - 0.939871311187744f, -0.237725138664246f, 0.939688861370087f, - -0.238062441349030f, - 0.939506113529205f, -0.238399609923363f, 0.939323127269745f, - -0.238736644387245f, - 0.939139902591705f, -0.239073529839516f, 0.938956379890442f, - -0.239410281181335f, - 0.938772618770599f, -0.239746883511543f, 0.938588619232178f, - -0.240083336830139f, - 0.938404381275177f, -0.240419670939446f, 0.938219845294952f, - -0.240755841135979f, - 0.938035070896149f, -0.241091892123222f, 0.937849998474121f, - -0.241427779197693f, - 0.937664687633514f, -0.241763532161713f, 0.937479138374329f, - -0.242099151015282f, - 0.937293350696564f, -0.242434620857239f, 0.937107264995575f, - -0.242769956588745f, - 0.936920940876007f, -0.243105143308640f, 0.936734318733215f, - -0.243440181016922f, - 0.936547517776489f, -0.243775084614754f, 0.936360359191895f, - -0.244109839200974f, - 0.936173021793365f, -0.244444444775581f, 0.935985386371613f, - -0.244778916239738f, - 0.935797572135925f, -0.245113238692284f, 0.935609400272369f, - -0.245447427034378f, - 0.935421049594879f, -0.245781451463699f, 0.935232400894165f, - -0.246115356683731f, - 0.935043513774872f, -0.246449097990990f, 0.934854328632355f, - -0.246782705187798f, - 0.934664964675903f, -0.247116148471832f, 0.934475243091583f, - -0.247449472546577f, - 0.934285342693329f, -0.247782632708550f, 0.934095203876495f, - -0.248115643858910f, - 0.933904767036438f, -0.248448520898819f, 0.933714091777802f, - -0.248781248927116f, - 0.933523118495941f, -0.249113827943802f, 0.933331906795502f, - -0.249446272850037f, - 0.933140456676483f, -0.249778553843498f, 0.932948768138886f, - -0.250110685825348f, - 0.932756841182709f, -0.250442683696747f, 0.932564616203308f, - -0.250774532556534f, - 0.932372152805328f, -0.251106232404709f, 0.932179391384125f, - -0.251437783241272f, - 0.931986451148987f, -0.251769185066223f, 0.931793212890625f, - -0.252100437879562f, - 0.931599736213684f, -0.252431541681290f, 0.931405961513519f, - -0.252762526273727f, - 0.931211948394775f, -0.253093332052231f, 0.931017756462097f, - -0.253423988819122f, - 0.930823206901550f, -0.253754496574402f, 0.930628478527069f, - -0.254084855318069f, - 0.930433452129364f, -0.254415065050125f, 0.930238187313080f, - -0.254745125770569f, - 0.930042684078217f, -0.255075037479401f, 0.929846942424774f, - -0.255404800176620f, - 0.929650902748108f, -0.255734413862228f, 0.929454624652863f, - -0.256063878536224f, - 0.929258108139038f, -0.256393194198608f, 0.929061353206635f, - -0.256722360849380f, - 0.928864300251007f, -0.257051378488541f, 0.928667008876801f, - -0.257380217313766f, - 0.928469479084015f, -0.257708936929703f, 0.928271710872650f, - -0.258037507534027f, - 0.928073644638062f, -0.258365899324417f, 0.927875399589539f, - -0.258694142103195f, - 0.927676856517792f, -0.259022265672684f, 0.927478015422821f, - -0.259350210428238f, - 0.927278995513916f, -0.259678006172180f, 0.927079677581787f, - -0.260005623102188f, - 0.926880121231079f, -0.260333120822906f, 0.926680326461792f, - -0.260660469532013f, - 0.926480293273926f, -0.260987639427185f, 0.926280021667480f, - -0.261314690113068f, - 0.926079452037811f, -0.261641561985016f, 0.925878643989563f, - -0.261968284845352f, - 0.925677597522736f, -0.262294828891754f, 0.925476312637329f, - -0.262621253728867f, - 0.925274729728699f, -0.262947499752045f, 0.925072908401489f, - -0.263273626565933f, - 0.924870908260345f, -0.263599574565887f, 0.924668610095978f, - -0.263925373554230f, - 0.924466013908386f, -0.264250993728638f, 0.924263238906860f, - -0.264576494693756f, - 0.924060165882111f, -0.264901816844940f, 0.923856854438782f, - -0.265226989984512f, - 0.923653304576874f, -0.265552014112473f, 0.923449516296387f, - -0.265876859426498f, - 0.923245489597321f, -0.266201555728912f, 0.923041164875031f, - -0.266526103019714f, - 0.922836601734161f, -0.266850501298904f, 0.922631800174713f, - -0.267174720764160f, - 0.922426760196686f, -0.267498821020126f, 0.922221481800079f, - -0.267822742462158f, - 0.922015964984894f, -0.268146485090256f, 0.921810150146484f, - -0.268470078706741f, - 0.921604096889496f, -0.268793523311615f, 0.921397805213928f, - -0.269116818904877f, - 0.921191275119781f, -0.269439965486526f, 0.920984506607056f, - -0.269762933254242f, - 0.920777499675751f, -0.270085722208023f, 0.920570194721222f, - -0.270408391952515f, - 0.920362710952759f, -0.270730882883072f, 0.920154929161072f, - -0.271053224802017f, - 0.919946908950806f, -0.271375387907028f, 0.919738650321960f, - -0.271697402000427f, - 0.919530093669891f, -0.272019267082214f, 0.919321358203888f, - -0.272340953350067f, - 0.919112324714661f, -0.272662490606308f, 0.918903112411499f, - -0.272983878850937f, - 0.918693602085114f, -0.273305088281631f, 0.918483853340149f, - -0.273626148700714f, - 0.918273866176605f, -0.273947030305862f, 0.918063640594482f, - -0.274267762899399f, - 0.917853116989136f, -0.274588316679001f, 0.917642414569855f, - -0.274908751249313f, - 0.917431414127350f, -0.275228977203369f, 0.917220234870911f, - -0.275549083948135f, - 0.917008757591248f, -0.275868982076645f, 0.916797041893005f, - -0.276188760995865f, - 0.916585087776184f, -0.276508361101151f, 0.916372895240784f, - -0.276827782392502f, - 0.916160404682159f, -0.277147054672241f, 0.915947735309601f, - -0.277466177940369f, - 0.915734827518463f, -0.277785122394562f, 0.915521621704102f, - -0.278103888034821f, - 0.915308177471161f, -0.278422504663467f, 0.915094554424286f, - -0.278740972280502f, - 0.914880633354187f, -0.279059261083603f, 0.914666473865509f, - -0.279377400875092f, - 0.914452075958252f, -0.279695361852646f, 0.914237439632416f, - -0.280013144016266f, - 0.914022505283356f, -0.280330777168274f, 0.913807392120361f, - -0.280648261308670f, - 0.913592040538788f, -0.280965566635132f, 0.913376390933990f, - -0.281282693147659f, - 0.913160502910614f, -0.281599670648575f, 0.912944436073303f, - -0.281916469335556f, - 0.912728071212769f, -0.282233119010925f, 0.912511467933655f, - -0.282549589872360f, - 0.912294626235962f, -0.282865911722183f, 0.912077546119690f, - -0.283182054758072f, - 0.911860227584839f, -0.283498018980026f, 0.911642670631409f, - -0.283813834190369f, - 0.911424875259399f, -0.284129470586777f, 0.911206841468811f, - -0.284444957971573f, - 0.910988569259644f, -0.284760266542435f, 0.910769999027252f, - -0.285075396299362f, - 0.910551249980927f, -0.285390377044678f, 0.910332262516022f, - -0.285705178976059f, - 0.910112977027893f, -0.286019802093506f, 0.909893512725830f, - -0.286334276199341f, - 0.909673750400543f, -0.286648571491241f, 0.909453809261322f, - -0.286962717771530f, - 0.909233570098877f, -0.287276685237885f, 0.909013092517853f, - -0.287590473890305f, - 0.908792436122894f, -0.287904083728790f, 0.908571481704712f, - -0.288217544555664f, - 0.908350288867950f, -0.288530826568604f, 0.908128857612610f, - -0.288843959569931f, - 0.907907187938690f, -0.289156883955002f, 0.907685279846191f, - -0.289469659328461f, - 0.907463192939758f, -0.289782285690308f, 0.907240808010101f, - -0.290094703435898f, - 0.907018184661865f, -0.290406972169876f, 0.906795322895050f, - -0.290719062089920f, - 0.906572222709656f, -0.291031002998352f, 0.906348884105682f, - -0.291342735290527f, - 0.906125307083130f, -0.291654318571091f, 0.905901491641998f, - -0.291965723037720f, - 0.905677437782288f, -0.292276978492737f, 0.905453145503998f, - -0.292588025331497f, - 0.905228614807129f, -0.292898923158646f, 0.905003845691681f, - -0.293209642171860f, - 0.904778838157654f, -0.293520182371140f, 0.904553592205048f, - -0.293830573558807f, - 0.904328107833862f, -0.294140785932541f, 0.904102385044098f, - -0.294450789690018f, - 0.903876423835754f, -0.294760644435883f, 0.903650224208832f, - -0.295070350170136f, - 0.903423786163330f, -0.295379847288132f, 0.903197109699249f, - -0.295689195394516f, - 0.902970194816589f, -0.295998334884644f, 0.902743041515350f, - -0.296307325363159f, - 0.902515649795532f, -0.296616137027740f, 0.902288019657135f, - -0.296924799680710f, - 0.902060210704803f, -0.297233253717422f, 0.901832103729248f, - -0.297541528940201f, - 0.901603758335114f, -0.297849655151367f, 0.901375174522400f, - -0.298157602548599f, - 0.901146411895752f, -0.298465341329575f, 0.900917351245880f, - -0.298772931098938f, - 0.900688111782074f, -0.299080342054367f, 0.900458574295044f, - -0.299387603998184f, - 0.900228857994080f, -0.299694657325745f, 0.899998843669891f, - -0.300001531839371f, - 0.899768650531769f, -0.300308227539063f, 0.899538159370422f, - -0.300614774227142f, - 0.899307489395142f, -0.300921112298965f, 0.899076581001282f, - -0.301227301359177f, - 0.898845434188843f, -0.301533311605453f, 0.898614048957825f, - -0.301839113235474f, - 0.898382425308228f, -0.302144765853882f, 0.898150563240051f, - -0.302450239658356f, - 0.897918462753296f, -0.302755534648895f, 0.897686123847961f, - -0.303060621023178f, - 0.897453546524048f, -0.303365558385849f, 0.897220790386200f, - -0.303670316934586f, - 0.896987736225128f, -0.303974896669388f, 0.896754503250122f, - -0.304279297590256f, - 0.896520972251892f, -0.304583519697189f, 0.896287262439728f, - -0.304887533187866f, - 0.896053314208984f, -0.305191397666931f, 0.895819067955017f, - -0.305495083332062f, - 0.895584642887115f, -0.305798590183258f, 0.895349979400635f, - -0.306101888418198f, - 0.895115137100220f, -0.306405037641525f, 0.894879996776581f, - -0.306708008050919f, - 0.894644618034363f, -0.307010769844055f, 0.894409060478210f, - -0.307313382625580f, - 0.894173204898834f, -0.307615786790848f, 0.893937170505524f, - -0.307918041944504f, - 0.893700897693634f, -0.308220088481903f, 0.893464326858521f, - -0.308521956205368f, - 0.893227577209473f, -0.308823645114899f, 0.892990648746490f, - -0.309125155210495f, - 0.892753422260284f, -0.309426486492157f, 0.892515957355499f, - -0.309727638959885f, - 0.892278313636780f, -0.310028612613678f, 0.892040371894836f, - -0.310329377651215f, - 0.891802251338959f, -0.310629993677139f, 0.891563892364502f, - -0.310930401086807f, - 0.891325294971466f, -0.311230629682541f, 0.891086459159851f, - -0.311530679464340f, - 0.890847444534302f, -0.311830550432205f, 0.890608131885529f, - -0.312130242586136f, - 0.890368640422821f, -0.312429755926132f, 0.890128850936890f, - -0.312729060649872f, - 0.889888882637024f, -0.313028186559677f, 0.889648675918579f, - -0.313327133655548f, - 0.889408230781555f, -0.313625901937485f, 0.889167606830597f, - -0.313924491405487f, - 0.888926684856415f, -0.314222872257233f, 0.888685584068298f, - -0.314521104097366f, - 0.888444244861603f, -0.314819127321243f, 0.888202667236328f, - -0.315116971731186f, - 0.887960851192474f, -0.315414607524872f, 0.887718796730042f, - -0.315712094306946f, - 0.887476563453674f, -0.316009372472763f, 0.887234091758728f, - -0.316306471824646f, - 0.886991322040558f, -0.316603392362595f, 0.886748373508453f, - -0.316900104284287f, - 0.886505246162415f, -0.317196637392044f, 0.886261820793152f, - -0.317492991685867f, - 0.886018216609955f, -0.317789167165756f, 0.885774314403534f, - -0.318085134029388f, - 0.885530233383179f, -0.318380922079086f, 0.885285973548889f, - -0.318676531314850f, - 0.885041415691376f, -0.318971961736679f, 0.884796679019928f, - -0.319267183542252f, - 0.884551644325256f, -0.319562226533890f, 0.884306430816650f, - -0.319857090711594f, - 0.884061038494110f, -0.320151746273041f, 0.883815348148346f, - -0.320446223020554f, - 0.883569478988647f, -0.320740520954132f, 0.883323311805725f, - -0.321034610271454f, - 0.883076965808868f, -0.321328520774841f, 0.882830440998077f, - -0.321622252464294f, - 0.882583618164063f, -0.321915775537491f, 0.882336616516113f, - -0.322209119796753f, - 0.882089376449585f, -0.322502255439758f, 0.881841897964478f, - -0.322795242071152f, - 0.881594181060791f, -0.323088020086288f, 0.881346285343170f, - -0.323380589485168f, - 0.881098151206970f, -0.323672980070114f, 0.880849778652191f, - -0.323965191841125f, - 0.880601167678833f, -0.324257194995880f, 0.880352377891541f, - -0.324549019336700f, - 0.880103349685669f, -0.324840664863586f, 0.879854083061218f, - -0.325132101774216f, - 0.879604578018188f, -0.325423330068588f, 0.879354894161224f, - -0.325714409351349f, - 0.879104971885681f, -0.326005280017853f, 0.878854811191559f, - -0.326295942068100f, - 0.878604412078857f, -0.326586425304413f, 0.878353834152222f, - -0.326876699924469f, - 0.878103017807007f, -0.327166795730591f, 0.877851963043213f, - -0.327456712722778f, - 0.877600669860840f, -0.327746421098709f, 0.877349197864532f, - -0.328035950660706f, - 0.877097487449646f, -0.328325271606445f, 0.876845538616180f, - -0.328614413738251f, - 0.876593410968781f, -0.328903347253799f, 0.876341044902802f, - -0.329192101955414f, - 0.876088440418243f, -0.329480648040771f, 0.875835597515106f, - -0.329769015312195f, - 0.875582575798035f, -0.330057173967361f, 0.875329315662384f, - -0.330345153808594f, - 0.875075817108154f, -0.330632925033569f, 0.874822139739990f, - -0.330920487642288f, - 0.874568223953247f, -0.331207901239395f, 0.874314069747925f, - -0.331495076417923f, - 0.874059677124023f, -0.331782072782516f, 0.873805105686188f, - -0.332068890333176f, - 0.873550295829773f, -0.332355499267578f, 0.873295307159424f, - -0.332641899585724f, - 0.873040020465851f, -0.332928121089935f, 0.872784554958344f, - -0.333214133977890f, - 0.872528910636902f, -0.333499968051910f, 0.872272968292236f, - -0.333785593509674f, - 0.872016847133636f, -0.334071010351181f, 0.871760547161102f, - -0.334356248378754f, - 0.871503949165344f, -0.334641307592392f, 0.871247172355652f, - -0.334926128387451f, - 0.870990216732025f, -0.335210770368576f, 0.870733022689819f, - -0.335495233535767f, - 0.870475590229034f, -0.335779488086700f, 0.870217919349670f, - -0.336063534021378f, - 0.869960069656372f, -0.336347371339798f, 0.869701981544495f, - -0.336631029844284f, - 0.869443655014038f, -0.336914509534836f, 0.869185149669647f, - -0.337197750806808f, - 0.868926405906677f, -0.337480813264847f, 0.868667483329773f, - -0.337763696908951f, - 0.868408262729645f, -0.338046342134476f, 0.868148922920227f, - -0.338328808546066f, - 0.867889285087585f, -0.338611096143723f, 0.867629468441010f, - -0.338893145322800f, - 0.867369413375854f, -0.339175015687943f, 0.867109179496765f, - -0.339456677436829f, - 0.866848707199097f, -0.339738160371780f, 0.866588056087494f, - -0.340019434690475f, - 0.866327106952667f, -0.340300500392914f, 0.866066038608551f, - -0.340581357479095f, - 0.865804672241211f, -0.340862035751343f, 0.865543127059937f, - -0.341142505407333f, - 0.865281403064728f, -0.341422766447067f, 0.865019381046295f, - -0.341702848672867f, - 0.864757239818573f, -0.341982692480087f, 0.864494800567627f, - -0.342262357473373f, - 0.864232182502747f, -0.342541843652725f, 0.863969385623932f, - -0.342821091413498f, - 0.863706290721893f, -0.343100160360336f, 0.863443076610565f, - -0.343379020690918f, - 0.863179564476013f, -0.343657672405243f, 0.862915873527527f, - -0.343936115503311f, - 0.862652003765106f, -0.344214379787445f, 0.862387895584106f, - -0.344492435455322f, - 0.862123548984528f, -0.344770282506943f, 0.861859023571014f, - -0.345047920942307f, - 0.861594259738922f, -0.345325350761414f, 0.861329257488251f, - -0.345602601766586f, - 0.861064076423645f, -0.345879614353180f, 0.860798716545105f, - -0.346156448125839f, - 0.860533118247986f, -0.346433073282242f, 0.860267281532288f, - -0.346709519624710f, - 0.860001266002655f, -0.346985727548599f, 0.859735012054443f, - -0.347261756658554f, - 0.859468579292297f, -0.347537547349930f, 0.859201908111572f, - -0.347813159227371f, - 0.858934998512268f, -0.348088562488556f, 0.858667910099030f, - -0.348363757133484f, - 0.858400642871857f, -0.348638743162155f, 0.858133137226105f, - -0.348913550376892f, - 0.857865393161774f, -0.349188119173050f, 0.857597470283508f, - -0.349462509155273f, - 0.857329368591309f, -0.349736660718918f, 0.857060968875885f, - -0.350010633468628f, - 0.856792449951172f, -0.350284397602081f, 0.856523692607880f, - -0.350557953119278f, - 0.856254696846008f, -0.350831300020218f, 0.855985522270203f, - -0.351104438304901f, - 0.855716109275818f, -0.351377367973328f, 0.855446517467499f, - -0.351650089025497f, - 0.855176687240601f, -0.351922631263733f, 0.854906618595123f, - -0.352194935083389f, - 0.854636430740356f, -0.352467030286789f, 0.854365944862366f, - -0.352738946676254f, - 0.854095339775085f, -0.353010624647141f, 0.853824436664581f, - -0.353282123804092f, - 0.853553414344788f, -0.353553384542465f, 0.853282094001770f, - -0.353824466466904f, - 0.853010654449463f, -0.354095309972763f, 0.852738916873932f, - -0.354365974664688f, - 0.852467060089111f, -0.354636400938034f, 0.852194905281067f, - -0.354906648397446f, - 0.851922631263733f, -0.355176687240601f, 0.851650118827820f, - -0.355446487665176f, - 0.851377367973328f, -0.355716109275818f, 0.851104438304901f, - -0.355985492467880f, - 0.850831270217896f, -0.356254696846008f, 0.850557923316956f, - -0.356523662805557f, - 0.850284397602081f, -0.356792420148849f, 0.850010633468628f, - -0.357060998678207f, - 0.849736690521240f, -0.357329338788986f, 0.849462509155273f, - -0.357597470283508f, - 0.849188148975372f, -0.357865422964096f, 0.848913550376892f, - -0.358133137226105f, - 0.848638772964478f, -0.358400642871857f, 0.848363757133484f, - -0.358667939901352f, - 0.848088562488556f, -0.358935028314590f, 0.847813189029694f, - -0.359201908111572f, - 0.847537577152252f, -0.359468549489975f, 0.847261726856232f, - -0.359735012054443f, - 0.846985757350922f, -0.360001266002655f, 0.846709489822388f, - -0.360267281532288f, - 0.846433103084564f, -0.360533088445663f, 0.846156477928162f, - -0.360798716545105f, - 0.845879614353180f, -0.361064106225967f, 0.845602571964264f, - -0.361329287290573f, - 0.845325350761414f, -0.361594229936600f, 0.845047891139984f, - -0.361858993768692f, - 0.844770252704620f, -0.362123548984528f, 0.844492435455322f, - -0.362387865781784f, - 0.844214379787445f, -0.362651973962784f, 0.843936145305634f, - -0.362915903329849f, - 0.843657672405243f, -0.363179564476013f, 0.843379020690918f, - -0.363443046808243f, - 0.843100130558014f, -0.363706320524216f, 0.842821121215820f, - -0.363969355821610f, - 0.842541813850403f, -0.364232182502747f, 0.842262387275696f, - -0.364494800567627f, - 0.841982722282410f, -0.364757210016251f, 0.841702818870544f, - -0.365019410848618f, - 0.841422796249390f, -0.365281373262405f, 0.841142535209656f, - -0.365543156862259f, - 0.840862035751343f, -0.365804702043533f, 0.840581357479095f, - -0.366066008806229f, - 0.840300500392914f, -0.366327136754990f, 0.840019404888153f, - -0.366588026285172f, - 0.839738130569458f, -0.366848707199097f, 0.839456677436829f, - -0.367109179496765f, - 0.839175045490265f, -0.367369443178177f, 0.838893175125122f, - -0.367629468441010f, - 0.838611066341400f, -0.367889285087585f, 0.838328838348389f, - -0.368148893117905f, - 0.838046371936798f, -0.368408292531967f, 0.837763667106628f, - -0.368667453527451f, - 0.837480843067169f, -0.368926405906677f, 0.837197780609131f, - -0.369185149669647f, - 0.836914479732513f, -0.369443655014038f, 0.836631059646606f, - -0.369701951742172f, - 0.836347401142120f, -0.369960039854050f, 0.836063504219055f, - -0.370217919349670f, - 0.835779488086700f, -0.370475560426712f, 0.835495233535767f, - -0.370732992887497f, - 0.835210800170898f, -0.370990216732025f, 0.834926128387451f, - -0.371247202157974f, - 0.834641277790070f, -0.371503978967667f, 0.834356248378754f, - -0.371760547161102f, - 0.834071040153503f, -0.372016876935959f, 0.833785593509674f, - -0.372272998094559f, - 0.833499968051910f, -0.372528880834579f, 0.833214163780212f, - -0.372784584760666f, - 0.832928121089935f, -0.373040050268173f, 0.832641899585724f, - -0.373295277357101f, - 0.832355499267578f, -0.373550295829773f, 0.832068860530853f, - -0.373805105686188f, - 0.831782102584839f, -0.374059677124023f, 0.831495106220245f, - -0.374314039945602f, - 0.831207871437073f, -0.374568194150925f, 0.830920517444611f, - -0.374822109937668f, - 0.830632925033569f, -0.375075817108154f, 0.830345153808594f, - -0.375329315662384f, - 0.830057144165039f, -0.375582575798035f, 0.829769015312195f, - -0.375835597515106f, - 0.829480648040771f, -0.376088410615921f, 0.829192101955414f, - -0.376341015100479f, - 0.828903317451477f, -0.376593410968781f, 0.828614413738251f, - -0.376845568418503f, - 0.828325271606445f, -0.377097487449646f, 0.828035950660706f, - -0.377349197864532f, - 0.827746450901031f, -0.377600699663162f, 0.827456712722778f, - -0.377851963043213f, - 0.827166795730591f, -0.378102988004684f, 0.826876699924469f, - -0.378353834152222f, - 0.826586425304413f, -0.378604412078857f, 0.826295912265778f, - -0.378854811191559f, - 0.826005280017853f, -0.379104942083359f, 0.825714409351349f, - -0.379354894161224f, - 0.825423359870911f, -0.379604607820511f, 0.825132071971893f, - -0.379854083061218f, - 0.824840664863586f, -0.380103349685669f, 0.824549019336700f, - -0.380352377891541f, - 0.824257194995880f, -0.380601197481155f, 0.823965191841125f, - -0.380849778652191f, - 0.823673009872437f, -0.381098151206970f, 0.823380589485168f, - -0.381346285343170f, - 0.823087990283966f, -0.381594210863113f, 0.822795212268829f, - -0.381841897964478f, - 0.822502255439758f, -0.382089376449585f, 0.822209119796753f, - -0.382336616516113f, - 0.821915745735168f, -0.382583618164063f, 0.821622252464294f, - -0.382830440998077f, - 0.821328520774841f, -0.383076995611191f, 0.821034610271454f, - -0.383323341608047f, - 0.820740520954132f, -0.383569449186325f, 0.820446193218231f, - -0.383815348148346f, - 0.820151746273041f, -0.384061008691788f, 0.819857060909271f, - -0.384306460618973f, - 0.819562196731567f, -0.384551674127579f, 0.819267153739929f, - -0.384796649217606f, - 0.818971931934357f, -0.385041415691376f, 0.818676531314850f, - -0.385285943746567f, - 0.818380951881409f, -0.385530263185501f, 0.818085134029388f, - -0.385774344205856f, - 0.817789137363434f, -0.386018186807632f, 0.817493021488190f, - -0.386261820793152f, - 0.817196667194366f, -0.386505216360092f, 0.816900074481964f, - -0.386748403310776f, - 0.816603362560272f, -0.386991351842880f, 0.816306471824646f, - -0.387234061956406f, - 0.816009342670441f, -0.387476563453674f, 0.815712094306946f, - -0.387718826532364f, - 0.815414607524872f, -0.387960851192474f, 0.815116941928864f, - -0.388202667236328f, - 0.814819097518921f, -0.388444244861603f, 0.814521074295044f, - -0.388685584068298f, - 0.814222872257233f, -0.388926714658737f, 0.813924491405487f, - -0.389167606830597f, - 0.813625931739807f, -0.389408260583878f, 0.813327133655548f, - -0.389648675918579f, - 0.813028216362000f, -0.389888882637024f, 0.812729060649872f, - -0.390128880739212f, - 0.812429726123810f, -0.390368610620499f, 0.812130272388458f, - -0.390608131885529f, - 0.811830580234528f, -0.390847414731979f, 0.811530709266663f, - -0.391086459159851f, - 0.811230659484863f, -0.391325294971466f, 0.810930430889130f, - -0.391563892364502f, - 0.810629963874817f, -0.391802251338959f, 0.810329377651215f, - -0.392040401697159f, - 0.810028612613678f, -0.392278283834457f, 0.809727668762207f, - -0.392515957355499f, - 0.809426486492157f, -0.392753422260284f, 0.809125185012817f, - -0.392990618944168f, - 0.808823645114899f, -0.393227607011795f, 0.808521986007690f, - -0.393464356660843f, - 0.808220088481903f, -0.393700867891312f, 0.807918012142181f, - -0.393937170505524f, - 0.807615816593170f, -0.394173204898834f, 0.807313382625580f, - -0.394409030675888f, - 0.807010769844055f, -0.394644618034363f, 0.806707978248596f, - -0.394879996776581f, - 0.806405067443848f, -0.395115107297897f, 0.806101918220520f, - -0.395350009202957f, - 0.805798590183258f, -0.395584672689438f, 0.805495083332062f, - -0.395819097757339f, - 0.805191397666931f, -0.396053284406662f, 0.804887533187866f, - -0.396287262439728f, - 0.804583489894867f, -0.396520972251892f, 0.804279267787933f, - -0.396754473447800f, - 0.803974866867065f, -0.396987736225128f, 0.803670346736908f, - -0.397220760583878f, - 0.803365588188171f, -0.397453576326370f, 0.803060650825500f, - -0.397686123847961f, - 0.802755534648895f, -0.397918462753296f, 0.802450239658356f, - -0.398150533437729f, - 0.802144765853882f, -0.398382395505905f, 0.801839113235474f, - -0.398614019155502f, - 0.801533281803131f, -0.398845434188843f, 0.801227271556854f, - -0.399076581001282f, - 0.800921142101288f, -0.399307489395142f, 0.800614774227142f, - -0.399538189172745f, - 0.800308227539063f, -0.399768620729446f, 0.800001561641693f, - -0.399998843669891f, - 0.799694657325745f, -0.400228828191757f, 0.799387574195862f, - -0.400458574295044f, - 0.799080371856689f, -0.400688081979752f, 0.798772931098938f, - -0.400917351245880f, - 0.798465371131897f, -0.401146411895752f, 0.798157572746277f, - -0.401375204324722f, - 0.797849655151367f, -0.401603758335114f, 0.797541558742523f, - -0.401832103729248f, - 0.797233223915100f, -0.402060180902481f, 0.796924769878387f, - -0.402288049459457f, - 0.796616137027740f, -0.402515679597855f, 0.796307325363159f, - -0.402743041515350f, - 0.795998334884644f, -0.402970194816589f, 0.795689165592194f, - -0.403197109699249f, - 0.795379877090454f, -0.403423786163330f, 0.795070350170136f, - -0.403650224208832f, - 0.794760644435883f, -0.403876423835754f, 0.794450819492340f, - -0.404102355241776f, - 0.794140756130219f, -0.404328078031540f, 0.793830573558807f, - -0.404553562402725f, - 0.793520212173462f, -0.404778808355331f, 0.793209671974182f, - -0.405003815889359f, - 0.792898952960968f, -0.405228585004807f, 0.792588055133820f, - -0.405453115701675f, - 0.792276978492737f, -0.405677437782288f, 0.791965723037720f, - -0.405901491641998f, - 0.791654348373413f, -0.406125307083130f, 0.791342735290527f, - -0.406348884105682f, - 0.791031002998352f, -0.406572192907333f, 0.790719091892242f, - -0.406795293092728f, - 0.790407001972198f, -0.407018154859543f, 0.790094733238220f, - -0.407240778207779f, - 0.789782285690308f, -0.407463163137436f, 0.789469659328461f, - -0.407685309648514f, - 0.789156913757324f, -0.407907217741013f, 0.788843929767609f, - -0.408128857612610f, - 0.788530826568604f, -0.408350288867950f, 0.788217544555664f, - -0.408571451902390f, - 0.787904083728790f, -0.408792406320572f, 0.787590444087982f, - -0.409013092517853f, - 0.787276685237885f, -0.409233570098877f, 0.786962687969208f, - -0.409453779459000f, - 0.786648571491241f, -0.409673750400543f, 0.786334276199341f, - -0.409893482923508f, - 0.786019802093506f, -0.410112977027893f, 0.785705149173737f, - -0.410332232713699f, - 0.785390377044678f, -0.410551249980927f, 0.785075426101685f, - -0.410770028829575f, - 0.784760236740112f, -0.410988569259644f, 0.784444928169250f, - -0.411206841468811f, - 0.784129500389099f, -0.411424905061722f, 0.783813834190369f, - -0.411642700433731f, - 0.783498048782349f, -0.411860257387161f, 0.783182024955750f, - -0.412077575922012f, - 0.782865881919861f, -0.412294656038284f, 0.782549619674683f, - -0.412511497735977f, - 0.782233119010925f, -0.412728071212769f, 0.781916499137878f, - -0.412944436073303f, - 0.781599700450897f, -0.413160532712936f, 0.781282722949982f, - -0.413376390933990f, - 0.780965566635132f, -0.413592010736465f, 0.780648231506348f, - -0.413807392120361f, - 0.780330777168274f, -0.414022535085678f, 0.780013144016266f, - -0.414237409830093f, - 0.779695332050323f, -0.414452046155930f, 0.779377400875092f, - -0.414666473865509f, - 0.779059290885925f, -0.414880603551865f, 0.778741002082825f, - -0.415094524621964f, - 0.778422534465790f, -0.415308207273483f, 0.778103888034821f, - -0.415521621704102f, - 0.777785122394562f, -0.415734797716141f, 0.777466177940369f, - -0.415947735309601f, - 0.777147054672241f, -0.416160434484482f, 0.776827812194824f, - -0.416372895240784f, - 0.776508331298828f, -0.416585087776184f, 0.776188731193542f, - -0.416797041893005f, - 0.775869011878967f, -0.417008757591248f, 0.775549054145813f, - -0.417220205068588f, - 0.775228977203369f, -0.417431443929672f, 0.774908721446991f, - -0.417642414569855f, - 0.774588346481323f, -0.417853146791458f, 0.774267733097076f, - -0.418063640594482f, - 0.773947000503540f, -0.418273866176605f, 0.773626148700714f, - -0.418483853340149f, - 0.773305058479309f, -0.418693602085114f, 0.772983849048615f, - -0.418903112411499f, - 0.772662520408630f, -0.419112354516983f, 0.772340953350067f, - -0.419321358203888f, - 0.772019267082214f, -0.419530123472214f, 0.771697402000427f, - -0.419738620519638f, - 0.771375417709351f, -0.419946908950806f, 0.771053194999695f, - -0.420154929161072f, - 0.770730912685394f, -0.420362681150436f, 0.770408391952515f, - -0.420570224523544f, - 0.770085752010345f, -0.420777499675751f, 0.769762933254242f, - -0.420984506607056f, - 0.769439935684204f, -0.421191304922104f, 0.769116818904877f, - -0.421397835016251f, - 0.768793523311615f, -0.421604126691818f, 0.768470108509064f, - -0.421810150146484f, - 0.768146514892578f, -0.422015935182571f, 0.767822742462158f, - -0.422221481800079f, - 0.767498791217804f, -0.422426789999008f, 0.767174720764160f, - -0.422631829977036f, - 0.766850471496582f, -0.422836631536484f, 0.766526103019714f, - -0.423041164875031f, - 0.766201555728912f, -0.423245459794998f, 0.765876889228821f, - -0.423449516296387f, - 0.765551984310150f, -0.423653304576874f, 0.765226960182190f, - -0.423856884241104f, - 0.764901816844940f, -0.424060165882111f, 0.764576494693756f, - -0.424263238906860f, - 0.764250993728638f, -0.424466013908386f, 0.763925373554230f, - -0.424668580293655f, - 0.763599574565887f, -0.424870878458023f, 0.763273596763611f, - -0.425072938203812f, - 0.762947499752045f, -0.425274729728699f, 0.762621283531189f, - -0.425476282835007f, - 0.762294828891754f, -0.425677597522736f, 0.761968255043030f, - -0.425878643989563f, - 0.761641561985016f, -0.426079452037811f, 0.761314690113068f, - -0.426279991865158f, - 0.760987639427185f, -0.426480293273926f, 0.760660469532013f, - -0.426680356264114f, - 0.760333120822906f, -0.426880151033401f, 0.760005652904511f, - -0.427079707384110f, - 0.759678006172180f, -0.427278995513916f, 0.759350180625916f, - -0.427478045225143f, - 0.759022235870361f, -0.427676826715469f, 0.758694171905518f, - -0.427875369787216f, - 0.758365929126740f, -0.428073674440384f, 0.758037507534027f, - -0.428271710872650f, - 0.757708966732025f, -0.428469479084015f, 0.757380247116089f, - -0.428667008876801f, - 0.757051348686218f, -0.428864300251007f, 0.756722390651703f, - -0.429061323404312f, - 0.756393194198608f, -0.429258108139038f, 0.756063878536224f, - -0.429454624652863f, - 0.755734443664551f, -0.429650902748108f, 0.755404829978943f, - -0.429846942424774f, - 0.755075037479401f, -0.430042684078217f, 0.754745125770569f, - -0.430238217115402f, - 0.754415094852448f, -0.430433481931686f, 0.754084885120392f, - -0.430628478527069f, - 0.753754496574402f, -0.430823236703873f, 0.753423988819122f, - -0.431017726659775f, - 0.753093302249908f, -0.431211978197098f, 0.752762496471405f, - -0.431405961513519f, - 0.752431571483612f, -0.431599706411362f, 0.752100467681885f, - -0.431793183088303f, - 0.751769185066223f, -0.431986421346664f, 0.751437783241272f, - -0.432179391384125f, - 0.751106262207031f, -0.432372123003006f, 0.750774562358856f, - -0.432564586400986f, - 0.750442683696747f, -0.432756811380386f, 0.750110685825348f, - -0.432948768138886f, - 0.749778568744659f, -0.433140486478806f, 0.749446272850037f, - -0.433331936597824f, - 0.749113857746124f, -0.433523118495941f, 0.748781263828278f, - -0.433714061975479f, - 0.748448550701141f, -0.433904737234116f, 0.748115658760071f, - -0.434095174074173f, - 0.747782647609711f, -0.434285342693329f, 0.747449457645416f, - -0.434475272893906f, - 0.747116148471832f, -0.434664934873581f, 0.746782720088959f, - -0.434854328632355f, - 0.746449112892151f, -0.435043483972549f, 0.746115326881409f, - -0.435232400894165f, - 0.745781481266022f, -0.435421019792557f, 0.745447397232056f, - -0.435609430074692f, - 0.745113253593445f, -0.435797542333603f, 0.744778931140900f, - -0.435985416173935f, - 0.744444429874420f, -0.436173021793365f, 0.744109809398651f, - -0.436360388994217f, - 0.743775069713593f, -0.436547487974167f, 0.743440151214600f, - -0.436734348535538f, - 0.743105113506317f, -0.436920911073685f, 0.742769956588745f, - -0.437107264995575f, - 0.742434620857239f, -0.437293320894241f, 0.742099165916443f, - -0.437479138374329f, - 0.741763532161713f, -0.437664687633514f, 0.741427779197693f, - -0.437849998474121f, - 0.741091907024384f, -0.438035041093826f, 0.740755856037140f, - -0.438219845294952f, - 0.740419685840607f, -0.438404351472855f, 0.740083336830139f, - -0.438588619232178f, - 0.739746868610382f, -0.438772648572922f, 0.739410281181335f, - -0.438956409692764f, - 0.739073514938354f, -0.439139902591705f, 0.738736629486084f, - -0.439323127269745f, - 0.738399624824524f, -0.439506113529205f, 0.738062441349030f, - -0.439688831567764f, - 0.737725138664246f, -0.439871311187744f, 0.737387716770172f, - -0.440053492784500f, - 0.737050116062164f, -0.440235435962677f, 0.736712396144867f, - -0.440417140722275f, - 0.736374497413635f, -0.440598547458649f, 0.736036539077759f, - -0.440779715776443f, - 0.735698342323303f, -0.440960645675659f, 0.735360085964203f, - -0.441141277551651f, - 0.735021650791168f, -0.441321671009064f, 0.734683096408844f, - -0.441501796245575f, - 0.734344422817230f, -0.441681683063507f, 0.734005570411682f, - -0.441861271858215f, - 0.733666598796844f, -0.442040622234344f, 0.733327507972717f, - -0.442219734191895f, - 0.732988238334656f, -0.442398548126221f, 0.732648849487305f, - -0.442577123641968f, - 0.732309341430664f, -0.442755430936813f, 0.731969714164734f, - -0.442933470010757f, - 0.731629908084869f, -0.443111270666122f, 0.731289982795715f, - -0.443288803100586f, - 0.730949878692627f, -0.443466067314148f, 0.730609714984894f, - -0.443643063306808f, - 0.730269372463226f, -0.443819820880890f, 0.729928910732269f, - -0.443996280431747f, - 0.729588270187378f, -0.444172531366348f, 0.729247510433197f, - -0.444348484277725f, - 0.728906631469727f, -0.444524168968201f, 0.728565633296967f, - -0.444699615240097f, - 0.728224515914917f, -0.444874793291092f, 0.727883219718933f, - -0.445049703121185f, - 0.727541804313660f, -0.445224374532700f, 0.727200269699097f, - -0.445398747920990f, - 0.726858556270599f, -0.445572882890701f, 0.726516723632813f, - -0.445746749639511f, - 0.726174771785736f, -0.445920348167419f, 0.725832700729370f, - -0.446093708276749f, - 0.725490510463715f, -0.446266770362854f, 0.725148141384125f, - -0.446439594030380f, - 0.724805653095245f, -0.446612149477005f, 0.724463045597076f, - -0.446784436702728f, - 0.724120318889618f, -0.446956485509872f, 0.723777413368225f, - -0.447128236293793f, - 0.723434448242188f, -0.447299748659134f, 0.723091304302216f, - -0.447470992803574f, - 0.722747981548309f, -0.447641968727112f, 0.722404599189758f, - -0.447812676429749f, - 0.722061097621918f, -0.447983115911484f, 0.721717417240143f, - -0.448153316974640f, - 0.721373617649078f, -0.448323249816895f, 0.721029698848724f, - -0.448492884635925f, - 0.720685660839081f, -0.448662281036377f, 0.720341444015503f, - -0.448831409215927f, - 0.719997107982636f, -0.449000298976898f, 0.719652712345123f, - -0.449168890714645f, - 0.719308137893677f, -0.449337244033813f, 0.718963444232941f, - -0.449505299329758f, - 0.718618571758270f, -0.449673116207123f, 0.718273639678955f, - -0.449840664863586f, - 0.717928528785706f, -0.450007945299149f, 0.717583298683167f, - -0.450174957513809f, - 0.717238008975983f, -0.450341701507568f, 0.716892480850220f, - -0.450508207082748f, - 0.716546893119812f, -0.450674414634705f, 0.716201186180115f, - -0.450840383768082f, - 0.715855300426483f, -0.451006084680557f, 0.715509355068207f, - -0.451171487569809f, - 0.715163230895996f, -0.451336652040482f, 0.714816987514496f, - -0.451501548290253f, - 0.714470624923706f, -0.451666176319122f, 0.714124143123627f, - -0.451830536127090f, - 0.713777542114258f, -0.451994657516479f, 0.713430821895599f, - -0.452158480882645f, - 0.713083922863007f, -0.452322036027908f, 0.712736964225769f, - -0.452485352754593f, - 0.712389826774597f, -0.452648371458054f, 0.712042629718781f, - -0.452811151742935f, - 0.711695253849030f, -0.452973634004593f, 0.711347758769989f, - -0.453135877847672f, - 0.711000144481659f, -0.453297853469849f, 0.710652410984039f, - -0.453459560871124f, - 0.710304558277130f, -0.453621000051498f, 0.709956526756287f, - -0.453782171010971f, - 0.709608435630798f, -0.453943043947220f, 0.709260225296021f, - -0.454103678464890f, - 0.708911836147308f, -0.454264044761658f, 0.708563387393951f, - -0.454424172639847f, - 0.708214759826660f, -0.454584002494812f, 0.707866072654724f, - -0.454743564128876f, - 0.707517206668854f, -0.454902857542038f, 0.707168221473694f, - -0.455061882734299f, - 0.706819176673889f, -0.455220639705658f, 0.706469953060150f, - -0.455379128456116f, - 0.706120610237122f, -0.455537378787994f, 0.705771148204803f, - -0.455695331096649f, - 0.705421566963196f, -0.455853015184402f, 0.705071866512299f, - -0.456010431051254f, - 0.704722046852112f, -0.456167578697205f, 0.704372167587280f, - -0.456324487924576f, - 0.704022109508514f, -0.456481099128723f, 0.703671932220459f, - -0.456637442111969f, - 0.703321635723114f, -0.456793516874313f, 0.702971220016479f, - -0.456949323415756f, - 0.702620685100555f, -0.457104891538620f, 0.702270030975342f, - -0.457260161638260f, - 0.701919257640839f, -0.457415163516998f, 0.701568365097046f, - -0.457569897174835f, - 0.701217353343964f, -0.457724362611771f, 0.700866222381592f, - -0.457878559827805f, - 0.700514972209930f, -0.458032488822937f, 0.700163602828979f, - -0.458186149597168f, - 0.699812114238739f, -0.458339542150497f, 0.699460506439209f, - -0.458492636680603f, - 0.699108779430389f, -0.458645492792130f, 0.698756933212280f, - -0.458798080682755f, - 0.698404967784882f, -0.458950400352478f, 0.698052942752838f, - -0.459102421998978f, - 0.697700738906860f, -0.459254205226898f, 0.697348415851593f, - -0.459405690431595f, - 0.696996033191681f, -0.459556937217712f, 0.696643471717834f, - -0.459707885980606f, - 0.696290850639343f, -0.459858566522598f, 0.695938050746918f, - -0.460008978843689f, - 0.695585191249847f, -0.460159152746201f, 0.695232212543488f, - -0.460309028625488f, - 0.694879114627838f, -0.460458606481552f, 0.694525837898254f, - -0.460607945919037f, - 0.694172501564026f, -0.460757017135620f, 0.693819046020508f, - -0.460905820131302f, - 0.693465530872345f, -0.461054325103760f, 0.693111836910248f, - -0.461202591657639f, - 0.692758023738861f, -0.461350560188293f, 0.692404091358185f, - -0.461498260498047f, - 0.692050099372864f, -0.461645722389221f, 0.691695988178253f, - -0.461792886257172f, - 0.691341698169708f, -0.461939752101898f, 0.690987348556519f, - -0.462086379528046f, - 0.690632879734039f, -0.462232738733292f, 0.690278291702271f, - -0.462378799915314f, - 0.689923584461212f, -0.462524622678757f, 0.689568817615509f, - -0.462670147418976f, - 0.689213871955872f, -0.462815403938293f, 0.688858866691589f, - -0.462960392236710f, - 0.688503682613373f, -0.463105112314224f, 0.688148438930511f, - -0.463249564170837f, - 0.687793076038361f, -0.463393747806549f, 0.687437593936920f, - -0.463537633419037f, - 0.687082052230835f, -0.463681250810623f, 0.686726331710815f, - -0.463824629783630f, - 0.686370551586151f, -0.463967710733414f, 0.686014592647552f, - -0.464110493659973f, - 0.685658574104309f, -0.464253038167953f, 0.685302436351776f, - -0.464395314455032f, - 0.684946238994598f, -0.464537292718887f, 0.684589862823486f, - -0.464679002761841f, - 0.684233427047729f, -0.464820444583893f, 0.683876872062683f, - -0.464961618185043f, - 0.683520197868347f, -0.465102523565292f, 0.683163404464722f, - -0.465243130922318f, - 0.682806491851807f, -0.465383470058441f, 0.682449519634247f, - -0.465523540973663f, - 0.682092368602753f, -0.465663343667984f, 0.681735157966614f, - -0.465802878141403f, - 0.681377887725830f, -0.465942144393921f, 0.681020438671112f, - -0.466081112623215f, - 0.680662930011749f, -0.466219812631607f, 0.680305242538452f, - -0.466358244419098f, - 0.679947495460510f, -0.466496407985687f, 0.679589688777924f, - -0.466634273529053f, - 0.679231703281403f, -0.466771900653839f, 0.678873658180237f, - -0.466909229755402f, - 0.678515493869781f, -0.467046260833740f, 0.678157210350037f, - -0.467183053493500f, - 0.677798807621002f, -0.467319577932358f, 0.677440345287323f, - -0.467455804347992f, - 0.677081763744354f, -0.467591762542725f, 0.676723062992096f, - -0.467727422714233f, - 0.676364302635193f, -0.467862844467163f, 0.676005363464355f, - -0.467997968196869f, - 0.675646364688873f, -0.468132823705673f, 0.675287246704102f, - -0.468267410993576f, - 0.674928069114685f, -0.468401730060577f, 0.674568772315979f, - -0.468535751104355f, - 0.674209356307983f, -0.468669503927231f, 0.673849821090698f, - -0.468802988529205f, - 0.673490226268768f, -0.468936175107956f, 0.673130512237549f, - -0.469069123268127f, - 0.672770678997040f, -0.469201773405075f, 0.672410726547241f, - -0.469334155321121f, - 0.672050714492798f, -0.469466239213943f, 0.671690583229065f, - -0.469598054885864f, - 0.671330332756042f, -0.469729602336884f, 0.670970022678375f, - -0.469860881567001f, - 0.670609593391418f, -0.469991862773895f, 0.670249044895172f, - -0.470122605562210f, - 0.669888436794281f, -0.470253020524979f, 0.669527709484100f, - -0.470383197069168f, - 0.669166862964630f, -0.470513075590134f, 0.668805956840515f, - -0.470642685890198f, - 0.668444931507111f, -0.470772027969360f, 0.668083786964417f, - -0.470901101827621f, - 0.667722582817078f, -0.471029877662659f, 0.667361259460449f, - -0.471158385276794f, - 0.666999816894531f, -0.471286594867706f, 0.666638314723969f, - -0.471414536237717f, - 0.666276693344116f, -0.471542209386826f, 0.665914952754974f, - -0.471669614315033f, - 0.665553152561188f, -0.471796721220016f, 0.665191233158112f, - -0.471923559904099f, - 0.664829254150391f, -0.472050130367279f, 0.664467096328735f, - -0.472176402807236f, - 0.664104938507080f, -0.472302407026291f, 0.663742601871490f, - -0.472428143024445f, - 0.663380205631256f, -0.472553610801697f, 0.663017749786377f, - -0.472678780555725f, - 0.662655174732208f, -0.472803652286530f, 0.662292480468750f, - -0.472928285598755f, - 0.661929666996002f, -0.473052620887756f, 0.661566793918610f, - -0.473176687955856f, - 0.661203861236572f, -0.473300457000732f, 0.660840749740601f, - -0.473423957824707f, - 0.660477638244629f, -0.473547190427780f, 0.660114347934723f, - -0.473670125007629f, - 0.659750998020172f, -0.473792791366577f, 0.659387588500977f, - -0.473915189504623f, - 0.659024059772491f, -0.474037289619446f, 0.658660411834717f, - -0.474159121513367f, - 0.658296704292297f, -0.474280685186386f, 0.657932877540588f, - -0.474401950836182f, - 0.657568991184235f, -0.474522948265076f, 0.657204985618591f, - -0.474643647670746f, - 0.656840860843658f, -0.474764078855515f, 0.656476676464081f, - -0.474884241819382f, - 0.656112432479858f, -0.475004136562347f, 0.655748009681702f, - -0.475123733282089f, - 0.655383586883545f, -0.475243031978607f, 0.655019044876099f, - -0.475362062454224f, - 0.654654383659363f, -0.475480824708939f, 0.654289662837982f, - -0.475599318742752f, - 0.653924822807312f, -0.475717514753342f, 0.653559923171997f, - -0.475835442543030f, - 0.653194904327393f, -0.475953072309494f, 0.652829825878143f, - -0.476070433855057f, - 0.652464628219604f, -0.476187497377396f, 0.652099311351776f, - -0.476304292678833f, - 0.651733994483948f, -0.476420819759369f, 0.651368498802185f, - -0.476537048816681f, - 0.651003003120422f, -0.476653009653091f, 0.650637328624725f, - -0.476768702268600f, - 0.650271594524384f, -0.476884096860886f, 0.649905800819397f, - -0.476999223232269f, - 0.649539887905121f, -0.477114051580429f, 0.649173915386200f, - -0.477228611707687f, - 0.648807883262634f, -0.477342873811722f, 0.648441672325134f, - -0.477456867694855f, - 0.648075461387634f, -0.477570593357086f, 0.647709131240845f, - -0.477684020996094f, - 0.647342681884766f, -0.477797180414200f, 0.646976172924042f, - -0.477910041809082f, - 0.646609604358673f, -0.478022634983063f, 0.646242916584015f, - -0.478134930133820f, - 0.645876109600067f, -0.478246957063675f, 0.645509302616119f, - -0.478358715772629f, - 0.645142316818237f, -0.478470176458359f, 0.644775331020355f, - -0.478581339120865f, - 0.644408226013184f, -0.478692263364792f, 0.644041001796722f, - -0.478802859783173f, - 0.643673717975616f, -0.478913217782974f, 0.643306374549866f, - -0.479023247957230f, - 0.642938911914825f, -0.479133039712906f, 0.642571389675140f, - -0.479242533445358f, - 0.642203748226166f, -0.479351729154587f, 0.641836047172546f, - -0.479460656642914f, - 0.641468286514282f, -0.479569315910339f, 0.641100406646729f, - -0.479677677154541f, - 0.640732467174530f, -0.479785770177841f, 0.640364408493042f, - -0.479893565177917f, - 0.639996349811554f, -0.480001062154770f, 0.639628112316132f, - -0.480108320713043f, - 0.639259815216064f, -0.480215251445770f, 0.638891458511353f, - -0.480321943759918f, - 0.638523042201996f, -0.480428308248520f, 0.638154506683350f, - -0.480534434318542f, - 0.637785911560059f, -0.480640232563019f, 0.637417197227478f, - -0.480745792388916f, - 0.637048482894897f, -0.480851024389267f, 0.636679589748383f, - -0.480956017971039f, - 0.636310696601868f, -0.481060713529587f, 0.635941684246063f, - -0.481165111064911f, - 0.635572552680969f, -0.481269240379334f, 0.635203421115875f, - -0.481373071670532f, - 0.634834170341492f, -0.481476634740829f, 0.634464859962463f, - -0.481579899787903f, - 0.634095430374146f, -0.481682896614075f, 0.633725941181183f, - -0.481785595417023f, - 0.633356392383575f, -0.481888025999069f, 0.632986724376678f, - -0.481990188360214f, - 0.632616996765137f, -0.482092022895813f, 0.632247209548950f, - -0.482193619012833f, - 0.631877362728119f, -0.482294887304306f, 0.631507396697998f, - -0.482395917177200f, - 0.631137371063232f, -0.482496619224548f, 0.630767226219177f, - -0.482597053050995f, - 0.630397081375122f, -0.482697218656540f, 0.630026817321777f, - -0.482797086238861f, - 0.629656434059143f, -0.482896685600281f, 0.629286050796509f, - -0.482995986938477f, - 0.628915548324585f, -0.483094990253448f, 0.628544986248016f, - -0.483193725347519f, - 0.628174364566803f, -0.483292192220688f, 0.627803623676300f, - -0.483390361070633f, - 0.627432823181152f, -0.483488231897354f, 0.627061963081360f, - -0.483585834503174f, - 0.626691043376923f, -0.483683139085770f, 0.626320004463196f, - -0.483780175447464f, - 0.625948905944824f, -0.483876913785934f, 0.625577747821808f, - -0.483973383903503f, - 0.625206530094147f, -0.484069555997849f, 0.624835193157196f, - -0.484165430068970f, - 0.624463796615601f, -0.484261035919189f, 0.624092340469360f, - -0.484356373548508f, - 0.623720824718475f, -0.484451413154602f, 0.623349189758301f, - -0.484546154737473f, - 0.622977554798126f, -0.484640628099442f, 0.622605800628662f, - -0.484734803438187f, - 0.622233927249908f, -0.484828680753708f, 0.621862053871155f, - -0.484922289848328f, - 0.621490061283112f, -0.485015630722046f, 0.621118068695068f, - -0.485108673572540f, - 0.620745956897736f, -0.485201418399811f, 0.620373785495758f, - -0.485293895006180f, - 0.620001494884491f, -0.485386073589325f, 0.619629204273224f, - -0.485477954149246f, - 0.619256794452667f, -0.485569566488266f, 0.618884325027466f, - -0.485660910606384f, - 0.618511795997620f, -0.485751956701279f, 0.618139207363129f, - -0.485842704772949f, - 0.617766559123993f, -0.485933154821396f, 0.617393791675568f, - -0.486023366451263f, - 0.617020964622498f, -0.486113250255585f, 0.616648077964783f, - -0.486202865839005f, - 0.616275131702423f, -0.486292183399200f, 0.615902125835419f, - -0.486381232738495f, - 0.615529060363770f, -0.486469984054565f, 0.615155875682831f, - -0.486558437347412f, - 0.614782691001892f, -0.486646622419357f, 0.614409387111664f, - -0.486734509468079f, - 0.614036023616791f, -0.486822128295898f, 0.613662600517273f, - -0.486909449100494f, - 0.613289117813110f, -0.486996471881866f, 0.612915575504303f, - -0.487083226442337f, - 0.612541973590851f, -0.487169682979584f, 0.612168252468109f, - -0.487255871295929f, - 0.611794531345367f, -0.487341761589050f, 0.611420691013336f, - -0.487427353858948f, - 0.611046791076660f, -0.487512677907944f, 0.610672831535339f, - -0.487597703933716f, - 0.610298871994019f, -0.487682431936264f, 0.609924793243408f, - -0.487766891717911f, - 0.609550595283508f, -0.487851053476334f, 0.609176397323608f, - -0.487934947013855f, - 0.608802139759064f, -0.488018542528152f, 0.608427822589874f, - -0.488101840019226f, - 0.608053386211395f, -0.488184869289398f, 0.607678949832916f, - -0.488267600536346f, - 0.607304394245148f, -0.488350033760071f, 0.606929838657379f, - -0.488432198762894f, - 0.606555163860321f, -0.488514065742493f, 0.606180429458618f, - -0.488595664501190f, - 0.605805635452271f, -0.488676935434341f, 0.605430841445923f, - -0.488757967948914f, - 0.605055928230286f, -0.488838672637939f, 0.604680955410004f, - -0.488919109106064f, - 0.604305922985077f, -0.488999247550964f, 0.603930830955505f, - -0.489079117774963f, - 0.603555679321289f, -0.489158689975739f, 0.603180468082428f, - -0.489237964153290f, - 0.602805197238922f, -0.489316970109940f, 0.602429866790771f, - -0.489395678043365f, - 0.602054476737976f, -0.489474087953568f, 0.601679027080536f, - -0.489552229642868f, - 0.601303517818451f, -0.489630073308945f, 0.600927948951721f, - -0.489707618951797f, - 0.600552320480347f, -0.489784896373749f, 0.600176632404327f, - -0.489861875772476f, - 0.599800884723663f, -0.489938557147980f, 0.599425077438354f, - -0.490014940500259f, - 0.599049210548401f, -0.490091055631638f, 0.598673284053802f, - -0.490166902542114f, - 0.598297297954559f, -0.490242421627045f, 0.597921252250671f, - -0.490317672491074f, - 0.597545146942139f, -0.490392625331879f, 0.597168982028961f, - -0.490467309951782f, - 0.596792817115784f, -0.490541696548462f, 0.596416532993317f, - -0.490615785121918f, - 0.596040189266205f, -0.490689605474472f, 0.595663845539093f, - -0.490763127803802f, - 0.595287382602692f, -0.490836352109909f, 0.594910860061646f, - -0.490909278392792f, - 0.594534337520599f, -0.490981936454773f, 0.594157755374908f, - -0.491054296493530f, - 0.593781054019928f, -0.491126358509064f, 0.593404352664948f, - -0.491198152303696f, - 0.593027591705322f, -0.491269648075104f, 0.592650771141052f, - -0.491340845823288f, - 0.592273890972137f, -0.491411775350571f, 0.591896951198578f, - -0.491482406854630f, - 0.591519951820374f, -0.491552740335464f, 0.591142892837524f, - -0.491622805595398f, - 0.590765833854675f, -0.491692543029785f, 0.590388655662537f, - -0.491762012243271f, - 0.590011477470398f, -0.491831213235855f, 0.589634180068970f, - -0.491900116205215f, - 0.589256882667542f, -0.491968721151352f, 0.588879525661469f, - -0.492037028074265f, - 0.588502109050751f, -0.492105036973953f, 0.588124632835388f, - -0.492172777652740f, - 0.587747097015381f, -0.492240220308304f, 0.587369561195374f, - -0.492307394742966f, - 0.586991965770721f, -0.492374241352081f, 0.586614251136780f, - -0.492440819740295f, - 0.586236536502838f, -0.492507129907608f, 0.585858762264252f, - -0.492573112249374f, - 0.585480928421021f, -0.492638826370239f, 0.585103094577789f, - -0.492704242467880f, - 0.584725141525269f, -0.492769360542297f, 0.584347188472748f, - -0.492834210395813f, - 0.583969175815582f, -0.492898762226105f, 0.583591103553772f, - -0.492963016033173f, - 0.583212971687317f, -0.493026971817017f, 0.582834780216217f, - -0.493090659379959f, - 0.582456588745117f, -0.493154048919678f, 0.582078278064728f, - -0.493217140436172f, - 0.581699967384338f, -0.493279963731766f, 0.581321597099304f, - -0.493342459201813f, - 0.580943167209625f, -0.493404686450958f, 0.580564737319946f, - -0.493466645479202f, - 0.580186247825623f, -0.493528276681900f, 0.579807698726654f, - -0.493589639663696f, - 0.579429090023041f, -0.493650704622269f, 0.579050421714783f, - -0.493711471557617f, - 0.578671753406525f, -0.493771970272064f, 0.578292965888977f, - -0.493832170963287f, - 0.577914178371429f, -0.493892073631287f, 0.577535390853882f, - -0.493951678276062f, - 0.577156484127045f, -0.494011014699936f, 0.576777577400208f, - -0.494070053100586f, - 0.576398611068726f, -0.494128793478012f, 0.576019585132599f, - -0.494187235832214f, - 0.575640499591827f, -0.494245409965515f, 0.575261414051056f, - -0.494303256273270f, - 0.574882268905640f, -0.494360834360123f, 0.574503064155579f, - -0.494418144226074f, - 0.574123859405518f, -0.494475126266479f, 0.573744535446167f, - -0.494531840085983f, - 0.573365211486816f, -0.494588255882263f, 0.572985887527466f, - -0.494644373655319f, - 0.572606444358826f, -0.494700223207474f, 0.572227001190186f, - -0.494755744934082f, - 0.571847498416901f, -0.494810998439789f, 0.571467995643616f, - -0.494865983724594f, - 0.571088373661041f, -0.494920641183853f, 0.570708811283112f, - -0.494975030422211f, - 0.570329129695892f, -0.495029091835022f, 0.569949388504028f, - -0.495082914829254f, - 0.569569647312164f, -0.495136409997940f, 0.569189906120300f, - -0.495189607143402f, - 0.568810045719147f, -0.495242536067963f, 0.568430185317993f, - -0.495295166969299f, - 0.568050265312195f, -0.495347499847412f, 0.567670345306396f, - -0.495399564504623f, - 0.567290365695953f, -0.495451331138611f, 0.566910326480865f, - -0.495502769947052f, - 0.566530287265778f, -0.495553970336914f, 0.566150128841400f, - -0.495604842901230f, - 0.565770030021667f, -0.495655417442322f, 0.565389811992645f, - -0.495705723762512f, - 0.565009593963623f, -0.495755732059479f, 0.564629375934601f, - -0.495805442333221f, - 0.564249038696289f, -0.495854884386063f, 0.563868701457977f, - -0.495903998613358f, - 0.563488364219666f, -0.495952844619751f, 0.563107967376709f, - -0.496001392602921f, - 0.562727510929108f, -0.496049642562866f, 0.562346994876862f, - -0.496097624301910f, - 0.561966478824615f, -0.496145308017731f, 0.561585903167725f, - -0.496192663908005f, - 0.561205327510834f, -0.496239781379700f, 0.560824692249298f, - -0.496286571025848f, - 0.560444056987762f, -0.496333062648773f, 0.560063362121582f, - -0.496379286050797f, - 0.559682607650757f, -0.496425211429596f, 0.559301853179932f, - -0.496470838785172f, - 0.558921039104462f, -0.496516168117523f, 0.558540165424347f, - -0.496561229228973f, - 0.558159291744232f, -0.496605962514877f, 0.557778418064117f, - -0.496650427579880f, - 0.557397484779358f, -0.496694594621658f, 0.557016491889954f, - -0.496738493442535f, - 0.556635499000549f, -0.496782064437866f, 0.556254446506500f, - -0.496825367212296f, - 0.555873334407806f, -0.496868371963501f, 0.555492222309113f, - -0.496911078691483f, - 0.555111110210419f, -0.496953487396240f, 0.554729938507080f, - -0.496995598077774f, - 0.554348707199097f, -0.497037440538406f, 0.553967475891113f, - -0.497078984975815f, - 0.553586184978485f, -0.497120231389999f, 0.553204894065857f, - -0.497161179780960f, - 0.552823603153229f, -0.497201830148697f, 0.552442193031311f, - -0.497242212295532f, - 0.552060842514038f, -0.497282296419144f, 0.551679372787476f, - -0.497322082519531f, - 0.551297962665558f, -0.497361570596695f, 0.550916433334351f, - -0.497400760650635f, - 0.550534904003143f, -0.497439652681351f, 0.550153374671936f, - -0.497478276491165f, - 0.549771785736084f, -0.497516602277756f, 0.549390196800232f, - -0.497554630041122f, - 0.549008548259735f, -0.497592359781265f, 0.548626899719238f, - -0.497629791498184f, - 0.548245191574097f, -0.497666954994202f, 0.547863483428955f, - -0.497703820466995f, - 0.547481775283813f, -0.497740387916565f, 0.547099947929382f, - -0.497776657342911f, - 0.546718180179596f, -0.497812628746033f, 0.546336352825165f, - -0.497848302125931f, - 0.545954465866089f, -0.497883707284927f, 0.545572578907013f, - -0.497918814420700f, - 0.545190691947937f, -0.497953623533249f, 0.544808745384216f, - -0.497988134622574f, - 0.544426798820496f, -0.498022347688675f, 0.544044792652130f, - -0.498056292533875f, - 0.543662786483765f, -0.498089909553528f, 0.543280720710754f, - -0.498123258352280f, - 0.542898654937744f, -0.498156309127808f, 0.542516589164734f, - -0.498189061880112f, - 0.542134463787079f, -0.498221516609192f, 0.541752278804779f, - -0.498253703117371f, - 0.541370153427124f, -0.498285561800003f, 0.540987968444824f, - -0.498317152261734f, - 0.540605723857880f, -0.498348444700241f, 0.540223479270935f, - -0.498379439115524f, - 0.539841234683990f, -0.498410135507584f, 0.539458930492401f, - -0.498440563678741f, - 0.539076626300812f, -0.498470664024353f, 0.538694262504578f, - -0.498500496149063f, - 0.538311958312988f, -0.498530030250549f, 0.537929534912109f, - -0.498559266328812f, - 0.537547171115875f, -0.498588204383850f, 0.537164747714996f, - -0.498616874217987f, - 0.536782264709473f, -0.498645216226578f, 0.536399841308594f, - -0.498673290014267f, - 0.536017298698425f, -0.498701065778732f, 0.535634815692902f, - -0.498728543519974f, - 0.535252273082733f, -0.498755723237991f, 0.534869730472565f, - -0.498782604932785f, - 0.534487187862396f, -0.498809218406677f, 0.534104585647583f, - -0.498835533857346f, - 0.533721983432770f, -0.498861521482468f, 0.533339321613312f, - -0.498887240886688f, - 0.532956659793854f, -0.498912662267685f, 0.532573997974396f, - -0.498937815427780f, - 0.532191336154938f, -0.498962640762329f, 0.531808614730835f, - -0.498987197875977f, - 0.531425893306732f, -0.499011427164078f, 0.531043112277985f, - -0.499035388231277f, - 0.530660390853882f, -0.499059051275253f, 0.530277609825134f, - -0.499082416296005f, - 0.529894769191742f, -0.499105513095856f, 0.529511988162994f, - -0.499128282070160f, - 0.529129147529602f, -0.499150782823563f, 0.528746306896210f, - -0.499172955751419f, - 0.528363406658173f, -0.499194860458374f, 0.527980506420136f, - -0.499216467142105f, - 0.527597606182098f, -0.499237775802612f, 0.527214705944061f, - -0.499258816242218f, - 0.526831746101379f, -0.499279528856277f, 0.526448845863342f, - -0.499299973249435f, - 0.526065826416016f, -0.499320119619370f, 0.525682866573334f, - -0.499339967966080f, - 0.525299847126007f, -0.499359518289566f, 0.524916887283325f, - -0.499378770589828f, - 0.524533808231354f, -0.499397724866867f, 0.524150788784027f, - -0.499416410923004f, - 0.523767769336700f, -0.499434769153595f, 0.523384690284729f, - -0.499452859163284f, - 0.523001611232758f, -0.499470651149750f, 0.522618472576141f, - -0.499488145112991f, - 0.522235393524170f, -0.499505341053009f, 0.521852254867554f, - -0.499522238969803f, - 0.521469116210938f, -0.499538868665695f, 0.521085977554321f, - -0.499555170536041f, - 0.520702838897705f, -0.499571204185486f, 0.520319640636444f, - -0.499586939811707f, - 0.519936442375183f, -0.499602377414703f, 0.519553244113922f, - -0.499617516994476f, - 0.519170045852661f, -0.499632388353348f, 0.518786847591400f, - -0.499646931886673f, - 0.518403589725494f, -0.499661177396774f, 0.518020391464233f, - -0.499675154685974f, - 0.517637133598328f, -0.499688833951950f, 0.517253875732422f, - -0.499702215194702f, - 0.516870558261871f, -0.499715298414230f, 0.516487300395966f, - -0.499728083610535f, - 0.516103982925415f, -0.499740600585938f, 0.515720725059509f, - -0.499752789735794f, - 0.515337407588959f, -0.499764710664749f, 0.514954090118408f, - -0.499776333570480f, - 0.514570772647858f, -0.499787658452988f, 0.514187395572662f, - -0.499798685312271f, - 0.513804078102112f, -0.499809414148331f, 0.513420701026917f, - -0.499819844961166f, - 0.513037383556366f, -0.499830007553101f, 0.512654006481171f, - -0.499839842319489f, - 0.512270629405975f, -0.499849408864975f, 0.511887252330780f, - -0.499858677387238f, - 0.511503815650940f, -0.499867647886276f, 0.511120438575745f, - -0.499876320362091f, - 0.510737061500549f, -0.499884694814682f, 0.510353624820709f, - -0.499892801046371f, - 0.509970188140869f, -0.499900579452515f, 0.509586811065674f, - -0.499908089637756f, - 0.509203374385834f, -0.499915301799774f, 0.508819937705994f, - -0.499922215938568f, - 0.508436501026154f, -0.499928832054138f, 0.508053064346313f, - -0.499935150146484f, - 0.507669627666473f, -0.499941170215607f, 0.507286131381989f, - -0.499946922063828f, - 0.506902694702148f, -0.499952346086502f, 0.506519258022308f, - -0.499957501888275f, - 0.506135761737823f, -0.499962359666824f, 0.505752325057983f, - -0.499966919422150f, - 0.505368828773499f, -0.499971181154251f, 0.504985332489014f, - -0.499975144863129f, - 0.504601895809174f, -0.499978810548782f, 0.504218399524689f, - -0.499982208013535f, - 0.503834903240204f, -0.499985307455063f, 0.503451406955719f, - -0.499988079071045f, - 0.503067970275879f, -0.499990582466125f, 0.502684473991394f, - -0.499992787837982f, - 0.502300977706909f, -0.499994695186615f, 0.501917481422424f, - -0.499996334314346f, - 0.501533985137939f, -0.499997645616531f, 0.501150488853455f, - -0.499998688697815f, - 0.500766992568970f, -0.499999403953552f, 0.500383496284485f, - -0.499999850988388f, -}; - - - -/** -* @brief Initialization function for the floating-point RFFT/RIFFT. -* @param[in,out] *S points to an instance of the floating-point RFFT/RIFFT structure. -* @param[in,out] *S_CFFT points to an instance of the floating-point CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_f32( - arm_rfft_instance_f32 * S, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (float32_t *) realCoefA; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (float32_t *) realCoefB; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initializations of structure parameters depending on the FFT length */ - switch (S->fftLenReal) - { - /* Init table modifier value */ - case 8192u: - S->twidCoefRModifier = 1u; - break; - case 2048u: - S->twidCoefRModifier = 4u; - break; - case 512u: - S->twidCoefRModifier = 16u; - break; - case 128u: - S->twidCoefRModifier = 64u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 1u, 0u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_f32(S->pCfft, S->fftLenBy2, 0u, 0u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c deleted file mode 100644 index 50b9d994d0..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q15.c +++ /dev/null @@ -1,2229 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_q15.c -* -* Description: RFFT & RIFFT Q15 initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - - - -/** -* \par -* Generation floating point real_CoefA array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-*  {    
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-*  } 
-* \par -* Convert to fixed point Q15 format -* round(pATable[i] * pow(2, 15)) -*/ - - -static const q15_t ALIGN4 realCoefAQ15[8192] = { - 0x4000, 0xc000, 0x3ff3, 0xc000, 0x3fe7, 0xc000, 0x3fda, 0xc000, - 0x3fce, 0xc000, 0x3fc1, 0xc000, 0x3fb5, 0xc000, 0x3fa8, 0xc000, - 0x3f9b, 0xc000, 0x3f8f, 0xc000, 0x3f82, 0xc000, 0x3f76, 0xc001, - 0x3f69, 0xc001, 0x3f5d, 0xc001, 0x3f50, 0xc001, 0x3f44, 0xc001, - 0x3f37, 0xc001, 0x3f2a, 0xc001, 0x3f1e, 0xc002, 0x3f11, 0xc002, - 0x3f05, 0xc002, 0x3ef8, 0xc002, 0x3eec, 0xc002, 0x3edf, 0xc003, - 0x3ed2, 0xc003, 0x3ec6, 0xc003, 0x3eb9, 0xc003, 0x3ead, 0xc004, - 0x3ea0, 0xc004, 0x3e94, 0xc004, 0x3e87, 0xc004, 0x3e7a, 0xc005, - 0x3e6e, 0xc005, 0x3e61, 0xc005, 0x3e55, 0xc006, 0x3e48, 0xc006, - 0x3e3c, 0xc006, 0x3e2f, 0xc007, 0x3e23, 0xc007, 0x3e16, 0xc007, - 0x3e09, 0xc008, 0x3dfd, 0xc008, 0x3df0, 0xc009, 0x3de4, 0xc009, - 0x3dd7, 0xc009, 0x3dcb, 0xc00a, 0x3dbe, 0xc00a, 0x3db2, 0xc00b, - 0x3da5, 0xc00b, 0x3d98, 0xc00c, 0x3d8c, 0xc00c, 0x3d7f, 0xc00d, - 0x3d73, 0xc00d, 0x3d66, 0xc00e, 0x3d5a, 0xc00e, 0x3d4d, 0xc00f, - 0x3d40, 0xc00f, 0x3d34, 0xc010, 0x3d27, 0xc010, 0x3d1b, 0xc011, - 0x3d0e, 0xc011, 0x3d02, 0xc012, 0x3cf5, 0xc013, 0x3ce9, 0xc013, - 0x3cdc, 0xc014, 0x3cd0, 0xc014, 0x3cc3, 0xc015, 0x3cb6, 0xc016, - 0x3caa, 0xc016, 0x3c9d, 0xc017, 0x3c91, 0xc018, 0x3c84, 0xc018, - 0x3c78, 0xc019, 0x3c6b, 0xc01a, 0x3c5f, 0xc01a, 0x3c52, 0xc01b, - 0x3c45, 0xc01c, 0x3c39, 0xc01d, 0x3c2c, 0xc01d, 0x3c20, 0xc01e, - 0x3c13, 0xc01f, 0x3c07, 0xc020, 0x3bfa, 0xc020, 0x3bee, 0xc021, - 0x3be1, 0xc022, 0x3bd5, 0xc023, 0x3bc8, 0xc024, 0x3bbc, 0xc024, - 0x3baf, 0xc025, 0x3ba2, 0xc026, 0x3b96, 0xc027, 0x3b89, 0xc028, - 0x3b7d, 0xc029, 0x3b70, 0xc02a, 0x3b64, 0xc02b, 0x3b57, 0xc02b, - 0x3b4b, 0xc02c, 0x3b3e, 0xc02d, 0x3b32, 0xc02e, 0x3b25, 0xc02f, - 0x3b19, 0xc030, 0x3b0c, 0xc031, 0x3b00, 0xc032, 0x3af3, 0xc033, - 0x3ae6, 0xc034, 0x3ada, 0xc035, 0x3acd, 0xc036, 0x3ac1, 0xc037, - 0x3ab4, 0xc038, 0x3aa8, 0xc039, 0x3a9b, 0xc03a, 0x3a8f, 0xc03b, - 0x3a82, 0xc03c, 0x3a76, 0xc03d, 0x3a69, 0xc03f, 0x3a5d, 0xc040, - 0x3a50, 0xc041, 0x3a44, 0xc042, 0x3a37, 0xc043, 0x3a2b, 0xc044, - 0x3a1e, 0xc045, 0x3a12, 0xc047, 0x3a05, 0xc048, 0x39f9, 0xc049, - 0x39ec, 0xc04a, 0x39e0, 0xc04b, 0x39d3, 0xc04c, 0x39c7, 0xc04e, - 0x39ba, 0xc04f, 0x39ae, 0xc050, 0x39a1, 0xc051, 0x3995, 0xc053, - 0x3988, 0xc054, 0x397c, 0xc055, 0x396f, 0xc056, 0x3963, 0xc058, - 0x3956, 0xc059, 0x394a, 0xc05a, 0x393d, 0xc05c, 0x3931, 0xc05d, - 0x3924, 0xc05e, 0x3918, 0xc060, 0x390b, 0xc061, 0x38ff, 0xc062, - 0x38f2, 0xc064, 0x38e6, 0xc065, 0x38d9, 0xc067, 0x38cd, 0xc068, - 0x38c0, 0xc069, 0x38b4, 0xc06b, 0x38a7, 0xc06c, 0x389b, 0xc06e, - 0x388e, 0xc06f, 0x3882, 0xc071, 0x3875, 0xc072, 0x3869, 0xc074, - 0x385c, 0xc075, 0x3850, 0xc077, 0x3843, 0xc078, 0x3837, 0xc07a, - 0x382a, 0xc07b, 0x381e, 0xc07d, 0x3811, 0xc07e, 0x3805, 0xc080, - 0x37f9, 0xc081, 0x37ec, 0xc083, 0x37e0, 0xc085, 0x37d3, 0xc086, - 0x37c7, 0xc088, 0x37ba, 0xc089, 0x37ae, 0xc08b, 0x37a1, 0xc08d, - 0x3795, 0xc08e, 0x3788, 0xc090, 0x377c, 0xc092, 0x376f, 0xc093, - 0x3763, 0xc095, 0x3757, 0xc097, 0x374a, 0xc098, 0x373e, 0xc09a, - 0x3731, 0xc09c, 0x3725, 0xc09e, 0x3718, 0xc09f, 0x370c, 0xc0a1, - 0x36ff, 0xc0a3, 0x36f3, 0xc0a5, 0x36e7, 0xc0a6, 0x36da, 0xc0a8, - 0x36ce, 0xc0aa, 0x36c1, 0xc0ac, 0x36b5, 0xc0ae, 0x36a8, 0xc0af, - 0x369c, 0xc0b1, 0x3690, 0xc0b3, 0x3683, 0xc0b5, 0x3677, 0xc0b7, - 0x366a, 0xc0b9, 0x365e, 0xc0bb, 0x3651, 0xc0bd, 0x3645, 0xc0be, - 0x3639, 0xc0c0, 0x362c, 0xc0c2, 0x3620, 0xc0c4, 0x3613, 0xc0c6, - 0x3607, 0xc0c8, 0x35fa, 0xc0ca, 0x35ee, 0xc0cc, 0x35e2, 0xc0ce, - 0x35d5, 0xc0d0, 0x35c9, 0xc0d2, 0x35bc, 0xc0d4, 0x35b0, 0xc0d6, - 0x35a4, 0xc0d8, 0x3597, 0xc0da, 0x358b, 0xc0dc, 0x357e, 0xc0de, - 0x3572, 0xc0e0, 0x3566, 0xc0e2, 0x3559, 0xc0e4, 0x354d, 0xc0e7, - 0x3540, 0xc0e9, 0x3534, 0xc0eb, 0x3528, 0xc0ed, 0x351b, 0xc0ef, - 0x350f, 0xc0f1, 0x3503, 0xc0f3, 0x34f6, 0xc0f6, 0x34ea, 0xc0f8, - 0x34dd, 0xc0fa, 0x34d1, 0xc0fc, 0x34c5, 0xc0fe, 0x34b8, 0xc100, - 0x34ac, 0xc103, 0x34a0, 0xc105, 0x3493, 0xc107, 0x3487, 0xc109, - 0x347b, 0xc10c, 0x346e, 0xc10e, 0x3462, 0xc110, 0x3455, 0xc113, - 0x3449, 0xc115, 0x343d, 0xc117, 0x3430, 0xc119, 0x3424, 0xc11c, - 0x3418, 0xc11e, 0x340b, 0xc120, 0x33ff, 0xc123, 0x33f3, 0xc125, - 0x33e6, 0xc128, 0x33da, 0xc12a, 0x33ce, 0xc12c, 0x33c1, 0xc12f, - 0x33b5, 0xc131, 0x33a9, 0xc134, 0x339c, 0xc136, 0x3390, 0xc138, - 0x3384, 0xc13b, 0x3377, 0xc13d, 0x336b, 0xc140, 0x335f, 0xc142, - 0x3352, 0xc145, 0x3346, 0xc147, 0x333a, 0xc14a, 0x332d, 0xc14c, - 0x3321, 0xc14f, 0x3315, 0xc151, 0x3308, 0xc154, 0x32fc, 0xc156, - 0x32f0, 0xc159, 0x32e4, 0xc15b, 0x32d7, 0xc15e, 0x32cb, 0xc161, - 0x32bf, 0xc163, 0x32b2, 0xc166, 0x32a6, 0xc168, 0x329a, 0xc16b, - 0x328e, 0xc16e, 0x3281, 0xc170, 0x3275, 0xc173, 0x3269, 0xc176, - 0x325c, 0xc178, 0x3250, 0xc17b, 0x3244, 0xc17e, 0x3238, 0xc180, - 0x322b, 0xc183, 0x321f, 0xc186, 0x3213, 0xc189, 0x3207, 0xc18b, - 0x31fa, 0xc18e, 0x31ee, 0xc191, 0x31e2, 0xc194, 0x31d5, 0xc196, - 0x31c9, 0xc199, 0x31bd, 0xc19c, 0x31b1, 0xc19f, 0x31a4, 0xc1a2, - 0x3198, 0xc1a4, 0x318c, 0xc1a7, 0x3180, 0xc1aa, 0x3174, 0xc1ad, - 0x3167, 0xc1b0, 0x315b, 0xc1b3, 0x314f, 0xc1b6, 0x3143, 0xc1b8, - 0x3136, 0xc1bb, 0x312a, 0xc1be, 0x311e, 0xc1c1, 0x3112, 0xc1c4, - 0x3105, 0xc1c7, 0x30f9, 0xc1ca, 0x30ed, 0xc1cd, 0x30e1, 0xc1d0, - 0x30d5, 0xc1d3, 0x30c8, 0xc1d6, 0x30bc, 0xc1d9, 0x30b0, 0xc1dc, - 0x30a4, 0xc1df, 0x3098, 0xc1e2, 0x308b, 0xc1e5, 0x307f, 0xc1e8, - 0x3073, 0xc1eb, 0x3067, 0xc1ee, 0x305b, 0xc1f1, 0x304e, 0xc1f4, - 0x3042, 0xc1f7, 0x3036, 0xc1fa, 0x302a, 0xc1fd, 0x301e, 0xc201, - 0x3012, 0xc204, 0x3005, 0xc207, 0x2ff9, 0xc20a, 0x2fed, 0xc20d, - 0x2fe1, 0xc210, 0x2fd5, 0xc213, 0x2fc9, 0xc217, 0x2fbc, 0xc21a, - 0x2fb0, 0xc21d, 0x2fa4, 0xc220, 0x2f98, 0xc223, 0x2f8c, 0xc227, - 0x2f80, 0xc22a, 0x2f74, 0xc22d, 0x2f67, 0xc230, 0x2f5b, 0xc234, - 0x2f4f, 0xc237, 0x2f43, 0xc23a, 0x2f37, 0xc23e, 0x2f2b, 0xc241, - 0x2f1f, 0xc244, 0x2f13, 0xc247, 0x2f06, 0xc24b, 0x2efa, 0xc24e, - 0x2eee, 0xc251, 0x2ee2, 0xc255, 0x2ed6, 0xc258, 0x2eca, 0xc25c, - 0x2ebe, 0xc25f, 0x2eb2, 0xc262, 0x2ea6, 0xc266, 0x2e99, 0xc269, - 0x2e8d, 0xc26d, 0x2e81, 0xc270, 0x2e75, 0xc273, 0x2e69, 0xc277, - 0x2e5d, 0xc27a, 0x2e51, 0xc27e, 0x2e45, 0xc281, 0x2e39, 0xc285, - 0x2e2d, 0xc288, 0x2e21, 0xc28c, 0x2e15, 0xc28f, 0x2e09, 0xc293, - 0x2dfc, 0xc296, 0x2df0, 0xc29a, 0x2de4, 0xc29d, 0x2dd8, 0xc2a1, - 0x2dcc, 0xc2a5, 0x2dc0, 0xc2a8, 0x2db4, 0xc2ac, 0x2da8, 0xc2af, - 0x2d9c, 0xc2b3, 0x2d90, 0xc2b7, 0x2d84, 0xc2ba, 0x2d78, 0xc2be, - 0x2d6c, 0xc2c1, 0x2d60, 0xc2c5, 0x2d54, 0xc2c9, 0x2d48, 0xc2cc, - 0x2d3c, 0xc2d0, 0x2d30, 0xc2d4, 0x2d24, 0xc2d8, 0x2d18, 0xc2db, - 0x2d0c, 0xc2df, 0x2d00, 0xc2e3, 0x2cf4, 0xc2e6, 0x2ce8, 0xc2ea, - 0x2cdc, 0xc2ee, 0x2cd0, 0xc2f2, 0x2cc4, 0xc2f5, 0x2cb8, 0xc2f9, - 0x2cac, 0xc2fd, 0x2ca0, 0xc301, 0x2c94, 0xc305, 0x2c88, 0xc308, - 0x2c7c, 0xc30c, 0x2c70, 0xc310, 0x2c64, 0xc314, 0x2c58, 0xc318, - 0x2c4c, 0xc31c, 0x2c40, 0xc320, 0x2c34, 0xc323, 0x2c28, 0xc327, - 0x2c1c, 0xc32b, 0x2c10, 0xc32f, 0x2c05, 0xc333, 0x2bf9, 0xc337, - 0x2bed, 0xc33b, 0x2be1, 0xc33f, 0x2bd5, 0xc343, 0x2bc9, 0xc347, - 0x2bbd, 0xc34b, 0x2bb1, 0xc34f, 0x2ba5, 0xc353, 0x2b99, 0xc357, - 0x2b8d, 0xc35b, 0x2b81, 0xc35f, 0x2b75, 0xc363, 0x2b6a, 0xc367, - 0x2b5e, 0xc36b, 0x2b52, 0xc36f, 0x2b46, 0xc373, 0x2b3a, 0xc377, - 0x2b2e, 0xc37b, 0x2b22, 0xc37f, 0x2b16, 0xc383, 0x2b0a, 0xc387, - 0x2aff, 0xc38c, 0x2af3, 0xc390, 0x2ae7, 0xc394, 0x2adb, 0xc398, - 0x2acf, 0xc39c, 0x2ac3, 0xc3a0, 0x2ab7, 0xc3a5, 0x2aac, 0xc3a9, - 0x2aa0, 0xc3ad, 0x2a94, 0xc3b1, 0x2a88, 0xc3b5, 0x2a7c, 0xc3ba, - 0x2a70, 0xc3be, 0x2a65, 0xc3c2, 0x2a59, 0xc3c6, 0x2a4d, 0xc3ca, - 0x2a41, 0xc3cf, 0x2a35, 0xc3d3, 0x2a29, 0xc3d7, 0x2a1e, 0xc3dc, - 0x2a12, 0xc3e0, 0x2a06, 0xc3e4, 0x29fa, 0xc3e9, 0x29ee, 0xc3ed, - 0x29e3, 0xc3f1, 0x29d7, 0xc3f6, 0x29cb, 0xc3fa, 0x29bf, 0xc3fe, - 0x29b4, 0xc403, 0x29a8, 0xc407, 0x299c, 0xc40b, 0x2990, 0xc410, - 0x2984, 0xc414, 0x2979, 0xc419, 0x296d, 0xc41d, 0x2961, 0xc422, - 0x2955, 0xc426, 0x294a, 0xc42a, 0x293e, 0xc42f, 0x2932, 0xc433, - 0x2926, 0xc438, 0x291b, 0xc43c, 0x290f, 0xc441, 0x2903, 0xc445, - 0x28f7, 0xc44a, 0x28ec, 0xc44e, 0x28e0, 0xc453, 0x28d4, 0xc457, - 0x28c9, 0xc45c, 0x28bd, 0xc461, 0x28b1, 0xc465, 0x28a5, 0xc46a, - 0x289a, 0xc46e, 0x288e, 0xc473, 0x2882, 0xc478, 0x2877, 0xc47c, - 0x286b, 0xc481, 0x285f, 0xc485, 0x2854, 0xc48a, 0x2848, 0xc48f, - 0x283c, 0xc493, 0x2831, 0xc498, 0x2825, 0xc49d, 0x2819, 0xc4a1, - 0x280e, 0xc4a6, 0x2802, 0xc4ab, 0x27f6, 0xc4b0, 0x27eb, 0xc4b4, - 0x27df, 0xc4b9, 0x27d3, 0xc4be, 0x27c8, 0xc4c2, 0x27bc, 0xc4c7, - 0x27b1, 0xc4cc, 0x27a5, 0xc4d1, 0x2799, 0xc4d6, 0x278e, 0xc4da, - 0x2782, 0xc4df, 0x2777, 0xc4e4, 0x276b, 0xc4e9, 0x275f, 0xc4ee, - 0x2754, 0xc4f2, 0x2748, 0xc4f7, 0x273d, 0xc4fc, 0x2731, 0xc501, - 0x2725, 0xc506, 0x271a, 0xc50b, 0x270e, 0xc510, 0x2703, 0xc515, - 0x26f7, 0xc51a, 0x26ec, 0xc51e, 0x26e0, 0xc523, 0x26d4, 0xc528, - 0x26c9, 0xc52d, 0x26bd, 0xc532, 0x26b2, 0xc537, 0x26a6, 0xc53c, - 0x269b, 0xc541, 0x268f, 0xc546, 0x2684, 0xc54b, 0x2678, 0xc550, - 0x266d, 0xc555, 0x2661, 0xc55a, 0x2656, 0xc55f, 0x264a, 0xc564, - 0x263f, 0xc569, 0x2633, 0xc56e, 0x2628, 0xc573, 0x261c, 0xc578, - 0x2611, 0xc57e, 0x2605, 0xc583, 0x25fa, 0xc588, 0x25ee, 0xc58d, - 0x25e3, 0xc592, 0x25d7, 0xc597, 0x25cc, 0xc59c, 0x25c0, 0xc5a1, - 0x25b5, 0xc5a7, 0x25a9, 0xc5ac, 0x259e, 0xc5b1, 0x2592, 0xc5b6, - 0x2587, 0xc5bb, 0x257c, 0xc5c1, 0x2570, 0xc5c6, 0x2565, 0xc5cb, - 0x2559, 0xc5d0, 0x254e, 0xc5d5, 0x2542, 0xc5db, 0x2537, 0xc5e0, - 0x252c, 0xc5e5, 0x2520, 0xc5ea, 0x2515, 0xc5f0, 0x2509, 0xc5f5, - 0x24fe, 0xc5fa, 0x24f3, 0xc600, 0x24e7, 0xc605, 0x24dc, 0xc60a, - 0x24d0, 0xc610, 0x24c5, 0xc615, 0x24ba, 0xc61a, 0x24ae, 0xc620, - 0x24a3, 0xc625, 0x2498, 0xc62a, 0x248c, 0xc630, 0x2481, 0xc635, - 0x2476, 0xc63b, 0x246a, 0xc640, 0x245f, 0xc645, 0x2454, 0xc64b, - 0x2448, 0xc650, 0x243d, 0xc656, 0x2432, 0xc65b, 0x2426, 0xc661, - 0x241b, 0xc666, 0x2410, 0xc66c, 0x2404, 0xc671, 0x23f9, 0xc677, - 0x23ee, 0xc67c, 0x23e2, 0xc682, 0x23d7, 0xc687, 0x23cc, 0xc68d, - 0x23c1, 0xc692, 0x23b5, 0xc698, 0x23aa, 0xc69d, 0x239f, 0xc6a3, - 0x2394, 0xc6a8, 0x2388, 0xc6ae, 0x237d, 0xc6b4, 0x2372, 0xc6b9, - 0x2367, 0xc6bf, 0x235b, 0xc6c5, 0x2350, 0xc6ca, 0x2345, 0xc6d0, - 0x233a, 0xc6d5, 0x232e, 0xc6db, 0x2323, 0xc6e1, 0x2318, 0xc6e6, - 0x230d, 0xc6ec, 0x2301, 0xc6f2, 0x22f6, 0xc6f7, 0x22eb, 0xc6fd, - 0x22e0, 0xc703, 0x22d5, 0xc709, 0x22ca, 0xc70e, 0x22be, 0xc714, - 0x22b3, 0xc71a, 0x22a8, 0xc720, 0x229d, 0xc725, 0x2292, 0xc72b, - 0x2287, 0xc731, 0x227b, 0xc737, 0x2270, 0xc73d, 0x2265, 0xc742, - 0x225a, 0xc748, 0x224f, 0xc74e, 0x2244, 0xc754, 0x2239, 0xc75a, - 0x222d, 0xc75f, 0x2222, 0xc765, 0x2217, 0xc76b, 0x220c, 0xc771, - 0x2201, 0xc777, 0x21f6, 0xc77d, 0x21eb, 0xc783, 0x21e0, 0xc789, - 0x21d5, 0xc78f, 0x21ca, 0xc795, 0x21be, 0xc79a, 0x21b3, 0xc7a0, - 0x21a8, 0xc7a6, 0x219d, 0xc7ac, 0x2192, 0xc7b2, 0x2187, 0xc7b8, - 0x217c, 0xc7be, 0x2171, 0xc7c4, 0x2166, 0xc7ca, 0x215b, 0xc7d0, - 0x2150, 0xc7d6, 0x2145, 0xc7dc, 0x213a, 0xc7e2, 0x212f, 0xc7e8, - 0x2124, 0xc7ee, 0x2119, 0xc7f5, 0x210e, 0xc7fb, 0x2103, 0xc801, - 0x20f8, 0xc807, 0x20ed, 0xc80d, 0x20e2, 0xc813, 0x20d7, 0xc819, - 0x20cc, 0xc81f, 0x20c1, 0xc825, 0x20b6, 0xc82b, 0x20ab, 0xc832, - 0x20a0, 0xc838, 0x2095, 0xc83e, 0x208a, 0xc844, 0x207f, 0xc84a, - 0x2074, 0xc850, 0x2069, 0xc857, 0x205e, 0xc85d, 0x2054, 0xc863, - 0x2049, 0xc869, 0x203e, 0xc870, 0x2033, 0xc876, 0x2028, 0xc87c, - 0x201d, 0xc882, 0x2012, 0xc889, 0x2007, 0xc88f, 0x1ffc, 0xc895, - 0x1ff1, 0xc89b, 0x1fe7, 0xc8a2, 0x1fdc, 0xc8a8, 0x1fd1, 0xc8ae, - 0x1fc6, 0xc8b5, 0x1fbb, 0xc8bb, 0x1fb0, 0xc8c1, 0x1fa5, 0xc8c8, - 0x1f9b, 0xc8ce, 0x1f90, 0xc8d4, 0x1f85, 0xc8db, 0x1f7a, 0xc8e1, - 0x1f6f, 0xc8e8, 0x1f65, 0xc8ee, 0x1f5a, 0xc8f4, 0x1f4f, 0xc8fb, - 0x1f44, 0xc901, 0x1f39, 0xc908, 0x1f2f, 0xc90e, 0x1f24, 0xc915, - 0x1f19, 0xc91b, 0x1f0e, 0xc921, 0x1f03, 0xc928, 0x1ef9, 0xc92e, - 0x1eee, 0xc935, 0x1ee3, 0xc93b, 0x1ed8, 0xc942, 0x1ece, 0xc948, - 0x1ec3, 0xc94f, 0x1eb8, 0xc955, 0x1ead, 0xc95c, 0x1ea3, 0xc963, - 0x1e98, 0xc969, 0x1e8d, 0xc970, 0x1e83, 0xc976, 0x1e78, 0xc97d, - 0x1e6d, 0xc983, 0x1e62, 0xc98a, 0x1e58, 0xc991, 0x1e4d, 0xc997, - 0x1e42, 0xc99e, 0x1e38, 0xc9a4, 0x1e2d, 0xc9ab, 0x1e22, 0xc9b2, - 0x1e18, 0xc9b8, 0x1e0d, 0xc9bf, 0x1e02, 0xc9c6, 0x1df8, 0xc9cc, - 0x1ded, 0xc9d3, 0x1de2, 0xc9da, 0x1dd8, 0xc9e0, 0x1dcd, 0xc9e7, - 0x1dc3, 0xc9ee, 0x1db8, 0xc9f5, 0x1dad, 0xc9fb, 0x1da3, 0xca02, - 0x1d98, 0xca09, 0x1d8e, 0xca10, 0x1d83, 0xca16, 0x1d78, 0xca1d, - 0x1d6e, 0xca24, 0x1d63, 0xca2b, 0x1d59, 0xca32, 0x1d4e, 0xca38, - 0x1d44, 0xca3f, 0x1d39, 0xca46, 0x1d2e, 0xca4d, 0x1d24, 0xca54, - 0x1d19, 0xca5b, 0x1d0f, 0xca61, 0x1d04, 0xca68, 0x1cfa, 0xca6f, - 0x1cef, 0xca76, 0x1ce5, 0xca7d, 0x1cda, 0xca84, 0x1cd0, 0xca8b, - 0x1cc5, 0xca92, 0x1cbb, 0xca99, 0x1cb0, 0xca9f, 0x1ca6, 0xcaa6, - 0x1c9b, 0xcaad, 0x1c91, 0xcab4, 0x1c86, 0xcabb, 0x1c7c, 0xcac2, - 0x1c72, 0xcac9, 0x1c67, 0xcad0, 0x1c5d, 0xcad7, 0x1c52, 0xcade, - 0x1c48, 0xcae5, 0x1c3d, 0xcaec, 0x1c33, 0xcaf3, 0x1c29, 0xcafa, - 0x1c1e, 0xcb01, 0x1c14, 0xcb08, 0x1c09, 0xcb0f, 0x1bff, 0xcb16, - 0x1bf5, 0xcb1e, 0x1bea, 0xcb25, 0x1be0, 0xcb2c, 0x1bd5, 0xcb33, - 0x1bcb, 0xcb3a, 0x1bc1, 0xcb41, 0x1bb6, 0xcb48, 0x1bac, 0xcb4f, - 0x1ba2, 0xcb56, 0x1b97, 0xcb5e, 0x1b8d, 0xcb65, 0x1b83, 0xcb6c, - 0x1b78, 0xcb73, 0x1b6e, 0xcb7a, 0x1b64, 0xcb81, 0x1b59, 0xcb89, - 0x1b4f, 0xcb90, 0x1b45, 0xcb97, 0x1b3b, 0xcb9e, 0x1b30, 0xcba5, - 0x1b26, 0xcbad, 0x1b1c, 0xcbb4, 0x1b11, 0xcbbb, 0x1b07, 0xcbc2, - 0x1afd, 0xcbca, 0x1af3, 0xcbd1, 0x1ae8, 0xcbd8, 0x1ade, 0xcbe0, - 0x1ad4, 0xcbe7, 0x1aca, 0xcbee, 0x1abf, 0xcbf5, 0x1ab5, 0xcbfd, - 0x1aab, 0xcc04, 0x1aa1, 0xcc0b, 0x1a97, 0xcc13, 0x1a8c, 0xcc1a, - 0x1a82, 0xcc21, 0x1a78, 0xcc29, 0x1a6e, 0xcc30, 0x1a64, 0xcc38, - 0x1a5a, 0xcc3f, 0x1a4f, 0xcc46, 0x1a45, 0xcc4e, 0x1a3b, 0xcc55, - 0x1a31, 0xcc5d, 0x1a27, 0xcc64, 0x1a1d, 0xcc6b, 0x1a13, 0xcc73, - 0x1a08, 0xcc7a, 0x19fe, 0xcc82, 0x19f4, 0xcc89, 0x19ea, 0xcc91, - 0x19e0, 0xcc98, 0x19d6, 0xcca0, 0x19cc, 0xcca7, 0x19c2, 0xccaf, - 0x19b8, 0xccb6, 0x19ae, 0xccbe, 0x19a4, 0xccc5, 0x199a, 0xcccd, - 0x198f, 0xccd4, 0x1985, 0xccdc, 0x197b, 0xcce3, 0x1971, 0xcceb, - 0x1967, 0xccf3, 0x195d, 0xccfa, 0x1953, 0xcd02, 0x1949, 0xcd09, - 0x193f, 0xcd11, 0x1935, 0xcd19, 0x192b, 0xcd20, 0x1921, 0xcd28, - 0x1917, 0xcd30, 0x190d, 0xcd37, 0x1903, 0xcd3f, 0x18f9, 0xcd46, - 0x18ef, 0xcd4e, 0x18e6, 0xcd56, 0x18dc, 0xcd5d, 0x18d2, 0xcd65, - 0x18c8, 0xcd6d, 0x18be, 0xcd75, 0x18b4, 0xcd7c, 0x18aa, 0xcd84, - 0x18a0, 0xcd8c, 0x1896, 0xcd93, 0x188c, 0xcd9b, 0x1882, 0xcda3, - 0x1878, 0xcdab, 0x186f, 0xcdb2, 0x1865, 0xcdba, 0x185b, 0xcdc2, - 0x1851, 0xcdca, 0x1847, 0xcdd2, 0x183d, 0xcdd9, 0x1833, 0xcde1, - 0x182a, 0xcde9, 0x1820, 0xcdf1, 0x1816, 0xcdf9, 0x180c, 0xce01, - 0x1802, 0xce08, 0x17f8, 0xce10, 0x17ef, 0xce18, 0x17e5, 0xce20, - 0x17db, 0xce28, 0x17d1, 0xce30, 0x17c8, 0xce38, 0x17be, 0xce40, - 0x17b4, 0xce47, 0x17aa, 0xce4f, 0x17a0, 0xce57, 0x1797, 0xce5f, - 0x178d, 0xce67, 0x1783, 0xce6f, 0x177a, 0xce77, 0x1770, 0xce7f, - 0x1766, 0xce87, 0x175c, 0xce8f, 0x1753, 0xce97, 0x1749, 0xce9f, - 0x173f, 0xcea7, 0x1736, 0xceaf, 0x172c, 0xceb7, 0x1722, 0xcebf, - 0x1719, 0xcec7, 0x170f, 0xcecf, 0x1705, 0xced7, 0x16fc, 0xcedf, - 0x16f2, 0xcee7, 0x16e8, 0xceef, 0x16df, 0xcef7, 0x16d5, 0xceff, - 0x16cb, 0xcf07, 0x16c2, 0xcf10, 0x16b8, 0xcf18, 0x16af, 0xcf20, - 0x16a5, 0xcf28, 0x169b, 0xcf30, 0x1692, 0xcf38, 0x1688, 0xcf40, - 0x167f, 0xcf48, 0x1675, 0xcf51, 0x166c, 0xcf59, 0x1662, 0xcf61, - 0x1659, 0xcf69, 0x164f, 0xcf71, 0x1645, 0xcf79, 0x163c, 0xcf82, - 0x1632, 0xcf8a, 0x1629, 0xcf92, 0x161f, 0xcf9a, 0x1616, 0xcfa3, - 0x160c, 0xcfab, 0x1603, 0xcfb3, 0x15f9, 0xcfbb, 0x15f0, 0xcfc4, - 0x15e6, 0xcfcc, 0x15dd, 0xcfd4, 0x15d4, 0xcfdc, 0x15ca, 0xcfe5, - 0x15c1, 0xcfed, 0x15b7, 0xcff5, 0x15ae, 0xcffe, 0x15a4, 0xd006, - 0x159b, 0xd00e, 0x1592, 0xd016, 0x1588, 0xd01f, 0x157f, 0xd027, - 0x1575, 0xd030, 0x156c, 0xd038, 0x1563, 0xd040, 0x1559, 0xd049, - 0x1550, 0xd051, 0x1547, 0xd059, 0x153d, 0xd062, 0x1534, 0xd06a, - 0x152a, 0xd073, 0x1521, 0xd07b, 0x1518, 0xd083, 0x150e, 0xd08c, - 0x1505, 0xd094, 0x14fc, 0xd09d, 0x14f3, 0xd0a5, 0x14e9, 0xd0ae, - 0x14e0, 0xd0b6, 0x14d7, 0xd0bf, 0x14cd, 0xd0c7, 0x14c4, 0xd0d0, - 0x14bb, 0xd0d8, 0x14b2, 0xd0e0, 0x14a8, 0xd0e9, 0x149f, 0xd0f2, - 0x1496, 0xd0fa, 0x148d, 0xd103, 0x1483, 0xd10b, 0x147a, 0xd114, - 0x1471, 0xd11c, 0x1468, 0xd125, 0x145f, 0xd12d, 0x1455, 0xd136, - 0x144c, 0xd13e, 0x1443, 0xd147, 0x143a, 0xd150, 0x1431, 0xd158, - 0x1428, 0xd161, 0x141e, 0xd169, 0x1415, 0xd172, 0x140c, 0xd17b, - 0x1403, 0xd183, 0x13fa, 0xd18c, 0x13f1, 0xd195, 0x13e8, 0xd19d, - 0x13df, 0xd1a6, 0x13d5, 0xd1af, 0x13cc, 0xd1b7, 0x13c3, 0xd1c0, - 0x13ba, 0xd1c9, 0x13b1, 0xd1d1, 0x13a8, 0xd1da, 0x139f, 0xd1e3, - 0x1396, 0xd1eb, 0x138d, 0xd1f4, 0x1384, 0xd1fd, 0x137b, 0xd206, - 0x1372, 0xd20e, 0x1369, 0xd217, 0x1360, 0xd220, 0x1357, 0xd229, - 0x134e, 0xd231, 0x1345, 0xd23a, 0x133c, 0xd243, 0x1333, 0xd24c, - 0x132a, 0xd255, 0x1321, 0xd25d, 0x1318, 0xd266, 0x130f, 0xd26f, - 0x1306, 0xd278, 0x12fd, 0xd281, 0x12f4, 0xd28a, 0x12eb, 0xd292, - 0x12e2, 0xd29b, 0x12d9, 0xd2a4, 0x12d1, 0xd2ad, 0x12c8, 0xd2b6, - 0x12bf, 0xd2bf, 0x12b6, 0xd2c8, 0x12ad, 0xd2d1, 0x12a4, 0xd2d9, - 0x129b, 0xd2e2, 0x1292, 0xd2eb, 0x128a, 0xd2f4, 0x1281, 0xd2fd, - 0x1278, 0xd306, 0x126f, 0xd30f, 0x1266, 0xd318, 0x125d, 0xd321, - 0x1255, 0xd32a, 0x124c, 0xd333, 0x1243, 0xd33c, 0x123a, 0xd345, - 0x1231, 0xd34e, 0x1229, 0xd357, 0x1220, 0xd360, 0x1217, 0xd369, - 0x120e, 0xd372, 0x1206, 0xd37b, 0x11fd, 0xd384, 0x11f4, 0xd38d, - 0x11eb, 0xd396, 0x11e3, 0xd39f, 0x11da, 0xd3a8, 0x11d1, 0xd3b1, - 0x11c9, 0xd3ba, 0x11c0, 0xd3c3, 0x11b7, 0xd3cc, 0x11af, 0xd3d5, - 0x11a6, 0xd3df, 0x119d, 0xd3e8, 0x1195, 0xd3f1, 0x118c, 0xd3fa, - 0x1183, 0xd403, 0x117b, 0xd40c, 0x1172, 0xd415, 0x1169, 0xd41e, - 0x1161, 0xd428, 0x1158, 0xd431, 0x1150, 0xd43a, 0x1147, 0xd443, - 0x113e, 0xd44c, 0x1136, 0xd455, 0x112d, 0xd45f, 0x1125, 0xd468, - 0x111c, 0xd471, 0x1114, 0xd47a, 0x110b, 0xd483, 0x1103, 0xd48d, - 0x10fa, 0xd496, 0x10f2, 0xd49f, 0x10e9, 0xd4a8, 0x10e0, 0xd4b2, - 0x10d8, 0xd4bb, 0x10d0, 0xd4c4, 0x10c7, 0xd4cd, 0x10bf, 0xd4d7, - 0x10b6, 0xd4e0, 0x10ae, 0xd4e9, 0x10a5, 0xd4f3, 0x109d, 0xd4fc, - 0x1094, 0xd505, 0x108c, 0xd50e, 0x1083, 0xd518, 0x107b, 0xd521, - 0x1073, 0xd52a, 0x106a, 0xd534, 0x1062, 0xd53d, 0x1059, 0xd547, - 0x1051, 0xd550, 0x1049, 0xd559, 0x1040, 0xd563, 0x1038, 0xd56c, - 0x1030, 0xd575, 0x1027, 0xd57f, 0x101f, 0xd588, 0x1016, 0xd592, - 0x100e, 0xd59b, 0x1006, 0xd5a4, 0xffe, 0xd5ae, 0xff5, 0xd5b7, - 0xfed, 0xd5c1, 0xfe5, 0xd5ca, 0xfdc, 0xd5d4, 0xfd4, 0xd5dd, - 0xfcc, 0xd5e6, 0xfc4, 0xd5f0, 0xfbb, 0xd5f9, 0xfb3, 0xd603, - 0xfab, 0xd60c, 0xfa3, 0xd616, 0xf9a, 0xd61f, 0xf92, 0xd629, - 0xf8a, 0xd632, 0xf82, 0xd63c, 0xf79, 0xd645, 0xf71, 0xd64f, - 0xf69, 0xd659, 0xf61, 0xd662, 0xf59, 0xd66c, 0xf51, 0xd675, - 0xf48, 0xd67f, 0xf40, 0xd688, 0xf38, 0xd692, 0xf30, 0xd69b, - 0xf28, 0xd6a5, 0xf20, 0xd6af, 0xf18, 0xd6b8, 0xf10, 0xd6c2, - 0xf07, 0xd6cb, 0xeff, 0xd6d5, 0xef7, 0xd6df, 0xeef, 0xd6e8, - 0xee7, 0xd6f2, 0xedf, 0xd6fc, 0xed7, 0xd705, 0xecf, 0xd70f, - 0xec7, 0xd719, 0xebf, 0xd722, 0xeb7, 0xd72c, 0xeaf, 0xd736, - 0xea7, 0xd73f, 0xe9f, 0xd749, 0xe97, 0xd753, 0xe8f, 0xd75c, - 0xe87, 0xd766, 0xe7f, 0xd770, 0xe77, 0xd77a, 0xe6f, 0xd783, - 0xe67, 0xd78d, 0xe5f, 0xd797, 0xe57, 0xd7a0, 0xe4f, 0xd7aa, - 0xe47, 0xd7b4, 0xe40, 0xd7be, 0xe38, 0xd7c8, 0xe30, 0xd7d1, - 0xe28, 0xd7db, 0xe20, 0xd7e5, 0xe18, 0xd7ef, 0xe10, 0xd7f8, - 0xe08, 0xd802, 0xe01, 0xd80c, 0xdf9, 0xd816, 0xdf1, 0xd820, - 0xde9, 0xd82a, 0xde1, 0xd833, 0xdd9, 0xd83d, 0xdd2, 0xd847, - 0xdca, 0xd851, 0xdc2, 0xd85b, 0xdba, 0xd865, 0xdb2, 0xd86f, - 0xdab, 0xd878, 0xda3, 0xd882, 0xd9b, 0xd88c, 0xd93, 0xd896, - 0xd8c, 0xd8a0, 0xd84, 0xd8aa, 0xd7c, 0xd8b4, 0xd75, 0xd8be, - 0xd6d, 0xd8c8, 0xd65, 0xd8d2, 0xd5d, 0xd8dc, 0xd56, 0xd8e6, - 0xd4e, 0xd8ef, 0xd46, 0xd8f9, 0xd3f, 0xd903, 0xd37, 0xd90d, - 0xd30, 0xd917, 0xd28, 0xd921, 0xd20, 0xd92b, 0xd19, 0xd935, - 0xd11, 0xd93f, 0xd09, 0xd949, 0xd02, 0xd953, 0xcfa, 0xd95d, - 0xcf3, 0xd967, 0xceb, 0xd971, 0xce3, 0xd97b, 0xcdc, 0xd985, - 0xcd4, 0xd98f, 0xccd, 0xd99a, 0xcc5, 0xd9a4, 0xcbe, 0xd9ae, - 0xcb6, 0xd9b8, 0xcaf, 0xd9c2, 0xca7, 0xd9cc, 0xca0, 0xd9d6, - 0xc98, 0xd9e0, 0xc91, 0xd9ea, 0xc89, 0xd9f4, 0xc82, 0xd9fe, - 0xc7a, 0xda08, 0xc73, 0xda13, 0xc6b, 0xda1d, 0xc64, 0xda27, - 0xc5d, 0xda31, 0xc55, 0xda3b, 0xc4e, 0xda45, 0xc46, 0xda4f, - 0xc3f, 0xda5a, 0xc38, 0xda64, 0xc30, 0xda6e, 0xc29, 0xda78, - 0xc21, 0xda82, 0xc1a, 0xda8c, 0xc13, 0xda97, 0xc0b, 0xdaa1, - 0xc04, 0xdaab, 0xbfd, 0xdab5, 0xbf5, 0xdabf, 0xbee, 0xdaca, - 0xbe7, 0xdad4, 0xbe0, 0xdade, 0xbd8, 0xdae8, 0xbd1, 0xdaf3, - 0xbca, 0xdafd, 0xbc2, 0xdb07, 0xbbb, 0xdb11, 0xbb4, 0xdb1c, - 0xbad, 0xdb26, 0xba5, 0xdb30, 0xb9e, 0xdb3b, 0xb97, 0xdb45, - 0xb90, 0xdb4f, 0xb89, 0xdb59, 0xb81, 0xdb64, 0xb7a, 0xdb6e, - 0xb73, 0xdb78, 0xb6c, 0xdb83, 0xb65, 0xdb8d, 0xb5e, 0xdb97, - 0xb56, 0xdba2, 0xb4f, 0xdbac, 0xb48, 0xdbb6, 0xb41, 0xdbc1, - 0xb3a, 0xdbcb, 0xb33, 0xdbd5, 0xb2c, 0xdbe0, 0xb25, 0xdbea, - 0xb1e, 0xdbf5, 0xb16, 0xdbff, 0xb0f, 0xdc09, 0xb08, 0xdc14, - 0xb01, 0xdc1e, 0xafa, 0xdc29, 0xaf3, 0xdc33, 0xaec, 0xdc3d, - 0xae5, 0xdc48, 0xade, 0xdc52, 0xad7, 0xdc5d, 0xad0, 0xdc67, - 0xac9, 0xdc72, 0xac2, 0xdc7c, 0xabb, 0xdc86, 0xab4, 0xdc91, - 0xaad, 0xdc9b, 0xaa6, 0xdca6, 0xa9f, 0xdcb0, 0xa99, 0xdcbb, - 0xa92, 0xdcc5, 0xa8b, 0xdcd0, 0xa84, 0xdcda, 0xa7d, 0xdce5, - 0xa76, 0xdcef, 0xa6f, 0xdcfa, 0xa68, 0xdd04, 0xa61, 0xdd0f, - 0xa5b, 0xdd19, 0xa54, 0xdd24, 0xa4d, 0xdd2e, 0xa46, 0xdd39, - 0xa3f, 0xdd44, 0xa38, 0xdd4e, 0xa32, 0xdd59, 0xa2b, 0xdd63, - 0xa24, 0xdd6e, 0xa1d, 0xdd78, 0xa16, 0xdd83, 0xa10, 0xdd8e, - 0xa09, 0xdd98, 0xa02, 0xdda3, 0x9fb, 0xddad, 0x9f5, 0xddb8, - 0x9ee, 0xddc3, 0x9e7, 0xddcd, 0x9e0, 0xddd8, 0x9da, 0xdde2, - 0x9d3, 0xdded, 0x9cc, 0xddf8, 0x9c6, 0xde02, 0x9bf, 0xde0d, - 0x9b8, 0xde18, 0x9b2, 0xde22, 0x9ab, 0xde2d, 0x9a4, 0xde38, - 0x99e, 0xde42, 0x997, 0xde4d, 0x991, 0xde58, 0x98a, 0xde62, - 0x983, 0xde6d, 0x97d, 0xde78, 0x976, 0xde83, 0x970, 0xde8d, - 0x969, 0xde98, 0x963, 0xdea3, 0x95c, 0xdead, 0x955, 0xdeb8, - 0x94f, 0xdec3, 0x948, 0xdece, 0x942, 0xded8, 0x93b, 0xdee3, - 0x935, 0xdeee, 0x92e, 0xdef9, 0x928, 0xdf03, 0x921, 0xdf0e, - 0x91b, 0xdf19, 0x915, 0xdf24, 0x90e, 0xdf2f, 0x908, 0xdf39, - 0x901, 0xdf44, 0x8fb, 0xdf4f, 0x8f4, 0xdf5a, 0x8ee, 0xdf65, - 0x8e8, 0xdf6f, 0x8e1, 0xdf7a, 0x8db, 0xdf85, 0x8d4, 0xdf90, - 0x8ce, 0xdf9b, 0x8c8, 0xdfa5, 0x8c1, 0xdfb0, 0x8bb, 0xdfbb, - 0x8b5, 0xdfc6, 0x8ae, 0xdfd1, 0x8a8, 0xdfdc, 0x8a2, 0xdfe7, - 0x89b, 0xdff1, 0x895, 0xdffc, 0x88f, 0xe007, 0x889, 0xe012, - 0x882, 0xe01d, 0x87c, 0xe028, 0x876, 0xe033, 0x870, 0xe03e, - 0x869, 0xe049, 0x863, 0xe054, 0x85d, 0xe05e, 0x857, 0xe069, - 0x850, 0xe074, 0x84a, 0xe07f, 0x844, 0xe08a, 0x83e, 0xe095, - 0x838, 0xe0a0, 0x832, 0xe0ab, 0x82b, 0xe0b6, 0x825, 0xe0c1, - 0x81f, 0xe0cc, 0x819, 0xe0d7, 0x813, 0xe0e2, 0x80d, 0xe0ed, - 0x807, 0xe0f8, 0x801, 0xe103, 0x7fb, 0xe10e, 0x7f5, 0xe119, - 0x7ee, 0xe124, 0x7e8, 0xe12f, 0x7e2, 0xe13a, 0x7dc, 0xe145, - 0x7d6, 0xe150, 0x7d0, 0xe15b, 0x7ca, 0xe166, 0x7c4, 0xe171, - 0x7be, 0xe17c, 0x7b8, 0xe187, 0x7b2, 0xe192, 0x7ac, 0xe19d, - 0x7a6, 0xe1a8, 0x7a0, 0xe1b3, 0x79a, 0xe1be, 0x795, 0xe1ca, - 0x78f, 0xe1d5, 0x789, 0xe1e0, 0x783, 0xe1eb, 0x77d, 0xe1f6, - 0x777, 0xe201, 0x771, 0xe20c, 0x76b, 0xe217, 0x765, 0xe222, - 0x75f, 0xe22d, 0x75a, 0xe239, 0x754, 0xe244, 0x74e, 0xe24f, - 0x748, 0xe25a, 0x742, 0xe265, 0x73d, 0xe270, 0x737, 0xe27b, - 0x731, 0xe287, 0x72b, 0xe292, 0x725, 0xe29d, 0x720, 0xe2a8, - 0x71a, 0xe2b3, 0x714, 0xe2be, 0x70e, 0xe2ca, 0x709, 0xe2d5, - 0x703, 0xe2e0, 0x6fd, 0xe2eb, 0x6f7, 0xe2f6, 0x6f2, 0xe301, - 0x6ec, 0xe30d, 0x6e6, 0xe318, 0x6e1, 0xe323, 0x6db, 0xe32e, - 0x6d5, 0xe33a, 0x6d0, 0xe345, 0x6ca, 0xe350, 0x6c5, 0xe35b, - 0x6bf, 0xe367, 0x6b9, 0xe372, 0x6b4, 0xe37d, 0x6ae, 0xe388, - 0x6a8, 0xe394, 0x6a3, 0xe39f, 0x69d, 0xe3aa, 0x698, 0xe3b5, - 0x692, 0xe3c1, 0x68d, 0xe3cc, 0x687, 0xe3d7, 0x682, 0xe3e2, - 0x67c, 0xe3ee, 0x677, 0xe3f9, 0x671, 0xe404, 0x66c, 0xe410, - 0x666, 0xe41b, 0x661, 0xe426, 0x65b, 0xe432, 0x656, 0xe43d, - 0x650, 0xe448, 0x64b, 0xe454, 0x645, 0xe45f, 0x640, 0xe46a, - 0x63b, 0xe476, 0x635, 0xe481, 0x630, 0xe48c, 0x62a, 0xe498, - 0x625, 0xe4a3, 0x620, 0xe4ae, 0x61a, 0xe4ba, 0x615, 0xe4c5, - 0x610, 0xe4d0, 0x60a, 0xe4dc, 0x605, 0xe4e7, 0x600, 0xe4f3, - 0x5fa, 0xe4fe, 0x5f5, 0xe509, 0x5f0, 0xe515, 0x5ea, 0xe520, - 0x5e5, 0xe52c, 0x5e0, 0xe537, 0x5db, 0xe542, 0x5d5, 0xe54e, - 0x5d0, 0xe559, 0x5cb, 0xe565, 0x5c6, 0xe570, 0x5c1, 0xe57c, - 0x5bb, 0xe587, 0x5b6, 0xe592, 0x5b1, 0xe59e, 0x5ac, 0xe5a9, - 0x5a7, 0xe5b5, 0x5a1, 0xe5c0, 0x59c, 0xe5cc, 0x597, 0xe5d7, - 0x592, 0xe5e3, 0x58d, 0xe5ee, 0x588, 0xe5fa, 0x583, 0xe605, - 0x57e, 0xe611, 0x578, 0xe61c, 0x573, 0xe628, 0x56e, 0xe633, - 0x569, 0xe63f, 0x564, 0xe64a, 0x55f, 0xe656, 0x55a, 0xe661, - 0x555, 0xe66d, 0x550, 0xe678, 0x54b, 0xe684, 0x546, 0xe68f, - 0x541, 0xe69b, 0x53c, 0xe6a6, 0x537, 0xe6b2, 0x532, 0xe6bd, - 0x52d, 0xe6c9, 0x528, 0xe6d4, 0x523, 0xe6e0, 0x51e, 0xe6ec, - 0x51a, 0xe6f7, 0x515, 0xe703, 0x510, 0xe70e, 0x50b, 0xe71a, - 0x506, 0xe725, 0x501, 0xe731, 0x4fc, 0xe73d, 0x4f7, 0xe748, - 0x4f2, 0xe754, 0x4ee, 0xe75f, 0x4e9, 0xe76b, 0x4e4, 0xe777, - 0x4df, 0xe782, 0x4da, 0xe78e, 0x4d6, 0xe799, 0x4d1, 0xe7a5, - 0x4cc, 0xe7b1, 0x4c7, 0xe7bc, 0x4c2, 0xe7c8, 0x4be, 0xe7d3, - 0x4b9, 0xe7df, 0x4b4, 0xe7eb, 0x4b0, 0xe7f6, 0x4ab, 0xe802, - 0x4a6, 0xe80e, 0x4a1, 0xe819, 0x49d, 0xe825, 0x498, 0xe831, - 0x493, 0xe83c, 0x48f, 0xe848, 0x48a, 0xe854, 0x485, 0xe85f, - 0x481, 0xe86b, 0x47c, 0xe877, 0x478, 0xe882, 0x473, 0xe88e, - 0x46e, 0xe89a, 0x46a, 0xe8a5, 0x465, 0xe8b1, 0x461, 0xe8bd, - 0x45c, 0xe8c9, 0x457, 0xe8d4, 0x453, 0xe8e0, 0x44e, 0xe8ec, - 0x44a, 0xe8f7, 0x445, 0xe903, 0x441, 0xe90f, 0x43c, 0xe91b, - 0x438, 0xe926, 0x433, 0xe932, 0x42f, 0xe93e, 0x42a, 0xe94a, - 0x426, 0xe955, 0x422, 0xe961, 0x41d, 0xe96d, 0x419, 0xe979, - 0x414, 0xe984, 0x410, 0xe990, 0x40b, 0xe99c, 0x407, 0xe9a8, - 0x403, 0xe9b4, 0x3fe, 0xe9bf, 0x3fa, 0xe9cb, 0x3f6, 0xe9d7, - 0x3f1, 0xe9e3, 0x3ed, 0xe9ee, 0x3e9, 0xe9fa, 0x3e4, 0xea06, - 0x3e0, 0xea12, 0x3dc, 0xea1e, 0x3d7, 0xea29, 0x3d3, 0xea35, - 0x3cf, 0xea41, 0x3ca, 0xea4d, 0x3c6, 0xea59, 0x3c2, 0xea65, - 0x3be, 0xea70, 0x3ba, 0xea7c, 0x3b5, 0xea88, 0x3b1, 0xea94, - 0x3ad, 0xeaa0, 0x3a9, 0xeaac, 0x3a5, 0xeab7, 0x3a0, 0xeac3, - 0x39c, 0xeacf, 0x398, 0xeadb, 0x394, 0xeae7, 0x390, 0xeaf3, - 0x38c, 0xeaff, 0x387, 0xeb0a, 0x383, 0xeb16, 0x37f, 0xeb22, - 0x37b, 0xeb2e, 0x377, 0xeb3a, 0x373, 0xeb46, 0x36f, 0xeb52, - 0x36b, 0xeb5e, 0x367, 0xeb6a, 0x363, 0xeb75, 0x35f, 0xeb81, - 0x35b, 0xeb8d, 0x357, 0xeb99, 0x353, 0xeba5, 0x34f, 0xebb1, - 0x34b, 0xebbd, 0x347, 0xebc9, 0x343, 0xebd5, 0x33f, 0xebe1, - 0x33b, 0xebed, 0x337, 0xebf9, 0x333, 0xec05, 0x32f, 0xec10, - 0x32b, 0xec1c, 0x327, 0xec28, 0x323, 0xec34, 0x320, 0xec40, - 0x31c, 0xec4c, 0x318, 0xec58, 0x314, 0xec64, 0x310, 0xec70, - 0x30c, 0xec7c, 0x308, 0xec88, 0x305, 0xec94, 0x301, 0xeca0, - 0x2fd, 0xecac, 0x2f9, 0xecb8, 0x2f5, 0xecc4, 0x2f2, 0xecd0, - 0x2ee, 0xecdc, 0x2ea, 0xece8, 0x2e6, 0xecf4, 0x2e3, 0xed00, - 0x2df, 0xed0c, 0x2db, 0xed18, 0x2d8, 0xed24, 0x2d4, 0xed30, - 0x2d0, 0xed3c, 0x2cc, 0xed48, 0x2c9, 0xed54, 0x2c5, 0xed60, - 0x2c1, 0xed6c, 0x2be, 0xed78, 0x2ba, 0xed84, 0x2b7, 0xed90, - 0x2b3, 0xed9c, 0x2af, 0xeda8, 0x2ac, 0xedb4, 0x2a8, 0xedc0, - 0x2a5, 0xedcc, 0x2a1, 0xedd8, 0x29d, 0xede4, 0x29a, 0xedf0, - 0x296, 0xedfc, 0x293, 0xee09, 0x28f, 0xee15, 0x28c, 0xee21, - 0x288, 0xee2d, 0x285, 0xee39, 0x281, 0xee45, 0x27e, 0xee51, - 0x27a, 0xee5d, 0x277, 0xee69, 0x273, 0xee75, 0x270, 0xee81, - 0x26d, 0xee8d, 0x269, 0xee99, 0x266, 0xeea6, 0x262, 0xeeb2, - 0x25f, 0xeebe, 0x25c, 0xeeca, 0x258, 0xeed6, 0x255, 0xeee2, - 0x251, 0xeeee, 0x24e, 0xeefa, 0x24b, 0xef06, 0x247, 0xef13, - 0x244, 0xef1f, 0x241, 0xef2b, 0x23e, 0xef37, 0x23a, 0xef43, - 0x237, 0xef4f, 0x234, 0xef5b, 0x230, 0xef67, 0x22d, 0xef74, - 0x22a, 0xef80, 0x227, 0xef8c, 0x223, 0xef98, 0x220, 0xefa4, - 0x21d, 0xefb0, 0x21a, 0xefbc, 0x217, 0xefc9, 0x213, 0xefd5, - 0x210, 0xefe1, 0x20d, 0xefed, 0x20a, 0xeff9, 0x207, 0xf005, - 0x204, 0xf012, 0x201, 0xf01e, 0x1fd, 0xf02a, 0x1fa, 0xf036, - 0x1f7, 0xf042, 0x1f4, 0xf04e, 0x1f1, 0xf05b, 0x1ee, 0xf067, - 0x1eb, 0xf073, 0x1e8, 0xf07f, 0x1e5, 0xf08b, 0x1e2, 0xf098, - 0x1df, 0xf0a4, 0x1dc, 0xf0b0, 0x1d9, 0xf0bc, 0x1d6, 0xf0c8, - 0x1d3, 0xf0d5, 0x1d0, 0xf0e1, 0x1cd, 0xf0ed, 0x1ca, 0xf0f9, - 0x1c7, 0xf105, 0x1c4, 0xf112, 0x1c1, 0xf11e, 0x1be, 0xf12a, - 0x1bb, 0xf136, 0x1b8, 0xf143, 0x1b6, 0xf14f, 0x1b3, 0xf15b, - 0x1b0, 0xf167, 0x1ad, 0xf174, 0x1aa, 0xf180, 0x1a7, 0xf18c, - 0x1a4, 0xf198, 0x1a2, 0xf1a4, 0x19f, 0xf1b1, 0x19c, 0xf1bd, - 0x199, 0xf1c9, 0x196, 0xf1d5, 0x194, 0xf1e2, 0x191, 0xf1ee, - 0x18e, 0xf1fa, 0x18b, 0xf207, 0x189, 0xf213, 0x186, 0xf21f, - 0x183, 0xf22b, 0x180, 0xf238, 0x17e, 0xf244, 0x17b, 0xf250, - 0x178, 0xf25c, 0x176, 0xf269, 0x173, 0xf275, 0x170, 0xf281, - 0x16e, 0xf28e, 0x16b, 0xf29a, 0x168, 0xf2a6, 0x166, 0xf2b2, - 0x163, 0xf2bf, 0x161, 0xf2cb, 0x15e, 0xf2d7, 0x15b, 0xf2e4, - 0x159, 0xf2f0, 0x156, 0xf2fc, 0x154, 0xf308, 0x151, 0xf315, - 0x14f, 0xf321, 0x14c, 0xf32d, 0x14a, 0xf33a, 0x147, 0xf346, - 0x145, 0xf352, 0x142, 0xf35f, 0x140, 0xf36b, 0x13d, 0xf377, - 0x13b, 0xf384, 0x138, 0xf390, 0x136, 0xf39c, 0x134, 0xf3a9, - 0x131, 0xf3b5, 0x12f, 0xf3c1, 0x12c, 0xf3ce, 0x12a, 0xf3da, - 0x128, 0xf3e6, 0x125, 0xf3f3, 0x123, 0xf3ff, 0x120, 0xf40b, - 0x11e, 0xf418, 0x11c, 0xf424, 0x119, 0xf430, 0x117, 0xf43d, - 0x115, 0xf449, 0x113, 0xf455, 0x110, 0xf462, 0x10e, 0xf46e, - 0x10c, 0xf47b, 0x109, 0xf487, 0x107, 0xf493, 0x105, 0xf4a0, - 0x103, 0xf4ac, 0x100, 0xf4b8, 0xfe, 0xf4c5, 0xfc, 0xf4d1, - 0xfa, 0xf4dd, 0xf8, 0xf4ea, 0xf6, 0xf4f6, 0xf3, 0xf503, - 0xf1, 0xf50f, 0xef, 0xf51b, 0xed, 0xf528, 0xeb, 0xf534, - 0xe9, 0xf540, 0xe7, 0xf54d, 0xe4, 0xf559, 0xe2, 0xf566, - 0xe0, 0xf572, 0xde, 0xf57e, 0xdc, 0xf58b, 0xda, 0xf597, - 0xd8, 0xf5a4, 0xd6, 0xf5b0, 0xd4, 0xf5bc, 0xd2, 0xf5c9, - 0xd0, 0xf5d5, 0xce, 0xf5e2, 0xcc, 0xf5ee, 0xca, 0xf5fa, - 0xc8, 0xf607, 0xc6, 0xf613, 0xc4, 0xf620, 0xc2, 0xf62c, - 0xc0, 0xf639, 0xbe, 0xf645, 0xbd, 0xf651, 0xbb, 0xf65e, - 0xb9, 0xf66a, 0xb7, 0xf677, 0xb5, 0xf683, 0xb3, 0xf690, - 0xb1, 0xf69c, 0xaf, 0xf6a8, 0xae, 0xf6b5, 0xac, 0xf6c1, - 0xaa, 0xf6ce, 0xa8, 0xf6da, 0xa6, 0xf6e7, 0xa5, 0xf6f3, - 0xa3, 0xf6ff, 0xa1, 0xf70c, 0x9f, 0xf718, 0x9e, 0xf725, - 0x9c, 0xf731, 0x9a, 0xf73e, 0x98, 0xf74a, 0x97, 0xf757, - 0x95, 0xf763, 0x93, 0xf76f, 0x92, 0xf77c, 0x90, 0xf788, - 0x8e, 0xf795, 0x8d, 0xf7a1, 0x8b, 0xf7ae, 0x89, 0xf7ba, - 0x88, 0xf7c7, 0x86, 0xf7d3, 0x85, 0xf7e0, 0x83, 0xf7ec, - 0x81, 0xf7f9, 0x80, 0xf805, 0x7e, 0xf811, 0x7d, 0xf81e, - 0x7b, 0xf82a, 0x7a, 0xf837, 0x78, 0xf843, 0x77, 0xf850, - 0x75, 0xf85c, 0x74, 0xf869, 0x72, 0xf875, 0x71, 0xf882, - 0x6f, 0xf88e, 0x6e, 0xf89b, 0x6c, 0xf8a7, 0x6b, 0xf8b4, - 0x69, 0xf8c0, 0x68, 0xf8cd, 0x67, 0xf8d9, 0x65, 0xf8e6, - 0x64, 0xf8f2, 0x62, 0xf8ff, 0x61, 0xf90b, 0x60, 0xf918, - 0x5e, 0xf924, 0x5d, 0xf931, 0x5c, 0xf93d, 0x5a, 0xf94a, - 0x59, 0xf956, 0x58, 0xf963, 0x56, 0xf96f, 0x55, 0xf97c, - 0x54, 0xf988, 0x53, 0xf995, 0x51, 0xf9a1, 0x50, 0xf9ae, - 0x4f, 0xf9ba, 0x4e, 0xf9c7, 0x4c, 0xf9d3, 0x4b, 0xf9e0, - 0x4a, 0xf9ec, 0x49, 0xf9f9, 0x48, 0xfa05, 0x47, 0xfa12, - 0x45, 0xfa1e, 0x44, 0xfa2b, 0x43, 0xfa37, 0x42, 0xfa44, - 0x41, 0xfa50, 0x40, 0xfa5d, 0x3f, 0xfa69, 0x3d, 0xfa76, - 0x3c, 0xfa82, 0x3b, 0xfa8f, 0x3a, 0xfa9b, 0x39, 0xfaa8, - 0x38, 0xfab4, 0x37, 0xfac1, 0x36, 0xfacd, 0x35, 0xfada, - 0x34, 0xfae6, 0x33, 0xfaf3, 0x32, 0xfb00, 0x31, 0xfb0c, - 0x30, 0xfb19, 0x2f, 0xfb25, 0x2e, 0xfb32, 0x2d, 0xfb3e, - 0x2c, 0xfb4b, 0x2b, 0xfb57, 0x2b, 0xfb64, 0x2a, 0xfb70, - 0x29, 0xfb7d, 0x28, 0xfb89, 0x27, 0xfb96, 0x26, 0xfba2, - 0x25, 0xfbaf, 0x24, 0xfbbc, 0x24, 0xfbc8, 0x23, 0xfbd5, - 0x22, 0xfbe1, 0x21, 0xfbee, 0x20, 0xfbfa, 0x20, 0xfc07, - 0x1f, 0xfc13, 0x1e, 0xfc20, 0x1d, 0xfc2c, 0x1d, 0xfc39, - 0x1c, 0xfc45, 0x1b, 0xfc52, 0x1a, 0xfc5f, 0x1a, 0xfc6b, - 0x19, 0xfc78, 0x18, 0xfc84, 0x18, 0xfc91, 0x17, 0xfc9d, - 0x16, 0xfcaa, 0x16, 0xfcb6, 0x15, 0xfcc3, 0x14, 0xfcd0, - 0x14, 0xfcdc, 0x13, 0xfce9, 0x13, 0xfcf5, 0x12, 0xfd02, - 0x11, 0xfd0e, 0x11, 0xfd1b, 0x10, 0xfd27, 0x10, 0xfd34, - 0xf, 0xfd40, 0xf, 0xfd4d, 0xe, 0xfd5a, 0xe, 0xfd66, - 0xd, 0xfd73, 0xd, 0xfd7f, 0xc, 0xfd8c, 0xc, 0xfd98, - 0xb, 0xfda5, 0xb, 0xfdb2, 0xa, 0xfdbe, 0xa, 0xfdcb, - 0x9, 0xfdd7, 0x9, 0xfde4, 0x9, 0xfdf0, 0x8, 0xfdfd, - 0x8, 0xfe09, 0x7, 0xfe16, 0x7, 0xfe23, 0x7, 0xfe2f, - 0x6, 0xfe3c, 0x6, 0xfe48, 0x6, 0xfe55, 0x5, 0xfe61, - 0x5, 0xfe6e, 0x5, 0xfe7a, 0x4, 0xfe87, 0x4, 0xfe94, - 0x4, 0xfea0, 0x4, 0xfead, 0x3, 0xfeb9, 0x3, 0xfec6, - 0x3, 0xfed2, 0x3, 0xfedf, 0x2, 0xfeec, 0x2, 0xfef8, - 0x2, 0xff05, 0x2, 0xff11, 0x2, 0xff1e, 0x1, 0xff2a, - 0x1, 0xff37, 0x1, 0xff44, 0x1, 0xff50, 0x1, 0xff5d, - 0x1, 0xff69, 0x1, 0xff76, 0x0, 0xff82, 0x0, 0xff8f, - 0x0, 0xff9b, 0x0, 0xffa8, 0x0, 0xffb5, 0x0, 0xffc1, - 0x0, 0xffce, 0x0, 0xffda, 0x0, 0xffe7, 0x0, 0xfff3, - 0x0, 0x0, 0x0, 0xd, 0x0, 0x19, 0x0, 0x26, - 0x0, 0x32, 0x0, 0x3f, 0x0, 0x4b, 0x0, 0x58, - 0x0, 0x65, 0x0, 0x71, 0x0, 0x7e, 0x1, 0x8a, - 0x1, 0x97, 0x1, 0xa3, 0x1, 0xb0, 0x1, 0xbc, - 0x1, 0xc9, 0x1, 0xd6, 0x2, 0xe2, 0x2, 0xef, - 0x2, 0xfb, 0x2, 0x108, 0x2, 0x114, 0x3, 0x121, - 0x3, 0x12e, 0x3, 0x13a, 0x3, 0x147, 0x4, 0x153, - 0x4, 0x160, 0x4, 0x16c, 0x4, 0x179, 0x5, 0x186, - 0x5, 0x192, 0x5, 0x19f, 0x6, 0x1ab, 0x6, 0x1b8, - 0x6, 0x1c4, 0x7, 0x1d1, 0x7, 0x1dd, 0x7, 0x1ea, - 0x8, 0x1f7, 0x8, 0x203, 0x9, 0x210, 0x9, 0x21c, - 0x9, 0x229, 0xa, 0x235, 0xa, 0x242, 0xb, 0x24e, - 0xb, 0x25b, 0xc, 0x268, 0xc, 0x274, 0xd, 0x281, - 0xd, 0x28d, 0xe, 0x29a, 0xe, 0x2a6, 0xf, 0x2b3, - 0xf, 0x2c0, 0x10, 0x2cc, 0x10, 0x2d9, 0x11, 0x2e5, - 0x11, 0x2f2, 0x12, 0x2fe, 0x13, 0x30b, 0x13, 0x317, - 0x14, 0x324, 0x14, 0x330, 0x15, 0x33d, 0x16, 0x34a, - 0x16, 0x356, 0x17, 0x363, 0x18, 0x36f, 0x18, 0x37c, - 0x19, 0x388, 0x1a, 0x395, 0x1a, 0x3a1, 0x1b, 0x3ae, - 0x1c, 0x3bb, 0x1d, 0x3c7, 0x1d, 0x3d4, 0x1e, 0x3e0, - 0x1f, 0x3ed, 0x20, 0x3f9, 0x20, 0x406, 0x21, 0x412, - 0x22, 0x41f, 0x23, 0x42b, 0x24, 0x438, 0x24, 0x444, - 0x25, 0x451, 0x26, 0x45e, 0x27, 0x46a, 0x28, 0x477, - 0x29, 0x483, 0x2a, 0x490, 0x2b, 0x49c, 0x2b, 0x4a9, - 0x2c, 0x4b5, 0x2d, 0x4c2, 0x2e, 0x4ce, 0x2f, 0x4db, - 0x30, 0x4e7, 0x31, 0x4f4, 0x32, 0x500, 0x33, 0x50d, - 0x34, 0x51a, 0x35, 0x526, 0x36, 0x533, 0x37, 0x53f, - 0x38, 0x54c, 0x39, 0x558, 0x3a, 0x565, 0x3b, 0x571, - 0x3c, 0x57e, 0x3d, 0x58a, 0x3f, 0x597, 0x40, 0x5a3, - 0x41, 0x5b0, 0x42, 0x5bc, 0x43, 0x5c9, 0x44, 0x5d5, - 0x45, 0x5e2, 0x47, 0x5ee, 0x48, 0x5fb, 0x49, 0x607, - 0x4a, 0x614, 0x4b, 0x620, 0x4c, 0x62d, 0x4e, 0x639, - 0x4f, 0x646, 0x50, 0x652, 0x51, 0x65f, 0x53, 0x66b, - 0x54, 0x678, 0x55, 0x684, 0x56, 0x691, 0x58, 0x69d, - 0x59, 0x6aa, 0x5a, 0x6b6, 0x5c, 0x6c3, 0x5d, 0x6cf, - 0x5e, 0x6dc, 0x60, 0x6e8, 0x61, 0x6f5, 0x62, 0x701, - 0x64, 0x70e, 0x65, 0x71a, 0x67, 0x727, 0x68, 0x733, - 0x69, 0x740, 0x6b, 0x74c, 0x6c, 0x759, 0x6e, 0x765, - 0x6f, 0x772, 0x71, 0x77e, 0x72, 0x78b, 0x74, 0x797, - 0x75, 0x7a4, 0x77, 0x7b0, 0x78, 0x7bd, 0x7a, 0x7c9, - 0x7b, 0x7d6, 0x7d, 0x7e2, 0x7e, 0x7ef, 0x80, 0x7fb, - 0x81, 0x807, 0x83, 0x814, 0x85, 0x820, 0x86, 0x82d, - 0x88, 0x839, 0x89, 0x846, 0x8b, 0x852, 0x8d, 0x85f, - 0x8e, 0x86b, 0x90, 0x878, 0x92, 0x884, 0x93, 0x891, - 0x95, 0x89d, 0x97, 0x8a9, 0x98, 0x8b6, 0x9a, 0x8c2, - 0x9c, 0x8cf, 0x9e, 0x8db, 0x9f, 0x8e8, 0xa1, 0x8f4, - 0xa3, 0x901, 0xa5, 0x90d, 0xa6, 0x919, 0xa8, 0x926, - 0xaa, 0x932, 0xac, 0x93f, 0xae, 0x94b, 0xaf, 0x958, - 0xb1, 0x964, 0xb3, 0x970, 0xb5, 0x97d, 0xb7, 0x989, - 0xb9, 0x996, 0xbb, 0x9a2, 0xbd, 0x9af, 0xbe, 0x9bb, - 0xc0, 0x9c7, 0xc2, 0x9d4, 0xc4, 0x9e0, 0xc6, 0x9ed, - 0xc8, 0x9f9, 0xca, 0xa06, 0xcc, 0xa12, 0xce, 0xa1e, - 0xd0, 0xa2b, 0xd2, 0xa37, 0xd4, 0xa44, 0xd6, 0xa50, - 0xd8, 0xa5c, 0xda, 0xa69, 0xdc, 0xa75, 0xde, 0xa82, - 0xe0, 0xa8e, 0xe2, 0xa9a, 0xe4, 0xaa7, 0xe7, 0xab3, - 0xe9, 0xac0, 0xeb, 0xacc, 0xed, 0xad8, 0xef, 0xae5, - 0xf1, 0xaf1, 0xf3, 0xafd, 0xf6, 0xb0a, 0xf8, 0xb16, - 0xfa, 0xb23, 0xfc, 0xb2f, 0xfe, 0xb3b, 0x100, 0xb48, - 0x103, 0xb54, 0x105, 0xb60, 0x107, 0xb6d, 0x109, 0xb79, - 0x10c, 0xb85, 0x10e, 0xb92, 0x110, 0xb9e, 0x113, 0xbab, - 0x115, 0xbb7, 0x117, 0xbc3, 0x119, 0xbd0, 0x11c, 0xbdc, - 0x11e, 0xbe8, 0x120, 0xbf5, 0x123, 0xc01, 0x125, 0xc0d, - 0x128, 0xc1a, 0x12a, 0xc26, 0x12c, 0xc32, 0x12f, 0xc3f, - 0x131, 0xc4b, 0x134, 0xc57, 0x136, 0xc64, 0x138, 0xc70, - 0x13b, 0xc7c, 0x13d, 0xc89, 0x140, 0xc95, 0x142, 0xca1, - 0x145, 0xcae, 0x147, 0xcba, 0x14a, 0xcc6, 0x14c, 0xcd3, - 0x14f, 0xcdf, 0x151, 0xceb, 0x154, 0xcf8, 0x156, 0xd04, - 0x159, 0xd10, 0x15b, 0xd1c, 0x15e, 0xd29, 0x161, 0xd35, - 0x163, 0xd41, 0x166, 0xd4e, 0x168, 0xd5a, 0x16b, 0xd66, - 0x16e, 0xd72, 0x170, 0xd7f, 0x173, 0xd8b, 0x176, 0xd97, - 0x178, 0xda4, 0x17b, 0xdb0, 0x17e, 0xdbc, 0x180, 0xdc8, - 0x183, 0xdd5, 0x186, 0xde1, 0x189, 0xded, 0x18b, 0xdf9, - 0x18e, 0xe06, 0x191, 0xe12, 0x194, 0xe1e, 0x196, 0xe2b, - 0x199, 0xe37, 0x19c, 0xe43, 0x19f, 0xe4f, 0x1a2, 0xe5c, - 0x1a4, 0xe68, 0x1a7, 0xe74, 0x1aa, 0xe80, 0x1ad, 0xe8c, - 0x1b0, 0xe99, 0x1b3, 0xea5, 0x1b6, 0xeb1, 0x1b8, 0xebd, - 0x1bb, 0xeca, 0x1be, 0xed6, 0x1c1, 0xee2, 0x1c4, 0xeee, - 0x1c7, 0xefb, 0x1ca, 0xf07, 0x1cd, 0xf13, 0x1d0, 0xf1f, - 0x1d3, 0xf2b, 0x1d6, 0xf38, 0x1d9, 0xf44, 0x1dc, 0xf50, - 0x1df, 0xf5c, 0x1e2, 0xf68, 0x1e5, 0xf75, 0x1e8, 0xf81, - 0x1eb, 0xf8d, 0x1ee, 0xf99, 0x1f1, 0xfa5, 0x1f4, 0xfb2, - 0x1f7, 0xfbe, 0x1fa, 0xfca, 0x1fd, 0xfd6, 0x201, 0xfe2, - 0x204, 0xfee, 0x207, 0xffb, 0x20a, 0x1007, 0x20d, 0x1013, - 0x210, 0x101f, 0x213, 0x102b, 0x217, 0x1037, 0x21a, 0x1044, - 0x21d, 0x1050, 0x220, 0x105c, 0x223, 0x1068, 0x227, 0x1074, - 0x22a, 0x1080, 0x22d, 0x108c, 0x230, 0x1099, 0x234, 0x10a5, - 0x237, 0x10b1, 0x23a, 0x10bd, 0x23e, 0x10c9, 0x241, 0x10d5, - 0x244, 0x10e1, 0x247, 0x10ed, 0x24b, 0x10fa, 0x24e, 0x1106, - 0x251, 0x1112, 0x255, 0x111e, 0x258, 0x112a, 0x25c, 0x1136, - 0x25f, 0x1142, 0x262, 0x114e, 0x266, 0x115a, 0x269, 0x1167, - 0x26d, 0x1173, 0x270, 0x117f, 0x273, 0x118b, 0x277, 0x1197, - 0x27a, 0x11a3, 0x27e, 0x11af, 0x281, 0x11bb, 0x285, 0x11c7, - 0x288, 0x11d3, 0x28c, 0x11df, 0x28f, 0x11eb, 0x293, 0x11f7, - 0x296, 0x1204, 0x29a, 0x1210, 0x29d, 0x121c, 0x2a1, 0x1228, - 0x2a5, 0x1234, 0x2a8, 0x1240, 0x2ac, 0x124c, 0x2af, 0x1258, - 0x2b3, 0x1264, 0x2b7, 0x1270, 0x2ba, 0x127c, 0x2be, 0x1288, - 0x2c1, 0x1294, 0x2c5, 0x12a0, 0x2c9, 0x12ac, 0x2cc, 0x12b8, - 0x2d0, 0x12c4, 0x2d4, 0x12d0, 0x2d8, 0x12dc, 0x2db, 0x12e8, - 0x2df, 0x12f4, 0x2e3, 0x1300, 0x2e6, 0x130c, 0x2ea, 0x1318, - 0x2ee, 0x1324, 0x2f2, 0x1330, 0x2f5, 0x133c, 0x2f9, 0x1348, - 0x2fd, 0x1354, 0x301, 0x1360, 0x305, 0x136c, 0x308, 0x1378, - 0x30c, 0x1384, 0x310, 0x1390, 0x314, 0x139c, 0x318, 0x13a8, - 0x31c, 0x13b4, 0x320, 0x13c0, 0x323, 0x13cc, 0x327, 0x13d8, - 0x32b, 0x13e4, 0x32f, 0x13f0, 0x333, 0x13fb, 0x337, 0x1407, - 0x33b, 0x1413, 0x33f, 0x141f, 0x343, 0x142b, 0x347, 0x1437, - 0x34b, 0x1443, 0x34f, 0x144f, 0x353, 0x145b, 0x357, 0x1467, - 0x35b, 0x1473, 0x35f, 0x147f, 0x363, 0x148b, 0x367, 0x1496, - 0x36b, 0x14a2, 0x36f, 0x14ae, 0x373, 0x14ba, 0x377, 0x14c6, - 0x37b, 0x14d2, 0x37f, 0x14de, 0x383, 0x14ea, 0x387, 0x14f6, - 0x38c, 0x1501, 0x390, 0x150d, 0x394, 0x1519, 0x398, 0x1525, - 0x39c, 0x1531, 0x3a0, 0x153d, 0x3a5, 0x1549, 0x3a9, 0x1554, - 0x3ad, 0x1560, 0x3b1, 0x156c, 0x3b5, 0x1578, 0x3ba, 0x1584, - 0x3be, 0x1590, 0x3c2, 0x159b, 0x3c6, 0x15a7, 0x3ca, 0x15b3, - 0x3cf, 0x15bf, 0x3d3, 0x15cb, 0x3d7, 0x15d7, 0x3dc, 0x15e2, - 0x3e0, 0x15ee, 0x3e4, 0x15fa, 0x3e9, 0x1606, 0x3ed, 0x1612, - 0x3f1, 0x161d, 0x3f6, 0x1629, 0x3fa, 0x1635, 0x3fe, 0x1641, - 0x403, 0x164c, 0x407, 0x1658, 0x40b, 0x1664, 0x410, 0x1670, - 0x414, 0x167c, 0x419, 0x1687, 0x41d, 0x1693, 0x422, 0x169f, - 0x426, 0x16ab, 0x42a, 0x16b6, 0x42f, 0x16c2, 0x433, 0x16ce, - 0x438, 0x16da, 0x43c, 0x16e5, 0x441, 0x16f1, 0x445, 0x16fd, - 0x44a, 0x1709, 0x44e, 0x1714, 0x453, 0x1720, 0x457, 0x172c, - 0x45c, 0x1737, 0x461, 0x1743, 0x465, 0x174f, 0x46a, 0x175b, - 0x46e, 0x1766, 0x473, 0x1772, 0x478, 0x177e, 0x47c, 0x1789, - 0x481, 0x1795, 0x485, 0x17a1, 0x48a, 0x17ac, 0x48f, 0x17b8, - 0x493, 0x17c4, 0x498, 0x17cf, 0x49d, 0x17db, 0x4a1, 0x17e7, - 0x4a6, 0x17f2, 0x4ab, 0x17fe, 0x4b0, 0x180a, 0x4b4, 0x1815, - 0x4b9, 0x1821, 0x4be, 0x182d, 0x4c2, 0x1838, 0x4c7, 0x1844, - 0x4cc, 0x184f, 0x4d1, 0x185b, 0x4d6, 0x1867, 0x4da, 0x1872, - 0x4df, 0x187e, 0x4e4, 0x1889, 0x4e9, 0x1895, 0x4ee, 0x18a1, - 0x4f2, 0x18ac, 0x4f7, 0x18b8, 0x4fc, 0x18c3, 0x501, 0x18cf, - 0x506, 0x18db, 0x50b, 0x18e6, 0x510, 0x18f2, 0x515, 0x18fd, - 0x51a, 0x1909, 0x51e, 0x1914, 0x523, 0x1920, 0x528, 0x192c, - 0x52d, 0x1937, 0x532, 0x1943, 0x537, 0x194e, 0x53c, 0x195a, - 0x541, 0x1965, 0x546, 0x1971, 0x54b, 0x197c, 0x550, 0x1988, - 0x555, 0x1993, 0x55a, 0x199f, 0x55f, 0x19aa, 0x564, 0x19b6, - 0x569, 0x19c1, 0x56e, 0x19cd, 0x573, 0x19d8, 0x578, 0x19e4, - 0x57e, 0x19ef, 0x583, 0x19fb, 0x588, 0x1a06, 0x58d, 0x1a12, - 0x592, 0x1a1d, 0x597, 0x1a29, 0x59c, 0x1a34, 0x5a1, 0x1a40, - 0x5a7, 0x1a4b, 0x5ac, 0x1a57, 0x5b1, 0x1a62, 0x5b6, 0x1a6e, - 0x5bb, 0x1a79, 0x5c1, 0x1a84, 0x5c6, 0x1a90, 0x5cb, 0x1a9b, - 0x5d0, 0x1aa7, 0x5d5, 0x1ab2, 0x5db, 0x1abe, 0x5e0, 0x1ac9, - 0x5e5, 0x1ad4, 0x5ea, 0x1ae0, 0x5f0, 0x1aeb, 0x5f5, 0x1af7, - 0x5fa, 0x1b02, 0x600, 0x1b0d, 0x605, 0x1b19, 0x60a, 0x1b24, - 0x610, 0x1b30, 0x615, 0x1b3b, 0x61a, 0x1b46, 0x620, 0x1b52, - 0x625, 0x1b5d, 0x62a, 0x1b68, 0x630, 0x1b74, 0x635, 0x1b7f, - 0x63b, 0x1b8a, 0x640, 0x1b96, 0x645, 0x1ba1, 0x64b, 0x1bac, - 0x650, 0x1bb8, 0x656, 0x1bc3, 0x65b, 0x1bce, 0x661, 0x1bda, - 0x666, 0x1be5, 0x66c, 0x1bf0, 0x671, 0x1bfc, 0x677, 0x1c07, - 0x67c, 0x1c12, 0x682, 0x1c1e, 0x687, 0x1c29, 0x68d, 0x1c34, - 0x692, 0x1c3f, 0x698, 0x1c4b, 0x69d, 0x1c56, 0x6a3, 0x1c61, - 0x6a8, 0x1c6c, 0x6ae, 0x1c78, 0x6b4, 0x1c83, 0x6b9, 0x1c8e, - 0x6bf, 0x1c99, 0x6c5, 0x1ca5, 0x6ca, 0x1cb0, 0x6d0, 0x1cbb, - 0x6d5, 0x1cc6, 0x6db, 0x1cd2, 0x6e1, 0x1cdd, 0x6e6, 0x1ce8, - 0x6ec, 0x1cf3, 0x6f2, 0x1cff, 0x6f7, 0x1d0a, 0x6fd, 0x1d15, - 0x703, 0x1d20, 0x709, 0x1d2b, 0x70e, 0x1d36, 0x714, 0x1d42, - 0x71a, 0x1d4d, 0x720, 0x1d58, 0x725, 0x1d63, 0x72b, 0x1d6e, - 0x731, 0x1d79, 0x737, 0x1d85, 0x73d, 0x1d90, 0x742, 0x1d9b, - 0x748, 0x1da6, 0x74e, 0x1db1, 0x754, 0x1dbc, 0x75a, 0x1dc7, - 0x75f, 0x1dd3, 0x765, 0x1dde, 0x76b, 0x1de9, 0x771, 0x1df4, - 0x777, 0x1dff, 0x77d, 0x1e0a, 0x783, 0x1e15, 0x789, 0x1e20, - 0x78f, 0x1e2b, 0x795, 0x1e36, 0x79a, 0x1e42, 0x7a0, 0x1e4d, - 0x7a6, 0x1e58, 0x7ac, 0x1e63, 0x7b2, 0x1e6e, 0x7b8, 0x1e79, - 0x7be, 0x1e84, 0x7c4, 0x1e8f, 0x7ca, 0x1e9a, 0x7d0, 0x1ea5, - 0x7d6, 0x1eb0, 0x7dc, 0x1ebb, 0x7e2, 0x1ec6, 0x7e8, 0x1ed1, - 0x7ee, 0x1edc, 0x7f5, 0x1ee7, 0x7fb, 0x1ef2, 0x801, 0x1efd, - 0x807, 0x1f08, 0x80d, 0x1f13, 0x813, 0x1f1e, 0x819, 0x1f29, - 0x81f, 0x1f34, 0x825, 0x1f3f, 0x82b, 0x1f4a, 0x832, 0x1f55, - 0x838, 0x1f60, 0x83e, 0x1f6b, 0x844, 0x1f76, 0x84a, 0x1f81, - 0x850, 0x1f8c, 0x857, 0x1f97, 0x85d, 0x1fa2, 0x863, 0x1fac, - 0x869, 0x1fb7, 0x870, 0x1fc2, 0x876, 0x1fcd, 0x87c, 0x1fd8, - 0x882, 0x1fe3, 0x889, 0x1fee, 0x88f, 0x1ff9, 0x895, 0x2004, - 0x89b, 0x200f, 0x8a2, 0x2019, 0x8a8, 0x2024, 0x8ae, 0x202f, - 0x8b5, 0x203a, 0x8bb, 0x2045, 0x8c1, 0x2050, 0x8c8, 0x205b, - 0x8ce, 0x2065, 0x8d4, 0x2070, 0x8db, 0x207b, 0x8e1, 0x2086, - 0x8e8, 0x2091, 0x8ee, 0x209b, 0x8f4, 0x20a6, 0x8fb, 0x20b1, - 0x901, 0x20bc, 0x908, 0x20c7, 0x90e, 0x20d1, 0x915, 0x20dc, - 0x91b, 0x20e7, 0x921, 0x20f2, 0x928, 0x20fd, 0x92e, 0x2107, - 0x935, 0x2112, 0x93b, 0x211d, 0x942, 0x2128, 0x948, 0x2132, - 0x94f, 0x213d, 0x955, 0x2148, 0x95c, 0x2153, 0x963, 0x215d, - 0x969, 0x2168, 0x970, 0x2173, 0x976, 0x217d, 0x97d, 0x2188, - 0x983, 0x2193, 0x98a, 0x219e, 0x991, 0x21a8, 0x997, 0x21b3, - 0x99e, 0x21be, 0x9a4, 0x21c8, 0x9ab, 0x21d3, 0x9b2, 0x21de, - 0x9b8, 0x21e8, 0x9bf, 0x21f3, 0x9c6, 0x21fe, 0x9cc, 0x2208, - 0x9d3, 0x2213, 0x9da, 0x221e, 0x9e0, 0x2228, 0x9e7, 0x2233, - 0x9ee, 0x223d, 0x9f5, 0x2248, 0x9fb, 0x2253, 0xa02, 0x225d, - 0xa09, 0x2268, 0xa10, 0x2272, 0xa16, 0x227d, 0xa1d, 0x2288, - 0xa24, 0x2292, 0xa2b, 0x229d, 0xa32, 0x22a7, 0xa38, 0x22b2, - 0xa3f, 0x22bc, 0xa46, 0x22c7, 0xa4d, 0x22d2, 0xa54, 0x22dc, - 0xa5b, 0x22e7, 0xa61, 0x22f1, 0xa68, 0x22fc, 0xa6f, 0x2306, - 0xa76, 0x2311, 0xa7d, 0x231b, 0xa84, 0x2326, 0xa8b, 0x2330, - 0xa92, 0x233b, 0xa99, 0x2345, 0xa9f, 0x2350, 0xaa6, 0x235a, - 0xaad, 0x2365, 0xab4, 0x236f, 0xabb, 0x237a, 0xac2, 0x2384, - 0xac9, 0x238e, 0xad0, 0x2399, 0xad7, 0x23a3, 0xade, 0x23ae, - 0xae5, 0x23b8, 0xaec, 0x23c3, 0xaf3, 0x23cd, 0xafa, 0x23d7, - 0xb01, 0x23e2, 0xb08, 0x23ec, 0xb0f, 0x23f7, 0xb16, 0x2401, - 0xb1e, 0x240b, 0xb25, 0x2416, 0xb2c, 0x2420, 0xb33, 0x242b, - 0xb3a, 0x2435, 0xb41, 0x243f, 0xb48, 0x244a, 0xb4f, 0x2454, - 0xb56, 0x245e, 0xb5e, 0x2469, 0xb65, 0x2473, 0xb6c, 0x247d, - 0xb73, 0x2488, 0xb7a, 0x2492, 0xb81, 0x249c, 0xb89, 0x24a7, - 0xb90, 0x24b1, 0xb97, 0x24bb, 0xb9e, 0x24c5, 0xba5, 0x24d0, - 0xbad, 0x24da, 0xbb4, 0x24e4, 0xbbb, 0x24ef, 0xbc2, 0x24f9, - 0xbca, 0x2503, 0xbd1, 0x250d, 0xbd8, 0x2518, 0xbe0, 0x2522, - 0xbe7, 0x252c, 0xbee, 0x2536, 0xbf5, 0x2541, 0xbfd, 0x254b, - 0xc04, 0x2555, 0xc0b, 0x255f, 0xc13, 0x2569, 0xc1a, 0x2574, - 0xc21, 0x257e, 0xc29, 0x2588, 0xc30, 0x2592, 0xc38, 0x259c, - 0xc3f, 0x25a6, 0xc46, 0x25b1, 0xc4e, 0x25bb, 0xc55, 0x25c5, - 0xc5d, 0x25cf, 0xc64, 0x25d9, 0xc6b, 0x25e3, 0xc73, 0x25ed, - 0xc7a, 0x25f8, 0xc82, 0x2602, 0xc89, 0x260c, 0xc91, 0x2616, - 0xc98, 0x2620, 0xca0, 0x262a, 0xca7, 0x2634, 0xcaf, 0x263e, - 0xcb6, 0x2648, 0xcbe, 0x2652, 0xcc5, 0x265c, 0xccd, 0x2666, - 0xcd4, 0x2671, 0xcdc, 0x267b, 0xce3, 0x2685, 0xceb, 0x268f, - 0xcf3, 0x2699, 0xcfa, 0x26a3, 0xd02, 0x26ad, 0xd09, 0x26b7, - 0xd11, 0x26c1, 0xd19, 0x26cb, 0xd20, 0x26d5, 0xd28, 0x26df, - 0xd30, 0x26e9, 0xd37, 0x26f3, 0xd3f, 0x26fd, 0xd46, 0x2707, - 0xd4e, 0x2711, 0xd56, 0x271a, 0xd5d, 0x2724, 0xd65, 0x272e, - 0xd6d, 0x2738, 0xd75, 0x2742, 0xd7c, 0x274c, 0xd84, 0x2756, - 0xd8c, 0x2760, 0xd93, 0x276a, 0xd9b, 0x2774, 0xda3, 0x277e, - 0xdab, 0x2788, 0xdb2, 0x2791, 0xdba, 0x279b, 0xdc2, 0x27a5, - 0xdca, 0x27af, 0xdd2, 0x27b9, 0xdd9, 0x27c3, 0xde1, 0x27cd, - 0xde9, 0x27d6, 0xdf1, 0x27e0, 0xdf9, 0x27ea, 0xe01, 0x27f4, - 0xe08, 0x27fe, 0xe10, 0x2808, 0xe18, 0x2811, 0xe20, 0x281b, - 0xe28, 0x2825, 0xe30, 0x282f, 0xe38, 0x2838, 0xe40, 0x2842, - 0xe47, 0x284c, 0xe4f, 0x2856, 0xe57, 0x2860, 0xe5f, 0x2869, - 0xe67, 0x2873, 0xe6f, 0x287d, 0xe77, 0x2886, 0xe7f, 0x2890, - 0xe87, 0x289a, 0xe8f, 0x28a4, 0xe97, 0x28ad, 0xe9f, 0x28b7, - 0xea7, 0x28c1, 0xeaf, 0x28ca, 0xeb7, 0x28d4, 0xebf, 0x28de, - 0xec7, 0x28e7, 0xecf, 0x28f1, 0xed7, 0x28fb, 0xedf, 0x2904, - 0xee7, 0x290e, 0xeef, 0x2918, 0xef7, 0x2921, 0xeff, 0x292b, - 0xf07, 0x2935, 0xf10, 0x293e, 0xf18, 0x2948, 0xf20, 0x2951, - 0xf28, 0x295b, 0xf30, 0x2965, 0xf38, 0x296e, 0xf40, 0x2978, - 0xf48, 0x2981, 0xf51, 0x298b, 0xf59, 0x2994, 0xf61, 0x299e, - 0xf69, 0x29a7, 0xf71, 0x29b1, 0xf79, 0x29bb, 0xf82, 0x29c4, - 0xf8a, 0x29ce, 0xf92, 0x29d7, 0xf9a, 0x29e1, 0xfa3, 0x29ea, - 0xfab, 0x29f4, 0xfb3, 0x29fd, 0xfbb, 0x2a07, 0xfc4, 0x2a10, - 0xfcc, 0x2a1a, 0xfd4, 0x2a23, 0xfdc, 0x2a2c, 0xfe5, 0x2a36, - 0xfed, 0x2a3f, 0xff5, 0x2a49, 0xffe, 0x2a52, 0x1006, 0x2a5c, - 0x100e, 0x2a65, 0x1016, 0x2a6e, 0x101f, 0x2a78, 0x1027, 0x2a81, - 0x1030, 0x2a8b, 0x1038, 0x2a94, 0x1040, 0x2a9d, 0x1049, 0x2aa7, - 0x1051, 0x2ab0, 0x1059, 0x2ab9, 0x1062, 0x2ac3, 0x106a, 0x2acc, - 0x1073, 0x2ad6, 0x107b, 0x2adf, 0x1083, 0x2ae8, 0x108c, 0x2af2, - 0x1094, 0x2afb, 0x109d, 0x2b04, 0x10a5, 0x2b0d, 0x10ae, 0x2b17, - 0x10b6, 0x2b20, 0x10bf, 0x2b29, 0x10c7, 0x2b33, 0x10d0, 0x2b3c, - 0x10d8, 0x2b45, 0x10e0, 0x2b4e, 0x10e9, 0x2b58, 0x10f2, 0x2b61, - 0x10fa, 0x2b6a, 0x1103, 0x2b73, 0x110b, 0x2b7d, 0x1114, 0x2b86, - 0x111c, 0x2b8f, 0x1125, 0x2b98, 0x112d, 0x2ba1, 0x1136, 0x2bab, - 0x113e, 0x2bb4, 0x1147, 0x2bbd, 0x1150, 0x2bc6, 0x1158, 0x2bcf, - 0x1161, 0x2bd8, 0x1169, 0x2be2, 0x1172, 0x2beb, 0x117b, 0x2bf4, - 0x1183, 0x2bfd, 0x118c, 0x2c06, 0x1195, 0x2c0f, 0x119d, 0x2c18, - 0x11a6, 0x2c21, 0x11af, 0x2c2b, 0x11b7, 0x2c34, 0x11c0, 0x2c3d, - 0x11c9, 0x2c46, 0x11d1, 0x2c4f, 0x11da, 0x2c58, 0x11e3, 0x2c61, - 0x11eb, 0x2c6a, 0x11f4, 0x2c73, 0x11fd, 0x2c7c, 0x1206, 0x2c85, - 0x120e, 0x2c8e, 0x1217, 0x2c97, 0x1220, 0x2ca0, 0x1229, 0x2ca9, - 0x1231, 0x2cb2, 0x123a, 0x2cbb, 0x1243, 0x2cc4, 0x124c, 0x2ccd, - 0x1255, 0x2cd6, 0x125d, 0x2cdf, 0x1266, 0x2ce8, 0x126f, 0x2cf1, - 0x1278, 0x2cfa, 0x1281, 0x2d03, 0x128a, 0x2d0c, 0x1292, 0x2d15, - 0x129b, 0x2d1e, 0x12a4, 0x2d27, 0x12ad, 0x2d2f, 0x12b6, 0x2d38, - 0x12bf, 0x2d41, 0x12c8, 0x2d4a, 0x12d1, 0x2d53, 0x12d9, 0x2d5c, - 0x12e2, 0x2d65, 0x12eb, 0x2d6e, 0x12f4, 0x2d76, 0x12fd, 0x2d7f, - 0x1306, 0x2d88, 0x130f, 0x2d91, 0x1318, 0x2d9a, 0x1321, 0x2da3, - 0x132a, 0x2dab, 0x1333, 0x2db4, 0x133c, 0x2dbd, 0x1345, 0x2dc6, - 0x134e, 0x2dcf, 0x1357, 0x2dd7, 0x1360, 0x2de0, 0x1369, 0x2de9, - 0x1372, 0x2df2, 0x137b, 0x2dfa, 0x1384, 0x2e03, 0x138d, 0x2e0c, - 0x1396, 0x2e15, 0x139f, 0x2e1d, 0x13a8, 0x2e26, 0x13b1, 0x2e2f, - 0x13ba, 0x2e37, 0x13c3, 0x2e40, 0x13cc, 0x2e49, 0x13d5, 0x2e51, - 0x13df, 0x2e5a, 0x13e8, 0x2e63, 0x13f1, 0x2e6b, 0x13fa, 0x2e74, - 0x1403, 0x2e7d, 0x140c, 0x2e85, 0x1415, 0x2e8e, 0x141e, 0x2e97, - 0x1428, 0x2e9f, 0x1431, 0x2ea8, 0x143a, 0x2eb0, 0x1443, 0x2eb9, - 0x144c, 0x2ec2, 0x1455, 0x2eca, 0x145f, 0x2ed3, 0x1468, 0x2edb, - 0x1471, 0x2ee4, 0x147a, 0x2eec, 0x1483, 0x2ef5, 0x148d, 0x2efd, - 0x1496, 0x2f06, 0x149f, 0x2f0e, 0x14a8, 0x2f17, 0x14b2, 0x2f20, - 0x14bb, 0x2f28, 0x14c4, 0x2f30, 0x14cd, 0x2f39, 0x14d7, 0x2f41, - 0x14e0, 0x2f4a, 0x14e9, 0x2f52, 0x14f3, 0x2f5b, 0x14fc, 0x2f63, - 0x1505, 0x2f6c, 0x150e, 0x2f74, 0x1518, 0x2f7d, 0x1521, 0x2f85, - 0x152a, 0x2f8d, 0x1534, 0x2f96, 0x153d, 0x2f9e, 0x1547, 0x2fa7, - 0x1550, 0x2faf, 0x1559, 0x2fb7, 0x1563, 0x2fc0, 0x156c, 0x2fc8, - 0x1575, 0x2fd0, 0x157f, 0x2fd9, 0x1588, 0x2fe1, 0x1592, 0x2fea, - 0x159b, 0x2ff2, 0x15a4, 0x2ffa, 0x15ae, 0x3002, 0x15b7, 0x300b, - 0x15c1, 0x3013, 0x15ca, 0x301b, 0x15d4, 0x3024, 0x15dd, 0x302c, - 0x15e6, 0x3034, 0x15f0, 0x303c, 0x15f9, 0x3045, 0x1603, 0x304d, - 0x160c, 0x3055, 0x1616, 0x305d, 0x161f, 0x3066, 0x1629, 0x306e, - 0x1632, 0x3076, 0x163c, 0x307e, 0x1645, 0x3087, 0x164f, 0x308f, - 0x1659, 0x3097, 0x1662, 0x309f, 0x166c, 0x30a7, 0x1675, 0x30af, - 0x167f, 0x30b8, 0x1688, 0x30c0, 0x1692, 0x30c8, 0x169b, 0x30d0, - 0x16a5, 0x30d8, 0x16af, 0x30e0, 0x16b8, 0x30e8, 0x16c2, 0x30f0, - 0x16cb, 0x30f9, 0x16d5, 0x3101, 0x16df, 0x3109, 0x16e8, 0x3111, - 0x16f2, 0x3119, 0x16fc, 0x3121, 0x1705, 0x3129, 0x170f, 0x3131, - 0x1719, 0x3139, 0x1722, 0x3141, 0x172c, 0x3149, 0x1736, 0x3151, - 0x173f, 0x3159, 0x1749, 0x3161, 0x1753, 0x3169, 0x175c, 0x3171, - 0x1766, 0x3179, 0x1770, 0x3181, 0x177a, 0x3189, 0x1783, 0x3191, - 0x178d, 0x3199, 0x1797, 0x31a1, 0x17a0, 0x31a9, 0x17aa, 0x31b1, - 0x17b4, 0x31b9, 0x17be, 0x31c0, 0x17c8, 0x31c8, 0x17d1, 0x31d0, - 0x17db, 0x31d8, 0x17e5, 0x31e0, 0x17ef, 0x31e8, 0x17f8, 0x31f0, - 0x1802, 0x31f8, 0x180c, 0x31ff, 0x1816, 0x3207, 0x1820, 0x320f, - 0x182a, 0x3217, 0x1833, 0x321f, 0x183d, 0x3227, 0x1847, 0x322e, - 0x1851, 0x3236, 0x185b, 0x323e, 0x1865, 0x3246, 0x186f, 0x324e, - 0x1878, 0x3255, 0x1882, 0x325d, 0x188c, 0x3265, 0x1896, 0x326d, - 0x18a0, 0x3274, 0x18aa, 0x327c, 0x18b4, 0x3284, 0x18be, 0x328b, - 0x18c8, 0x3293, 0x18d2, 0x329b, 0x18dc, 0x32a3, 0x18e6, 0x32aa, - 0x18ef, 0x32b2, 0x18f9, 0x32ba, 0x1903, 0x32c1, 0x190d, 0x32c9, - 0x1917, 0x32d0, 0x1921, 0x32d8, 0x192b, 0x32e0, 0x1935, 0x32e7, - 0x193f, 0x32ef, 0x1949, 0x32f7, 0x1953, 0x32fe, 0x195d, 0x3306, - 0x1967, 0x330d, 0x1971, 0x3315, 0x197b, 0x331d, 0x1985, 0x3324, - 0x198f, 0x332c, 0x199a, 0x3333, 0x19a4, 0x333b, 0x19ae, 0x3342, - 0x19b8, 0x334a, 0x19c2, 0x3351, 0x19cc, 0x3359, 0x19d6, 0x3360, - 0x19e0, 0x3368, 0x19ea, 0x336f, 0x19f4, 0x3377, 0x19fe, 0x337e, - 0x1a08, 0x3386, 0x1a13, 0x338d, 0x1a1d, 0x3395, 0x1a27, 0x339c, - 0x1a31, 0x33a3, 0x1a3b, 0x33ab, 0x1a45, 0x33b2, 0x1a4f, 0x33ba, - 0x1a5a, 0x33c1, 0x1a64, 0x33c8, 0x1a6e, 0x33d0, 0x1a78, 0x33d7, - 0x1a82, 0x33df, 0x1a8c, 0x33e6, 0x1a97, 0x33ed, 0x1aa1, 0x33f5, - 0x1aab, 0x33fc, 0x1ab5, 0x3403, 0x1abf, 0x340b, 0x1aca, 0x3412, - 0x1ad4, 0x3419, 0x1ade, 0x3420, 0x1ae8, 0x3428, 0x1af3, 0x342f, - 0x1afd, 0x3436, 0x1b07, 0x343e, 0x1b11, 0x3445, 0x1b1c, 0x344c, - 0x1b26, 0x3453, 0x1b30, 0x345b, 0x1b3b, 0x3462, 0x1b45, 0x3469, - 0x1b4f, 0x3470, 0x1b59, 0x3477, 0x1b64, 0x347f, 0x1b6e, 0x3486, - 0x1b78, 0x348d, 0x1b83, 0x3494, 0x1b8d, 0x349b, 0x1b97, 0x34a2, - 0x1ba2, 0x34aa, 0x1bac, 0x34b1, 0x1bb6, 0x34b8, 0x1bc1, 0x34bf, - 0x1bcb, 0x34c6, 0x1bd5, 0x34cd, 0x1be0, 0x34d4, 0x1bea, 0x34db, - 0x1bf5, 0x34e2, 0x1bff, 0x34ea, 0x1c09, 0x34f1, 0x1c14, 0x34f8, - 0x1c1e, 0x34ff, 0x1c29, 0x3506, 0x1c33, 0x350d, 0x1c3d, 0x3514, - 0x1c48, 0x351b, 0x1c52, 0x3522, 0x1c5d, 0x3529, 0x1c67, 0x3530, - 0x1c72, 0x3537, 0x1c7c, 0x353e, 0x1c86, 0x3545, 0x1c91, 0x354c, - 0x1c9b, 0x3553, 0x1ca6, 0x355a, 0x1cb0, 0x3561, 0x1cbb, 0x3567, - 0x1cc5, 0x356e, 0x1cd0, 0x3575, 0x1cda, 0x357c, 0x1ce5, 0x3583, - 0x1cef, 0x358a, 0x1cfa, 0x3591, 0x1d04, 0x3598, 0x1d0f, 0x359f, - 0x1d19, 0x35a5, 0x1d24, 0x35ac, 0x1d2e, 0x35b3, 0x1d39, 0x35ba, - 0x1d44, 0x35c1, 0x1d4e, 0x35c8, 0x1d59, 0x35ce, 0x1d63, 0x35d5, - 0x1d6e, 0x35dc, 0x1d78, 0x35e3, 0x1d83, 0x35ea, 0x1d8e, 0x35f0, - 0x1d98, 0x35f7, 0x1da3, 0x35fe, 0x1dad, 0x3605, 0x1db8, 0x360b, - 0x1dc3, 0x3612, 0x1dcd, 0x3619, 0x1dd8, 0x3620, 0x1de2, 0x3626, - 0x1ded, 0x362d, 0x1df8, 0x3634, 0x1e02, 0x363a, 0x1e0d, 0x3641, - 0x1e18, 0x3648, 0x1e22, 0x364e, 0x1e2d, 0x3655, 0x1e38, 0x365c, - 0x1e42, 0x3662, 0x1e4d, 0x3669, 0x1e58, 0x366f, 0x1e62, 0x3676, - 0x1e6d, 0x367d, 0x1e78, 0x3683, 0x1e83, 0x368a, 0x1e8d, 0x3690, - 0x1e98, 0x3697, 0x1ea3, 0x369d, 0x1ead, 0x36a4, 0x1eb8, 0x36ab, - 0x1ec3, 0x36b1, 0x1ece, 0x36b8, 0x1ed8, 0x36be, 0x1ee3, 0x36c5, - 0x1eee, 0x36cb, 0x1ef9, 0x36d2, 0x1f03, 0x36d8, 0x1f0e, 0x36df, - 0x1f19, 0x36e5, 0x1f24, 0x36eb, 0x1f2f, 0x36f2, 0x1f39, 0x36f8, - 0x1f44, 0x36ff, 0x1f4f, 0x3705, 0x1f5a, 0x370c, 0x1f65, 0x3712, - 0x1f6f, 0x3718, 0x1f7a, 0x371f, 0x1f85, 0x3725, 0x1f90, 0x372c, - 0x1f9b, 0x3732, 0x1fa5, 0x3738, 0x1fb0, 0x373f, 0x1fbb, 0x3745, - 0x1fc6, 0x374b, 0x1fd1, 0x3752, 0x1fdc, 0x3758, 0x1fe7, 0x375e, - 0x1ff1, 0x3765, 0x1ffc, 0x376b, 0x2007, 0x3771, 0x2012, 0x3777, - 0x201d, 0x377e, 0x2028, 0x3784, 0x2033, 0x378a, 0x203e, 0x3790, - 0x2049, 0x3797, 0x2054, 0x379d, 0x205e, 0x37a3, 0x2069, 0x37a9, - 0x2074, 0x37b0, 0x207f, 0x37b6, 0x208a, 0x37bc, 0x2095, 0x37c2, - 0x20a0, 0x37c8, 0x20ab, 0x37ce, 0x20b6, 0x37d5, 0x20c1, 0x37db, - 0x20cc, 0x37e1, 0x20d7, 0x37e7, 0x20e2, 0x37ed, 0x20ed, 0x37f3, - 0x20f8, 0x37f9, 0x2103, 0x37ff, 0x210e, 0x3805, 0x2119, 0x380b, - 0x2124, 0x3812, 0x212f, 0x3818, 0x213a, 0x381e, 0x2145, 0x3824, - 0x2150, 0x382a, 0x215b, 0x3830, 0x2166, 0x3836, 0x2171, 0x383c, - 0x217c, 0x3842, 0x2187, 0x3848, 0x2192, 0x384e, 0x219d, 0x3854, - 0x21a8, 0x385a, 0x21b3, 0x3860, 0x21be, 0x3866, 0x21ca, 0x386b, - 0x21d5, 0x3871, 0x21e0, 0x3877, 0x21eb, 0x387d, 0x21f6, 0x3883, - 0x2201, 0x3889, 0x220c, 0x388f, 0x2217, 0x3895, 0x2222, 0x389b, - 0x222d, 0x38a1, 0x2239, 0x38a6, 0x2244, 0x38ac, 0x224f, 0x38b2, - 0x225a, 0x38b8, 0x2265, 0x38be, 0x2270, 0x38c3, 0x227b, 0x38c9, - 0x2287, 0x38cf, 0x2292, 0x38d5, 0x229d, 0x38db, 0x22a8, 0x38e0, - 0x22b3, 0x38e6, 0x22be, 0x38ec, 0x22ca, 0x38f2, 0x22d5, 0x38f7, - 0x22e0, 0x38fd, 0x22eb, 0x3903, 0x22f6, 0x3909, 0x2301, 0x390e, - 0x230d, 0x3914, 0x2318, 0x391a, 0x2323, 0x391f, 0x232e, 0x3925, - 0x233a, 0x392b, 0x2345, 0x3930, 0x2350, 0x3936, 0x235b, 0x393b, - 0x2367, 0x3941, 0x2372, 0x3947, 0x237d, 0x394c, 0x2388, 0x3952, - 0x2394, 0x3958, 0x239f, 0x395d, 0x23aa, 0x3963, 0x23b5, 0x3968, - 0x23c1, 0x396e, 0x23cc, 0x3973, 0x23d7, 0x3979, 0x23e2, 0x397e, - 0x23ee, 0x3984, 0x23f9, 0x3989, 0x2404, 0x398f, 0x2410, 0x3994, - 0x241b, 0x399a, 0x2426, 0x399f, 0x2432, 0x39a5, 0x243d, 0x39aa, - 0x2448, 0x39b0, 0x2454, 0x39b5, 0x245f, 0x39bb, 0x246a, 0x39c0, - 0x2476, 0x39c5, 0x2481, 0x39cb, 0x248c, 0x39d0, 0x2498, 0x39d6, - 0x24a3, 0x39db, 0x24ae, 0x39e0, 0x24ba, 0x39e6, 0x24c5, 0x39eb, - 0x24d0, 0x39f0, 0x24dc, 0x39f6, 0x24e7, 0x39fb, 0x24f3, 0x3a00, - 0x24fe, 0x3a06, 0x2509, 0x3a0b, 0x2515, 0x3a10, 0x2520, 0x3a16, - 0x252c, 0x3a1b, 0x2537, 0x3a20, 0x2542, 0x3a25, 0x254e, 0x3a2b, - 0x2559, 0x3a30, 0x2565, 0x3a35, 0x2570, 0x3a3a, 0x257c, 0x3a3f, - 0x2587, 0x3a45, 0x2592, 0x3a4a, 0x259e, 0x3a4f, 0x25a9, 0x3a54, - 0x25b5, 0x3a59, 0x25c0, 0x3a5f, 0x25cc, 0x3a64, 0x25d7, 0x3a69, - 0x25e3, 0x3a6e, 0x25ee, 0x3a73, 0x25fa, 0x3a78, 0x2605, 0x3a7d, - 0x2611, 0x3a82, 0x261c, 0x3a88, 0x2628, 0x3a8d, 0x2633, 0x3a92, - 0x263f, 0x3a97, 0x264a, 0x3a9c, 0x2656, 0x3aa1, 0x2661, 0x3aa6, - 0x266d, 0x3aab, 0x2678, 0x3ab0, 0x2684, 0x3ab5, 0x268f, 0x3aba, - 0x269b, 0x3abf, 0x26a6, 0x3ac4, 0x26b2, 0x3ac9, 0x26bd, 0x3ace, - 0x26c9, 0x3ad3, 0x26d4, 0x3ad8, 0x26e0, 0x3add, 0x26ec, 0x3ae2, - 0x26f7, 0x3ae6, 0x2703, 0x3aeb, 0x270e, 0x3af0, 0x271a, 0x3af5, - 0x2725, 0x3afa, 0x2731, 0x3aff, 0x273d, 0x3b04, 0x2748, 0x3b09, - 0x2754, 0x3b0e, 0x275f, 0x3b12, 0x276b, 0x3b17, 0x2777, 0x3b1c, - 0x2782, 0x3b21, 0x278e, 0x3b26, 0x2799, 0x3b2a, 0x27a5, 0x3b2f, - 0x27b1, 0x3b34, 0x27bc, 0x3b39, 0x27c8, 0x3b3e, 0x27d3, 0x3b42, - 0x27df, 0x3b47, 0x27eb, 0x3b4c, 0x27f6, 0x3b50, 0x2802, 0x3b55, - 0x280e, 0x3b5a, 0x2819, 0x3b5f, 0x2825, 0x3b63, 0x2831, 0x3b68, - 0x283c, 0x3b6d, 0x2848, 0x3b71, 0x2854, 0x3b76, 0x285f, 0x3b7b, - 0x286b, 0x3b7f, 0x2877, 0x3b84, 0x2882, 0x3b88, 0x288e, 0x3b8d, - 0x289a, 0x3b92, 0x28a5, 0x3b96, 0x28b1, 0x3b9b, 0x28bd, 0x3b9f, - 0x28c9, 0x3ba4, 0x28d4, 0x3ba9, 0x28e0, 0x3bad, 0x28ec, 0x3bb2, - 0x28f7, 0x3bb6, 0x2903, 0x3bbb, 0x290f, 0x3bbf, 0x291b, 0x3bc4, - 0x2926, 0x3bc8, 0x2932, 0x3bcd, 0x293e, 0x3bd1, 0x294a, 0x3bd6, - 0x2955, 0x3bda, 0x2961, 0x3bde, 0x296d, 0x3be3, 0x2979, 0x3be7, - 0x2984, 0x3bec, 0x2990, 0x3bf0, 0x299c, 0x3bf5, 0x29a8, 0x3bf9, - 0x29b4, 0x3bfd, 0x29bf, 0x3c02, 0x29cb, 0x3c06, 0x29d7, 0x3c0a, - 0x29e3, 0x3c0f, 0x29ee, 0x3c13, 0x29fa, 0x3c17, 0x2a06, 0x3c1c, - 0x2a12, 0x3c20, 0x2a1e, 0x3c24, 0x2a29, 0x3c29, 0x2a35, 0x3c2d, - 0x2a41, 0x3c31, 0x2a4d, 0x3c36, 0x2a59, 0x3c3a, 0x2a65, 0x3c3e, - 0x2a70, 0x3c42, 0x2a7c, 0x3c46, 0x2a88, 0x3c4b, 0x2a94, 0x3c4f, - 0x2aa0, 0x3c53, 0x2aac, 0x3c57, 0x2ab7, 0x3c5b, 0x2ac3, 0x3c60, - 0x2acf, 0x3c64, 0x2adb, 0x3c68, 0x2ae7, 0x3c6c, 0x2af3, 0x3c70, - 0x2aff, 0x3c74, 0x2b0a, 0x3c79, 0x2b16, 0x3c7d, 0x2b22, 0x3c81, - 0x2b2e, 0x3c85, 0x2b3a, 0x3c89, 0x2b46, 0x3c8d, 0x2b52, 0x3c91, - 0x2b5e, 0x3c95, 0x2b6a, 0x3c99, 0x2b75, 0x3c9d, 0x2b81, 0x3ca1, - 0x2b8d, 0x3ca5, 0x2b99, 0x3ca9, 0x2ba5, 0x3cad, 0x2bb1, 0x3cb1, - 0x2bbd, 0x3cb5, 0x2bc9, 0x3cb9, 0x2bd5, 0x3cbd, 0x2be1, 0x3cc1, - 0x2bed, 0x3cc5, 0x2bf9, 0x3cc9, 0x2c05, 0x3ccd, 0x2c10, 0x3cd1, - 0x2c1c, 0x3cd5, 0x2c28, 0x3cd9, 0x2c34, 0x3cdd, 0x2c40, 0x3ce0, - 0x2c4c, 0x3ce4, 0x2c58, 0x3ce8, 0x2c64, 0x3cec, 0x2c70, 0x3cf0, - 0x2c7c, 0x3cf4, 0x2c88, 0x3cf8, 0x2c94, 0x3cfb, 0x2ca0, 0x3cff, - 0x2cac, 0x3d03, 0x2cb8, 0x3d07, 0x2cc4, 0x3d0b, 0x2cd0, 0x3d0e, - 0x2cdc, 0x3d12, 0x2ce8, 0x3d16, 0x2cf4, 0x3d1a, 0x2d00, 0x3d1d, - 0x2d0c, 0x3d21, 0x2d18, 0x3d25, 0x2d24, 0x3d28, 0x2d30, 0x3d2c, - 0x2d3c, 0x3d30, 0x2d48, 0x3d34, 0x2d54, 0x3d37, 0x2d60, 0x3d3b, - 0x2d6c, 0x3d3f, 0x2d78, 0x3d42, 0x2d84, 0x3d46, 0x2d90, 0x3d49, - 0x2d9c, 0x3d4d, 0x2da8, 0x3d51, 0x2db4, 0x3d54, 0x2dc0, 0x3d58, - 0x2dcc, 0x3d5b, 0x2dd8, 0x3d5f, 0x2de4, 0x3d63, 0x2df0, 0x3d66, - 0x2dfc, 0x3d6a, 0x2e09, 0x3d6d, 0x2e15, 0x3d71, 0x2e21, 0x3d74, - 0x2e2d, 0x3d78, 0x2e39, 0x3d7b, 0x2e45, 0x3d7f, 0x2e51, 0x3d82, - 0x2e5d, 0x3d86, 0x2e69, 0x3d89, 0x2e75, 0x3d8d, 0x2e81, 0x3d90, - 0x2e8d, 0x3d93, 0x2e99, 0x3d97, 0x2ea6, 0x3d9a, 0x2eb2, 0x3d9e, - 0x2ebe, 0x3da1, 0x2eca, 0x3da4, 0x2ed6, 0x3da8, 0x2ee2, 0x3dab, - 0x2eee, 0x3daf, 0x2efa, 0x3db2, 0x2f06, 0x3db5, 0x2f13, 0x3db9, - 0x2f1f, 0x3dbc, 0x2f2b, 0x3dbf, 0x2f37, 0x3dc2, 0x2f43, 0x3dc6, - 0x2f4f, 0x3dc9, 0x2f5b, 0x3dcc, 0x2f67, 0x3dd0, 0x2f74, 0x3dd3, - 0x2f80, 0x3dd6, 0x2f8c, 0x3dd9, 0x2f98, 0x3ddd, 0x2fa4, 0x3de0, - 0x2fb0, 0x3de3, 0x2fbc, 0x3de6, 0x2fc9, 0x3de9, 0x2fd5, 0x3ded, - 0x2fe1, 0x3df0, 0x2fed, 0x3df3, 0x2ff9, 0x3df6, 0x3005, 0x3df9, - 0x3012, 0x3dfc, 0x301e, 0x3dff, 0x302a, 0x3e03, 0x3036, 0x3e06, - 0x3042, 0x3e09, 0x304e, 0x3e0c, 0x305b, 0x3e0f, 0x3067, 0x3e12, - 0x3073, 0x3e15, 0x307f, 0x3e18, 0x308b, 0x3e1b, 0x3098, 0x3e1e, - 0x30a4, 0x3e21, 0x30b0, 0x3e24, 0x30bc, 0x3e27, 0x30c8, 0x3e2a, - 0x30d5, 0x3e2d, 0x30e1, 0x3e30, 0x30ed, 0x3e33, 0x30f9, 0x3e36, - 0x3105, 0x3e39, 0x3112, 0x3e3c, 0x311e, 0x3e3f, 0x312a, 0x3e42, - 0x3136, 0x3e45, 0x3143, 0x3e48, 0x314f, 0x3e4a, 0x315b, 0x3e4d, - 0x3167, 0x3e50, 0x3174, 0x3e53, 0x3180, 0x3e56, 0x318c, 0x3e59, - 0x3198, 0x3e5c, 0x31a4, 0x3e5e, 0x31b1, 0x3e61, 0x31bd, 0x3e64, - 0x31c9, 0x3e67, 0x31d5, 0x3e6a, 0x31e2, 0x3e6c, 0x31ee, 0x3e6f, - 0x31fa, 0x3e72, 0x3207, 0x3e75, 0x3213, 0x3e77, 0x321f, 0x3e7a, - 0x322b, 0x3e7d, 0x3238, 0x3e80, 0x3244, 0x3e82, 0x3250, 0x3e85, - 0x325c, 0x3e88, 0x3269, 0x3e8a, 0x3275, 0x3e8d, 0x3281, 0x3e90, - 0x328e, 0x3e92, 0x329a, 0x3e95, 0x32a6, 0x3e98, 0x32b2, 0x3e9a, - 0x32bf, 0x3e9d, 0x32cb, 0x3e9f, 0x32d7, 0x3ea2, 0x32e4, 0x3ea5, - 0x32f0, 0x3ea7, 0x32fc, 0x3eaa, 0x3308, 0x3eac, 0x3315, 0x3eaf, - 0x3321, 0x3eb1, 0x332d, 0x3eb4, 0x333a, 0x3eb6, 0x3346, 0x3eb9, - 0x3352, 0x3ebb, 0x335f, 0x3ebe, 0x336b, 0x3ec0, 0x3377, 0x3ec3, - 0x3384, 0x3ec5, 0x3390, 0x3ec8, 0x339c, 0x3eca, 0x33a9, 0x3ecc, - 0x33b5, 0x3ecf, 0x33c1, 0x3ed1, 0x33ce, 0x3ed4, 0x33da, 0x3ed6, - 0x33e6, 0x3ed8, 0x33f3, 0x3edb, 0x33ff, 0x3edd, 0x340b, 0x3ee0, - 0x3418, 0x3ee2, 0x3424, 0x3ee4, 0x3430, 0x3ee7, 0x343d, 0x3ee9, - 0x3449, 0x3eeb, 0x3455, 0x3eed, 0x3462, 0x3ef0, 0x346e, 0x3ef2, - 0x347b, 0x3ef4, 0x3487, 0x3ef7, 0x3493, 0x3ef9, 0x34a0, 0x3efb, - 0x34ac, 0x3efd, 0x34b8, 0x3f00, 0x34c5, 0x3f02, 0x34d1, 0x3f04, - 0x34dd, 0x3f06, 0x34ea, 0x3f08, 0x34f6, 0x3f0a, 0x3503, 0x3f0d, - 0x350f, 0x3f0f, 0x351b, 0x3f11, 0x3528, 0x3f13, 0x3534, 0x3f15, - 0x3540, 0x3f17, 0x354d, 0x3f19, 0x3559, 0x3f1c, 0x3566, 0x3f1e, - 0x3572, 0x3f20, 0x357e, 0x3f22, 0x358b, 0x3f24, 0x3597, 0x3f26, - 0x35a4, 0x3f28, 0x35b0, 0x3f2a, 0x35bc, 0x3f2c, 0x35c9, 0x3f2e, - 0x35d5, 0x3f30, 0x35e2, 0x3f32, 0x35ee, 0x3f34, 0x35fa, 0x3f36, - 0x3607, 0x3f38, 0x3613, 0x3f3a, 0x3620, 0x3f3c, 0x362c, 0x3f3e, - 0x3639, 0x3f40, 0x3645, 0x3f42, 0x3651, 0x3f43, 0x365e, 0x3f45, - 0x366a, 0x3f47, 0x3677, 0x3f49, 0x3683, 0x3f4b, 0x3690, 0x3f4d, - 0x369c, 0x3f4f, 0x36a8, 0x3f51, 0x36b5, 0x3f52, 0x36c1, 0x3f54, - 0x36ce, 0x3f56, 0x36da, 0x3f58, 0x36e7, 0x3f5a, 0x36f3, 0x3f5b, - 0x36ff, 0x3f5d, 0x370c, 0x3f5f, 0x3718, 0x3f61, 0x3725, 0x3f62, - 0x3731, 0x3f64, 0x373e, 0x3f66, 0x374a, 0x3f68, 0x3757, 0x3f69, - 0x3763, 0x3f6b, 0x376f, 0x3f6d, 0x377c, 0x3f6e, 0x3788, 0x3f70, - 0x3795, 0x3f72, 0x37a1, 0x3f73, 0x37ae, 0x3f75, 0x37ba, 0x3f77, - 0x37c7, 0x3f78, 0x37d3, 0x3f7a, 0x37e0, 0x3f7b, 0x37ec, 0x3f7d, - 0x37f9, 0x3f7f, 0x3805, 0x3f80, 0x3811, 0x3f82, 0x381e, 0x3f83, - 0x382a, 0x3f85, 0x3837, 0x3f86, 0x3843, 0x3f88, 0x3850, 0x3f89, - 0x385c, 0x3f8b, 0x3869, 0x3f8c, 0x3875, 0x3f8e, 0x3882, 0x3f8f, - 0x388e, 0x3f91, 0x389b, 0x3f92, 0x38a7, 0x3f94, 0x38b4, 0x3f95, - 0x38c0, 0x3f97, 0x38cd, 0x3f98, 0x38d9, 0x3f99, 0x38e6, 0x3f9b, - 0x38f2, 0x3f9c, 0x38ff, 0x3f9e, 0x390b, 0x3f9f, 0x3918, 0x3fa0, - 0x3924, 0x3fa2, 0x3931, 0x3fa3, 0x393d, 0x3fa4, 0x394a, 0x3fa6, - 0x3956, 0x3fa7, 0x3963, 0x3fa8, 0x396f, 0x3faa, 0x397c, 0x3fab, - 0x3988, 0x3fac, 0x3995, 0x3fad, 0x39a1, 0x3faf, 0x39ae, 0x3fb0, - 0x39ba, 0x3fb1, 0x39c7, 0x3fb2, 0x39d3, 0x3fb4, 0x39e0, 0x3fb5, - 0x39ec, 0x3fb6, 0x39f9, 0x3fb7, 0x3a05, 0x3fb8, 0x3a12, 0x3fb9, - 0x3a1e, 0x3fbb, 0x3a2b, 0x3fbc, 0x3a37, 0x3fbd, 0x3a44, 0x3fbe, - 0x3a50, 0x3fbf, 0x3a5d, 0x3fc0, 0x3a69, 0x3fc1, 0x3a76, 0x3fc3, - 0x3a82, 0x3fc4, 0x3a8f, 0x3fc5, 0x3a9b, 0x3fc6, 0x3aa8, 0x3fc7, - 0x3ab4, 0x3fc8, 0x3ac1, 0x3fc9, 0x3acd, 0x3fca, 0x3ada, 0x3fcb, - 0x3ae6, 0x3fcc, 0x3af3, 0x3fcd, 0x3b00, 0x3fce, 0x3b0c, 0x3fcf, - 0x3b19, 0x3fd0, 0x3b25, 0x3fd1, 0x3b32, 0x3fd2, 0x3b3e, 0x3fd3, - 0x3b4b, 0x3fd4, 0x3b57, 0x3fd5, 0x3b64, 0x3fd5, 0x3b70, 0x3fd6, - 0x3b7d, 0x3fd7, 0x3b89, 0x3fd8, 0x3b96, 0x3fd9, 0x3ba2, 0x3fda, - 0x3baf, 0x3fdb, 0x3bbc, 0x3fdc, 0x3bc8, 0x3fdc, 0x3bd5, 0x3fdd, - 0x3be1, 0x3fde, 0x3bee, 0x3fdf, 0x3bfa, 0x3fe0, 0x3c07, 0x3fe0, - 0x3c13, 0x3fe1, 0x3c20, 0x3fe2, 0x3c2c, 0x3fe3, 0x3c39, 0x3fe3, - 0x3c45, 0x3fe4, 0x3c52, 0x3fe5, 0x3c5f, 0x3fe6, 0x3c6b, 0x3fe6, - 0x3c78, 0x3fe7, 0x3c84, 0x3fe8, 0x3c91, 0x3fe8, 0x3c9d, 0x3fe9, - 0x3caa, 0x3fea, 0x3cb6, 0x3fea, 0x3cc3, 0x3feb, 0x3cd0, 0x3fec, - 0x3cdc, 0x3fec, 0x3ce9, 0x3fed, 0x3cf5, 0x3fed, 0x3d02, 0x3fee, - 0x3d0e, 0x3fef, 0x3d1b, 0x3fef, 0x3d27, 0x3ff0, 0x3d34, 0x3ff0, - 0x3d40, 0x3ff1, 0x3d4d, 0x3ff1, 0x3d5a, 0x3ff2, 0x3d66, 0x3ff2, - 0x3d73, 0x3ff3, 0x3d7f, 0x3ff3, 0x3d8c, 0x3ff4, 0x3d98, 0x3ff4, - 0x3da5, 0x3ff5, 0x3db2, 0x3ff5, 0x3dbe, 0x3ff6, 0x3dcb, 0x3ff6, - 0x3dd7, 0x3ff7, 0x3de4, 0x3ff7, 0x3df0, 0x3ff7, 0x3dfd, 0x3ff8, - 0x3e09, 0x3ff8, 0x3e16, 0x3ff9, 0x3e23, 0x3ff9, 0x3e2f, 0x3ff9, - 0x3e3c, 0x3ffa, 0x3e48, 0x3ffa, 0x3e55, 0x3ffa, 0x3e61, 0x3ffb, - 0x3e6e, 0x3ffb, 0x3e7a, 0x3ffb, 0x3e87, 0x3ffc, 0x3e94, 0x3ffc, - 0x3ea0, 0x3ffc, 0x3ead, 0x3ffc, 0x3eb9, 0x3ffd, 0x3ec6, 0x3ffd, - 0x3ed2, 0x3ffd, 0x3edf, 0x3ffd, 0x3eec, 0x3ffe, 0x3ef8, 0x3ffe, - 0x3f05, 0x3ffe, 0x3f11, 0x3ffe, 0x3f1e, 0x3ffe, 0x3f2a, 0x3fff, - 0x3f37, 0x3fff, 0x3f44, 0x3fff, 0x3f50, 0x3fff, 0x3f5d, 0x3fff, - 0x3f69, 0x3fff, 0x3f76, 0x3fff, 0x3f82, 0x4000, 0x3f8f, 0x4000, - 0x3f9b, 0x4000, 0x3fa8, 0x4000, 0x3fb5, 0x4000, 0x3fc1, 0x4000, - 0x3fce, 0x4000, 0x3fda, 0x4000, 0x3fe7, 0x4000, 0x3ff3, 0x4000, -}; - -/** -* \par -* Generation of real_CoefB array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-*  {    
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-*  } 
-* \par -* Convert to fixed point Q15 format -* round(pBTable[i] * pow(2, 15)) -* -*/ - -static const q15_t ALIGN4 realCoefBQ15[8192] = { - 0x4000, 0x4000, 0x400d, 0x4000, 0x4019, 0x4000, 0x4026, 0x4000, - 0x4032, 0x4000, 0x403f, 0x4000, 0x404b, 0x4000, 0x4058, 0x4000, - 0x4065, 0x4000, 0x4071, 0x4000, 0x407e, 0x4000, 0x408a, 0x3fff, - 0x4097, 0x3fff, 0x40a3, 0x3fff, 0x40b0, 0x3fff, 0x40bc, 0x3fff, - 0x40c9, 0x3fff, 0x40d6, 0x3fff, 0x40e2, 0x3ffe, 0x40ef, 0x3ffe, - 0x40fb, 0x3ffe, 0x4108, 0x3ffe, 0x4114, 0x3ffe, 0x4121, 0x3ffd, - 0x412e, 0x3ffd, 0x413a, 0x3ffd, 0x4147, 0x3ffd, 0x4153, 0x3ffc, - 0x4160, 0x3ffc, 0x416c, 0x3ffc, 0x4179, 0x3ffc, 0x4186, 0x3ffb, - 0x4192, 0x3ffb, 0x419f, 0x3ffb, 0x41ab, 0x3ffa, 0x41b8, 0x3ffa, - 0x41c4, 0x3ffa, 0x41d1, 0x3ff9, 0x41dd, 0x3ff9, 0x41ea, 0x3ff9, - 0x41f7, 0x3ff8, 0x4203, 0x3ff8, 0x4210, 0x3ff7, 0x421c, 0x3ff7, - 0x4229, 0x3ff7, 0x4235, 0x3ff6, 0x4242, 0x3ff6, 0x424e, 0x3ff5, - 0x425b, 0x3ff5, 0x4268, 0x3ff4, 0x4274, 0x3ff4, 0x4281, 0x3ff3, - 0x428d, 0x3ff3, 0x429a, 0x3ff2, 0x42a6, 0x3ff2, 0x42b3, 0x3ff1, - 0x42c0, 0x3ff1, 0x42cc, 0x3ff0, 0x42d9, 0x3ff0, 0x42e5, 0x3fef, - 0x42f2, 0x3fef, 0x42fe, 0x3fee, 0x430b, 0x3fed, 0x4317, 0x3fed, - 0x4324, 0x3fec, 0x4330, 0x3fec, 0x433d, 0x3feb, 0x434a, 0x3fea, - 0x4356, 0x3fea, 0x4363, 0x3fe9, 0x436f, 0x3fe8, 0x437c, 0x3fe8, - 0x4388, 0x3fe7, 0x4395, 0x3fe6, 0x43a1, 0x3fe6, 0x43ae, 0x3fe5, - 0x43bb, 0x3fe4, 0x43c7, 0x3fe3, 0x43d4, 0x3fe3, 0x43e0, 0x3fe2, - 0x43ed, 0x3fe1, 0x43f9, 0x3fe0, 0x4406, 0x3fe0, 0x4412, 0x3fdf, - 0x441f, 0x3fde, 0x442b, 0x3fdd, 0x4438, 0x3fdc, 0x4444, 0x3fdc, - 0x4451, 0x3fdb, 0x445e, 0x3fda, 0x446a, 0x3fd9, 0x4477, 0x3fd8, - 0x4483, 0x3fd7, 0x4490, 0x3fd6, 0x449c, 0x3fd5, 0x44a9, 0x3fd5, - 0x44b5, 0x3fd4, 0x44c2, 0x3fd3, 0x44ce, 0x3fd2, 0x44db, 0x3fd1, - 0x44e7, 0x3fd0, 0x44f4, 0x3fcf, 0x4500, 0x3fce, 0x450d, 0x3fcd, - 0x451a, 0x3fcc, 0x4526, 0x3fcb, 0x4533, 0x3fca, 0x453f, 0x3fc9, - 0x454c, 0x3fc8, 0x4558, 0x3fc7, 0x4565, 0x3fc6, 0x4571, 0x3fc5, - 0x457e, 0x3fc4, 0x458a, 0x3fc3, 0x4597, 0x3fc1, 0x45a3, 0x3fc0, - 0x45b0, 0x3fbf, 0x45bc, 0x3fbe, 0x45c9, 0x3fbd, 0x45d5, 0x3fbc, - 0x45e2, 0x3fbb, 0x45ee, 0x3fb9, 0x45fb, 0x3fb8, 0x4607, 0x3fb7, - 0x4614, 0x3fb6, 0x4620, 0x3fb5, 0x462d, 0x3fb4, 0x4639, 0x3fb2, - 0x4646, 0x3fb1, 0x4652, 0x3fb0, 0x465f, 0x3faf, 0x466b, 0x3fad, - 0x4678, 0x3fac, 0x4684, 0x3fab, 0x4691, 0x3faa, 0x469d, 0x3fa8, - 0x46aa, 0x3fa7, 0x46b6, 0x3fa6, 0x46c3, 0x3fa4, 0x46cf, 0x3fa3, - 0x46dc, 0x3fa2, 0x46e8, 0x3fa0, 0x46f5, 0x3f9f, 0x4701, 0x3f9e, - 0x470e, 0x3f9c, 0x471a, 0x3f9b, 0x4727, 0x3f99, 0x4733, 0x3f98, - 0x4740, 0x3f97, 0x474c, 0x3f95, 0x4759, 0x3f94, 0x4765, 0x3f92, - 0x4772, 0x3f91, 0x477e, 0x3f8f, 0x478b, 0x3f8e, 0x4797, 0x3f8c, - 0x47a4, 0x3f8b, 0x47b0, 0x3f89, 0x47bd, 0x3f88, 0x47c9, 0x3f86, - 0x47d6, 0x3f85, 0x47e2, 0x3f83, 0x47ef, 0x3f82, 0x47fb, 0x3f80, - 0x4807, 0x3f7f, 0x4814, 0x3f7d, 0x4820, 0x3f7b, 0x482d, 0x3f7a, - 0x4839, 0x3f78, 0x4846, 0x3f77, 0x4852, 0x3f75, 0x485f, 0x3f73, - 0x486b, 0x3f72, 0x4878, 0x3f70, 0x4884, 0x3f6e, 0x4891, 0x3f6d, - 0x489d, 0x3f6b, 0x48a9, 0x3f69, 0x48b6, 0x3f68, 0x48c2, 0x3f66, - 0x48cf, 0x3f64, 0x48db, 0x3f62, 0x48e8, 0x3f61, 0x48f4, 0x3f5f, - 0x4901, 0x3f5d, 0x490d, 0x3f5b, 0x4919, 0x3f5a, 0x4926, 0x3f58, - 0x4932, 0x3f56, 0x493f, 0x3f54, 0x494b, 0x3f52, 0x4958, 0x3f51, - 0x4964, 0x3f4f, 0x4970, 0x3f4d, 0x497d, 0x3f4b, 0x4989, 0x3f49, - 0x4996, 0x3f47, 0x49a2, 0x3f45, 0x49af, 0x3f43, 0x49bb, 0x3f42, - 0x49c7, 0x3f40, 0x49d4, 0x3f3e, 0x49e0, 0x3f3c, 0x49ed, 0x3f3a, - 0x49f9, 0x3f38, 0x4a06, 0x3f36, 0x4a12, 0x3f34, 0x4a1e, 0x3f32, - 0x4a2b, 0x3f30, 0x4a37, 0x3f2e, 0x4a44, 0x3f2c, 0x4a50, 0x3f2a, - 0x4a5c, 0x3f28, 0x4a69, 0x3f26, 0x4a75, 0x3f24, 0x4a82, 0x3f22, - 0x4a8e, 0x3f20, 0x4a9a, 0x3f1e, 0x4aa7, 0x3f1c, 0x4ab3, 0x3f19, - 0x4ac0, 0x3f17, 0x4acc, 0x3f15, 0x4ad8, 0x3f13, 0x4ae5, 0x3f11, - 0x4af1, 0x3f0f, 0x4afd, 0x3f0d, 0x4b0a, 0x3f0a, 0x4b16, 0x3f08, - 0x4b23, 0x3f06, 0x4b2f, 0x3f04, 0x4b3b, 0x3f02, 0x4b48, 0x3f00, - 0x4b54, 0x3efd, 0x4b60, 0x3efb, 0x4b6d, 0x3ef9, 0x4b79, 0x3ef7, - 0x4b85, 0x3ef4, 0x4b92, 0x3ef2, 0x4b9e, 0x3ef0, 0x4bab, 0x3eed, - 0x4bb7, 0x3eeb, 0x4bc3, 0x3ee9, 0x4bd0, 0x3ee7, 0x4bdc, 0x3ee4, - 0x4be8, 0x3ee2, 0x4bf5, 0x3ee0, 0x4c01, 0x3edd, 0x4c0d, 0x3edb, - 0x4c1a, 0x3ed8, 0x4c26, 0x3ed6, 0x4c32, 0x3ed4, 0x4c3f, 0x3ed1, - 0x4c4b, 0x3ecf, 0x4c57, 0x3ecc, 0x4c64, 0x3eca, 0x4c70, 0x3ec8, - 0x4c7c, 0x3ec5, 0x4c89, 0x3ec3, 0x4c95, 0x3ec0, 0x4ca1, 0x3ebe, - 0x4cae, 0x3ebb, 0x4cba, 0x3eb9, 0x4cc6, 0x3eb6, 0x4cd3, 0x3eb4, - 0x4cdf, 0x3eb1, 0x4ceb, 0x3eaf, 0x4cf8, 0x3eac, 0x4d04, 0x3eaa, - 0x4d10, 0x3ea7, 0x4d1c, 0x3ea5, 0x4d29, 0x3ea2, 0x4d35, 0x3e9f, - 0x4d41, 0x3e9d, 0x4d4e, 0x3e9a, 0x4d5a, 0x3e98, 0x4d66, 0x3e95, - 0x4d72, 0x3e92, 0x4d7f, 0x3e90, 0x4d8b, 0x3e8d, 0x4d97, 0x3e8a, - 0x4da4, 0x3e88, 0x4db0, 0x3e85, 0x4dbc, 0x3e82, 0x4dc8, 0x3e80, - 0x4dd5, 0x3e7d, 0x4de1, 0x3e7a, 0x4ded, 0x3e77, 0x4df9, 0x3e75, - 0x4e06, 0x3e72, 0x4e12, 0x3e6f, 0x4e1e, 0x3e6c, 0x4e2b, 0x3e6a, - 0x4e37, 0x3e67, 0x4e43, 0x3e64, 0x4e4f, 0x3e61, 0x4e5c, 0x3e5e, - 0x4e68, 0x3e5c, 0x4e74, 0x3e59, 0x4e80, 0x3e56, 0x4e8c, 0x3e53, - 0x4e99, 0x3e50, 0x4ea5, 0x3e4d, 0x4eb1, 0x3e4a, 0x4ebd, 0x3e48, - 0x4eca, 0x3e45, 0x4ed6, 0x3e42, 0x4ee2, 0x3e3f, 0x4eee, 0x3e3c, - 0x4efb, 0x3e39, 0x4f07, 0x3e36, 0x4f13, 0x3e33, 0x4f1f, 0x3e30, - 0x4f2b, 0x3e2d, 0x4f38, 0x3e2a, 0x4f44, 0x3e27, 0x4f50, 0x3e24, - 0x4f5c, 0x3e21, 0x4f68, 0x3e1e, 0x4f75, 0x3e1b, 0x4f81, 0x3e18, - 0x4f8d, 0x3e15, 0x4f99, 0x3e12, 0x4fa5, 0x3e0f, 0x4fb2, 0x3e0c, - 0x4fbe, 0x3e09, 0x4fca, 0x3e06, 0x4fd6, 0x3e03, 0x4fe2, 0x3dff, - 0x4fee, 0x3dfc, 0x4ffb, 0x3df9, 0x5007, 0x3df6, 0x5013, 0x3df3, - 0x501f, 0x3df0, 0x502b, 0x3ded, 0x5037, 0x3de9, 0x5044, 0x3de6, - 0x5050, 0x3de3, 0x505c, 0x3de0, 0x5068, 0x3ddd, 0x5074, 0x3dd9, - 0x5080, 0x3dd6, 0x508c, 0x3dd3, 0x5099, 0x3dd0, 0x50a5, 0x3dcc, - 0x50b1, 0x3dc9, 0x50bd, 0x3dc6, 0x50c9, 0x3dc2, 0x50d5, 0x3dbf, - 0x50e1, 0x3dbc, 0x50ed, 0x3db9, 0x50fa, 0x3db5, 0x5106, 0x3db2, - 0x5112, 0x3daf, 0x511e, 0x3dab, 0x512a, 0x3da8, 0x5136, 0x3da4, - 0x5142, 0x3da1, 0x514e, 0x3d9e, 0x515a, 0x3d9a, 0x5167, 0x3d97, - 0x5173, 0x3d93, 0x517f, 0x3d90, 0x518b, 0x3d8d, 0x5197, 0x3d89, - 0x51a3, 0x3d86, 0x51af, 0x3d82, 0x51bb, 0x3d7f, 0x51c7, 0x3d7b, - 0x51d3, 0x3d78, 0x51df, 0x3d74, 0x51eb, 0x3d71, 0x51f7, 0x3d6d, - 0x5204, 0x3d6a, 0x5210, 0x3d66, 0x521c, 0x3d63, 0x5228, 0x3d5f, - 0x5234, 0x3d5b, 0x5240, 0x3d58, 0x524c, 0x3d54, 0x5258, 0x3d51, - 0x5264, 0x3d4d, 0x5270, 0x3d49, 0x527c, 0x3d46, 0x5288, 0x3d42, - 0x5294, 0x3d3f, 0x52a0, 0x3d3b, 0x52ac, 0x3d37, 0x52b8, 0x3d34, - 0x52c4, 0x3d30, 0x52d0, 0x3d2c, 0x52dc, 0x3d28, 0x52e8, 0x3d25, - 0x52f4, 0x3d21, 0x5300, 0x3d1d, 0x530c, 0x3d1a, 0x5318, 0x3d16, - 0x5324, 0x3d12, 0x5330, 0x3d0e, 0x533c, 0x3d0b, 0x5348, 0x3d07, - 0x5354, 0x3d03, 0x5360, 0x3cff, 0x536c, 0x3cfb, 0x5378, 0x3cf8, - 0x5384, 0x3cf4, 0x5390, 0x3cf0, 0x539c, 0x3cec, 0x53a8, 0x3ce8, - 0x53b4, 0x3ce4, 0x53c0, 0x3ce0, 0x53cc, 0x3cdd, 0x53d8, 0x3cd9, - 0x53e4, 0x3cd5, 0x53f0, 0x3cd1, 0x53fb, 0x3ccd, 0x5407, 0x3cc9, - 0x5413, 0x3cc5, 0x541f, 0x3cc1, 0x542b, 0x3cbd, 0x5437, 0x3cb9, - 0x5443, 0x3cb5, 0x544f, 0x3cb1, 0x545b, 0x3cad, 0x5467, 0x3ca9, - 0x5473, 0x3ca5, 0x547f, 0x3ca1, 0x548b, 0x3c9d, 0x5496, 0x3c99, - 0x54a2, 0x3c95, 0x54ae, 0x3c91, 0x54ba, 0x3c8d, 0x54c6, 0x3c89, - 0x54d2, 0x3c85, 0x54de, 0x3c81, 0x54ea, 0x3c7d, 0x54f6, 0x3c79, - 0x5501, 0x3c74, 0x550d, 0x3c70, 0x5519, 0x3c6c, 0x5525, 0x3c68, - 0x5531, 0x3c64, 0x553d, 0x3c60, 0x5549, 0x3c5b, 0x5554, 0x3c57, - 0x5560, 0x3c53, 0x556c, 0x3c4f, 0x5578, 0x3c4b, 0x5584, 0x3c46, - 0x5590, 0x3c42, 0x559b, 0x3c3e, 0x55a7, 0x3c3a, 0x55b3, 0x3c36, - 0x55bf, 0x3c31, 0x55cb, 0x3c2d, 0x55d7, 0x3c29, 0x55e2, 0x3c24, - 0x55ee, 0x3c20, 0x55fa, 0x3c1c, 0x5606, 0x3c17, 0x5612, 0x3c13, - 0x561d, 0x3c0f, 0x5629, 0x3c0a, 0x5635, 0x3c06, 0x5641, 0x3c02, - 0x564c, 0x3bfd, 0x5658, 0x3bf9, 0x5664, 0x3bf5, 0x5670, 0x3bf0, - 0x567c, 0x3bec, 0x5687, 0x3be7, 0x5693, 0x3be3, 0x569f, 0x3bde, - 0x56ab, 0x3bda, 0x56b6, 0x3bd6, 0x56c2, 0x3bd1, 0x56ce, 0x3bcd, - 0x56da, 0x3bc8, 0x56e5, 0x3bc4, 0x56f1, 0x3bbf, 0x56fd, 0x3bbb, - 0x5709, 0x3bb6, 0x5714, 0x3bb2, 0x5720, 0x3bad, 0x572c, 0x3ba9, - 0x5737, 0x3ba4, 0x5743, 0x3b9f, 0x574f, 0x3b9b, 0x575b, 0x3b96, - 0x5766, 0x3b92, 0x5772, 0x3b8d, 0x577e, 0x3b88, 0x5789, 0x3b84, - 0x5795, 0x3b7f, 0x57a1, 0x3b7b, 0x57ac, 0x3b76, 0x57b8, 0x3b71, - 0x57c4, 0x3b6d, 0x57cf, 0x3b68, 0x57db, 0x3b63, 0x57e7, 0x3b5f, - 0x57f2, 0x3b5a, 0x57fe, 0x3b55, 0x580a, 0x3b50, 0x5815, 0x3b4c, - 0x5821, 0x3b47, 0x582d, 0x3b42, 0x5838, 0x3b3e, 0x5844, 0x3b39, - 0x584f, 0x3b34, 0x585b, 0x3b2f, 0x5867, 0x3b2a, 0x5872, 0x3b26, - 0x587e, 0x3b21, 0x5889, 0x3b1c, 0x5895, 0x3b17, 0x58a1, 0x3b12, - 0x58ac, 0x3b0e, 0x58b8, 0x3b09, 0x58c3, 0x3b04, 0x58cf, 0x3aff, - 0x58db, 0x3afa, 0x58e6, 0x3af5, 0x58f2, 0x3af0, 0x58fd, 0x3aeb, - 0x5909, 0x3ae6, 0x5914, 0x3ae2, 0x5920, 0x3add, 0x592c, 0x3ad8, - 0x5937, 0x3ad3, 0x5943, 0x3ace, 0x594e, 0x3ac9, 0x595a, 0x3ac4, - 0x5965, 0x3abf, 0x5971, 0x3aba, 0x597c, 0x3ab5, 0x5988, 0x3ab0, - 0x5993, 0x3aab, 0x599f, 0x3aa6, 0x59aa, 0x3aa1, 0x59b6, 0x3a9c, - 0x59c1, 0x3a97, 0x59cd, 0x3a92, 0x59d8, 0x3a8d, 0x59e4, 0x3a88, - 0x59ef, 0x3a82, 0x59fb, 0x3a7d, 0x5a06, 0x3a78, 0x5a12, 0x3a73, - 0x5a1d, 0x3a6e, 0x5a29, 0x3a69, 0x5a34, 0x3a64, 0x5a40, 0x3a5f, - 0x5a4b, 0x3a59, 0x5a57, 0x3a54, 0x5a62, 0x3a4f, 0x5a6e, 0x3a4a, - 0x5a79, 0x3a45, 0x5a84, 0x3a3f, 0x5a90, 0x3a3a, 0x5a9b, 0x3a35, - 0x5aa7, 0x3a30, 0x5ab2, 0x3a2b, 0x5abe, 0x3a25, 0x5ac9, 0x3a20, - 0x5ad4, 0x3a1b, 0x5ae0, 0x3a16, 0x5aeb, 0x3a10, 0x5af7, 0x3a0b, - 0x5b02, 0x3a06, 0x5b0d, 0x3a00, 0x5b19, 0x39fb, 0x5b24, 0x39f6, - 0x5b30, 0x39f0, 0x5b3b, 0x39eb, 0x5b46, 0x39e6, 0x5b52, 0x39e0, - 0x5b5d, 0x39db, 0x5b68, 0x39d6, 0x5b74, 0x39d0, 0x5b7f, 0x39cb, - 0x5b8a, 0x39c5, 0x5b96, 0x39c0, 0x5ba1, 0x39bb, 0x5bac, 0x39b5, - 0x5bb8, 0x39b0, 0x5bc3, 0x39aa, 0x5bce, 0x39a5, 0x5bda, 0x399f, - 0x5be5, 0x399a, 0x5bf0, 0x3994, 0x5bfc, 0x398f, 0x5c07, 0x3989, - 0x5c12, 0x3984, 0x5c1e, 0x397e, 0x5c29, 0x3979, 0x5c34, 0x3973, - 0x5c3f, 0x396e, 0x5c4b, 0x3968, 0x5c56, 0x3963, 0x5c61, 0x395d, - 0x5c6c, 0x3958, 0x5c78, 0x3952, 0x5c83, 0x394c, 0x5c8e, 0x3947, - 0x5c99, 0x3941, 0x5ca5, 0x393b, 0x5cb0, 0x3936, 0x5cbb, 0x3930, - 0x5cc6, 0x392b, 0x5cd2, 0x3925, 0x5cdd, 0x391f, 0x5ce8, 0x391a, - 0x5cf3, 0x3914, 0x5cff, 0x390e, 0x5d0a, 0x3909, 0x5d15, 0x3903, - 0x5d20, 0x38fd, 0x5d2b, 0x38f7, 0x5d36, 0x38f2, 0x5d42, 0x38ec, - 0x5d4d, 0x38e6, 0x5d58, 0x38e0, 0x5d63, 0x38db, 0x5d6e, 0x38d5, - 0x5d79, 0x38cf, 0x5d85, 0x38c9, 0x5d90, 0x38c3, 0x5d9b, 0x38be, - 0x5da6, 0x38b8, 0x5db1, 0x38b2, 0x5dbc, 0x38ac, 0x5dc7, 0x38a6, - 0x5dd3, 0x38a1, 0x5dde, 0x389b, 0x5de9, 0x3895, 0x5df4, 0x388f, - 0x5dff, 0x3889, 0x5e0a, 0x3883, 0x5e15, 0x387d, 0x5e20, 0x3877, - 0x5e2b, 0x3871, 0x5e36, 0x386b, 0x5e42, 0x3866, 0x5e4d, 0x3860, - 0x5e58, 0x385a, 0x5e63, 0x3854, 0x5e6e, 0x384e, 0x5e79, 0x3848, - 0x5e84, 0x3842, 0x5e8f, 0x383c, 0x5e9a, 0x3836, 0x5ea5, 0x3830, - 0x5eb0, 0x382a, 0x5ebb, 0x3824, 0x5ec6, 0x381e, 0x5ed1, 0x3818, - 0x5edc, 0x3812, 0x5ee7, 0x380b, 0x5ef2, 0x3805, 0x5efd, 0x37ff, - 0x5f08, 0x37f9, 0x5f13, 0x37f3, 0x5f1e, 0x37ed, 0x5f29, 0x37e7, - 0x5f34, 0x37e1, 0x5f3f, 0x37db, 0x5f4a, 0x37d5, 0x5f55, 0x37ce, - 0x5f60, 0x37c8, 0x5f6b, 0x37c2, 0x5f76, 0x37bc, 0x5f81, 0x37b6, - 0x5f8c, 0x37b0, 0x5f97, 0x37a9, 0x5fa2, 0x37a3, 0x5fac, 0x379d, - 0x5fb7, 0x3797, 0x5fc2, 0x3790, 0x5fcd, 0x378a, 0x5fd8, 0x3784, - 0x5fe3, 0x377e, 0x5fee, 0x3777, 0x5ff9, 0x3771, 0x6004, 0x376b, - 0x600f, 0x3765, 0x6019, 0x375e, 0x6024, 0x3758, 0x602f, 0x3752, - 0x603a, 0x374b, 0x6045, 0x3745, 0x6050, 0x373f, 0x605b, 0x3738, - 0x6065, 0x3732, 0x6070, 0x372c, 0x607b, 0x3725, 0x6086, 0x371f, - 0x6091, 0x3718, 0x609b, 0x3712, 0x60a6, 0x370c, 0x60b1, 0x3705, - 0x60bc, 0x36ff, 0x60c7, 0x36f8, 0x60d1, 0x36f2, 0x60dc, 0x36eb, - 0x60e7, 0x36e5, 0x60f2, 0x36df, 0x60fd, 0x36d8, 0x6107, 0x36d2, - 0x6112, 0x36cb, 0x611d, 0x36c5, 0x6128, 0x36be, 0x6132, 0x36b8, - 0x613d, 0x36b1, 0x6148, 0x36ab, 0x6153, 0x36a4, 0x615d, 0x369d, - 0x6168, 0x3697, 0x6173, 0x3690, 0x617d, 0x368a, 0x6188, 0x3683, - 0x6193, 0x367d, 0x619e, 0x3676, 0x61a8, 0x366f, 0x61b3, 0x3669, - 0x61be, 0x3662, 0x61c8, 0x365c, 0x61d3, 0x3655, 0x61de, 0x364e, - 0x61e8, 0x3648, 0x61f3, 0x3641, 0x61fe, 0x363a, 0x6208, 0x3634, - 0x6213, 0x362d, 0x621e, 0x3626, 0x6228, 0x3620, 0x6233, 0x3619, - 0x623d, 0x3612, 0x6248, 0x360b, 0x6253, 0x3605, 0x625d, 0x35fe, - 0x6268, 0x35f7, 0x6272, 0x35f0, 0x627d, 0x35ea, 0x6288, 0x35e3, - 0x6292, 0x35dc, 0x629d, 0x35d5, 0x62a7, 0x35ce, 0x62b2, 0x35c8, - 0x62bc, 0x35c1, 0x62c7, 0x35ba, 0x62d2, 0x35b3, 0x62dc, 0x35ac, - 0x62e7, 0x35a5, 0x62f1, 0x359f, 0x62fc, 0x3598, 0x6306, 0x3591, - 0x6311, 0x358a, 0x631b, 0x3583, 0x6326, 0x357c, 0x6330, 0x3575, - 0x633b, 0x356e, 0x6345, 0x3567, 0x6350, 0x3561, 0x635a, 0x355a, - 0x6365, 0x3553, 0x636f, 0x354c, 0x637a, 0x3545, 0x6384, 0x353e, - 0x638e, 0x3537, 0x6399, 0x3530, 0x63a3, 0x3529, 0x63ae, 0x3522, - 0x63b8, 0x351b, 0x63c3, 0x3514, 0x63cd, 0x350d, 0x63d7, 0x3506, - 0x63e2, 0x34ff, 0x63ec, 0x34f8, 0x63f7, 0x34f1, 0x6401, 0x34ea, - 0x640b, 0x34e2, 0x6416, 0x34db, 0x6420, 0x34d4, 0x642b, 0x34cd, - 0x6435, 0x34c6, 0x643f, 0x34bf, 0x644a, 0x34b8, 0x6454, 0x34b1, - 0x645e, 0x34aa, 0x6469, 0x34a2, 0x6473, 0x349b, 0x647d, 0x3494, - 0x6488, 0x348d, 0x6492, 0x3486, 0x649c, 0x347f, 0x64a7, 0x3477, - 0x64b1, 0x3470, 0x64bb, 0x3469, 0x64c5, 0x3462, 0x64d0, 0x345b, - 0x64da, 0x3453, 0x64e4, 0x344c, 0x64ef, 0x3445, 0x64f9, 0x343e, - 0x6503, 0x3436, 0x650d, 0x342f, 0x6518, 0x3428, 0x6522, 0x3420, - 0x652c, 0x3419, 0x6536, 0x3412, 0x6541, 0x340b, 0x654b, 0x3403, - 0x6555, 0x33fc, 0x655f, 0x33f5, 0x6569, 0x33ed, 0x6574, 0x33e6, - 0x657e, 0x33df, 0x6588, 0x33d7, 0x6592, 0x33d0, 0x659c, 0x33c8, - 0x65a6, 0x33c1, 0x65b1, 0x33ba, 0x65bb, 0x33b2, 0x65c5, 0x33ab, - 0x65cf, 0x33a3, 0x65d9, 0x339c, 0x65e3, 0x3395, 0x65ed, 0x338d, - 0x65f8, 0x3386, 0x6602, 0x337e, 0x660c, 0x3377, 0x6616, 0x336f, - 0x6620, 0x3368, 0x662a, 0x3360, 0x6634, 0x3359, 0x663e, 0x3351, - 0x6648, 0x334a, 0x6652, 0x3342, 0x665c, 0x333b, 0x6666, 0x3333, - 0x6671, 0x332c, 0x667b, 0x3324, 0x6685, 0x331d, 0x668f, 0x3315, - 0x6699, 0x330d, 0x66a3, 0x3306, 0x66ad, 0x32fe, 0x66b7, 0x32f7, - 0x66c1, 0x32ef, 0x66cb, 0x32e7, 0x66d5, 0x32e0, 0x66df, 0x32d8, - 0x66e9, 0x32d0, 0x66f3, 0x32c9, 0x66fd, 0x32c1, 0x6707, 0x32ba, - 0x6711, 0x32b2, 0x671a, 0x32aa, 0x6724, 0x32a3, 0x672e, 0x329b, - 0x6738, 0x3293, 0x6742, 0x328b, 0x674c, 0x3284, 0x6756, 0x327c, - 0x6760, 0x3274, 0x676a, 0x326d, 0x6774, 0x3265, 0x677e, 0x325d, - 0x6788, 0x3255, 0x6791, 0x324e, 0x679b, 0x3246, 0x67a5, 0x323e, - 0x67af, 0x3236, 0x67b9, 0x322e, 0x67c3, 0x3227, 0x67cd, 0x321f, - 0x67d6, 0x3217, 0x67e0, 0x320f, 0x67ea, 0x3207, 0x67f4, 0x31ff, - 0x67fe, 0x31f8, 0x6808, 0x31f0, 0x6811, 0x31e8, 0x681b, 0x31e0, - 0x6825, 0x31d8, 0x682f, 0x31d0, 0x6838, 0x31c8, 0x6842, 0x31c0, - 0x684c, 0x31b9, 0x6856, 0x31b1, 0x6860, 0x31a9, 0x6869, 0x31a1, - 0x6873, 0x3199, 0x687d, 0x3191, 0x6886, 0x3189, 0x6890, 0x3181, - 0x689a, 0x3179, 0x68a4, 0x3171, 0x68ad, 0x3169, 0x68b7, 0x3161, - 0x68c1, 0x3159, 0x68ca, 0x3151, 0x68d4, 0x3149, 0x68de, 0x3141, - 0x68e7, 0x3139, 0x68f1, 0x3131, 0x68fb, 0x3129, 0x6904, 0x3121, - 0x690e, 0x3119, 0x6918, 0x3111, 0x6921, 0x3109, 0x692b, 0x3101, - 0x6935, 0x30f9, 0x693e, 0x30f0, 0x6948, 0x30e8, 0x6951, 0x30e0, - 0x695b, 0x30d8, 0x6965, 0x30d0, 0x696e, 0x30c8, 0x6978, 0x30c0, - 0x6981, 0x30b8, 0x698b, 0x30af, 0x6994, 0x30a7, 0x699e, 0x309f, - 0x69a7, 0x3097, 0x69b1, 0x308f, 0x69bb, 0x3087, 0x69c4, 0x307e, - 0x69ce, 0x3076, 0x69d7, 0x306e, 0x69e1, 0x3066, 0x69ea, 0x305d, - 0x69f4, 0x3055, 0x69fd, 0x304d, 0x6a07, 0x3045, 0x6a10, 0x303c, - 0x6a1a, 0x3034, 0x6a23, 0x302c, 0x6a2c, 0x3024, 0x6a36, 0x301b, - 0x6a3f, 0x3013, 0x6a49, 0x300b, 0x6a52, 0x3002, 0x6a5c, 0x2ffa, - 0x6a65, 0x2ff2, 0x6a6e, 0x2fea, 0x6a78, 0x2fe1, 0x6a81, 0x2fd9, - 0x6a8b, 0x2fd0, 0x6a94, 0x2fc8, 0x6a9d, 0x2fc0, 0x6aa7, 0x2fb7, - 0x6ab0, 0x2faf, 0x6ab9, 0x2fa7, 0x6ac3, 0x2f9e, 0x6acc, 0x2f96, - 0x6ad6, 0x2f8d, 0x6adf, 0x2f85, 0x6ae8, 0x2f7d, 0x6af2, 0x2f74, - 0x6afb, 0x2f6c, 0x6b04, 0x2f63, 0x6b0d, 0x2f5b, 0x6b17, 0x2f52, - 0x6b20, 0x2f4a, 0x6b29, 0x2f41, 0x6b33, 0x2f39, 0x6b3c, 0x2f30, - 0x6b45, 0x2f28, 0x6b4e, 0x2f20, 0x6b58, 0x2f17, 0x6b61, 0x2f0e, - 0x6b6a, 0x2f06, 0x6b73, 0x2efd, 0x6b7d, 0x2ef5, 0x6b86, 0x2eec, - 0x6b8f, 0x2ee4, 0x6b98, 0x2edb, 0x6ba1, 0x2ed3, 0x6bab, 0x2eca, - 0x6bb4, 0x2ec2, 0x6bbd, 0x2eb9, 0x6bc6, 0x2eb0, 0x6bcf, 0x2ea8, - 0x6bd8, 0x2e9f, 0x6be2, 0x2e97, 0x6beb, 0x2e8e, 0x6bf4, 0x2e85, - 0x6bfd, 0x2e7d, 0x6c06, 0x2e74, 0x6c0f, 0x2e6b, 0x6c18, 0x2e63, - 0x6c21, 0x2e5a, 0x6c2b, 0x2e51, 0x6c34, 0x2e49, 0x6c3d, 0x2e40, - 0x6c46, 0x2e37, 0x6c4f, 0x2e2f, 0x6c58, 0x2e26, 0x6c61, 0x2e1d, - 0x6c6a, 0x2e15, 0x6c73, 0x2e0c, 0x6c7c, 0x2e03, 0x6c85, 0x2dfa, - 0x6c8e, 0x2df2, 0x6c97, 0x2de9, 0x6ca0, 0x2de0, 0x6ca9, 0x2dd7, - 0x6cb2, 0x2dcf, 0x6cbb, 0x2dc6, 0x6cc4, 0x2dbd, 0x6ccd, 0x2db4, - 0x6cd6, 0x2dab, 0x6cdf, 0x2da3, 0x6ce8, 0x2d9a, 0x6cf1, 0x2d91, - 0x6cfa, 0x2d88, 0x6d03, 0x2d7f, 0x6d0c, 0x2d76, 0x6d15, 0x2d6e, - 0x6d1e, 0x2d65, 0x6d27, 0x2d5c, 0x6d2f, 0x2d53, 0x6d38, 0x2d4a, - 0x6d41, 0x2d41, 0x6d4a, 0x2d38, 0x6d53, 0x2d2f, 0x6d5c, 0x2d27, - 0x6d65, 0x2d1e, 0x6d6e, 0x2d15, 0x6d76, 0x2d0c, 0x6d7f, 0x2d03, - 0x6d88, 0x2cfa, 0x6d91, 0x2cf1, 0x6d9a, 0x2ce8, 0x6da3, 0x2cdf, - 0x6dab, 0x2cd6, 0x6db4, 0x2ccd, 0x6dbd, 0x2cc4, 0x6dc6, 0x2cbb, - 0x6dcf, 0x2cb2, 0x6dd7, 0x2ca9, 0x6de0, 0x2ca0, 0x6de9, 0x2c97, - 0x6df2, 0x2c8e, 0x6dfa, 0x2c85, 0x6e03, 0x2c7c, 0x6e0c, 0x2c73, - 0x6e15, 0x2c6a, 0x6e1d, 0x2c61, 0x6e26, 0x2c58, 0x6e2f, 0x2c4f, - 0x6e37, 0x2c46, 0x6e40, 0x2c3d, 0x6e49, 0x2c34, 0x6e51, 0x2c2b, - 0x6e5a, 0x2c21, 0x6e63, 0x2c18, 0x6e6b, 0x2c0f, 0x6e74, 0x2c06, - 0x6e7d, 0x2bfd, 0x6e85, 0x2bf4, 0x6e8e, 0x2beb, 0x6e97, 0x2be2, - 0x6e9f, 0x2bd8, 0x6ea8, 0x2bcf, 0x6eb0, 0x2bc6, 0x6eb9, 0x2bbd, - 0x6ec2, 0x2bb4, 0x6eca, 0x2bab, 0x6ed3, 0x2ba1, 0x6edb, 0x2b98, - 0x6ee4, 0x2b8f, 0x6eec, 0x2b86, 0x6ef5, 0x2b7d, 0x6efd, 0x2b73, - 0x6f06, 0x2b6a, 0x6f0e, 0x2b61, 0x6f17, 0x2b58, 0x6f20, 0x2b4e, - 0x6f28, 0x2b45, 0x6f30, 0x2b3c, 0x6f39, 0x2b33, 0x6f41, 0x2b29, - 0x6f4a, 0x2b20, 0x6f52, 0x2b17, 0x6f5b, 0x2b0d, 0x6f63, 0x2b04, - 0x6f6c, 0x2afb, 0x6f74, 0x2af2, 0x6f7d, 0x2ae8, 0x6f85, 0x2adf, - 0x6f8d, 0x2ad6, 0x6f96, 0x2acc, 0x6f9e, 0x2ac3, 0x6fa7, 0x2ab9, - 0x6faf, 0x2ab0, 0x6fb7, 0x2aa7, 0x6fc0, 0x2a9d, 0x6fc8, 0x2a94, - 0x6fd0, 0x2a8b, 0x6fd9, 0x2a81, 0x6fe1, 0x2a78, 0x6fea, 0x2a6e, - 0x6ff2, 0x2a65, 0x6ffa, 0x2a5c, 0x7002, 0x2a52, 0x700b, 0x2a49, - 0x7013, 0x2a3f, 0x701b, 0x2a36, 0x7024, 0x2a2c, 0x702c, 0x2a23, - 0x7034, 0x2a1a, 0x703c, 0x2a10, 0x7045, 0x2a07, 0x704d, 0x29fd, - 0x7055, 0x29f4, 0x705d, 0x29ea, 0x7066, 0x29e1, 0x706e, 0x29d7, - 0x7076, 0x29ce, 0x707e, 0x29c4, 0x7087, 0x29bb, 0x708f, 0x29b1, - 0x7097, 0x29a7, 0x709f, 0x299e, 0x70a7, 0x2994, 0x70af, 0x298b, - 0x70b8, 0x2981, 0x70c0, 0x2978, 0x70c8, 0x296e, 0x70d0, 0x2965, - 0x70d8, 0x295b, 0x70e0, 0x2951, 0x70e8, 0x2948, 0x70f0, 0x293e, - 0x70f9, 0x2935, 0x7101, 0x292b, 0x7109, 0x2921, 0x7111, 0x2918, - 0x7119, 0x290e, 0x7121, 0x2904, 0x7129, 0x28fb, 0x7131, 0x28f1, - 0x7139, 0x28e7, 0x7141, 0x28de, 0x7149, 0x28d4, 0x7151, 0x28ca, - 0x7159, 0x28c1, 0x7161, 0x28b7, 0x7169, 0x28ad, 0x7171, 0x28a4, - 0x7179, 0x289a, 0x7181, 0x2890, 0x7189, 0x2886, 0x7191, 0x287d, - 0x7199, 0x2873, 0x71a1, 0x2869, 0x71a9, 0x2860, 0x71b1, 0x2856, - 0x71b9, 0x284c, 0x71c0, 0x2842, 0x71c8, 0x2838, 0x71d0, 0x282f, - 0x71d8, 0x2825, 0x71e0, 0x281b, 0x71e8, 0x2811, 0x71f0, 0x2808, - 0x71f8, 0x27fe, 0x71ff, 0x27f4, 0x7207, 0x27ea, 0x720f, 0x27e0, - 0x7217, 0x27d6, 0x721f, 0x27cd, 0x7227, 0x27c3, 0x722e, 0x27b9, - 0x7236, 0x27af, 0x723e, 0x27a5, 0x7246, 0x279b, 0x724e, 0x2791, - 0x7255, 0x2788, 0x725d, 0x277e, 0x7265, 0x2774, 0x726d, 0x276a, - 0x7274, 0x2760, 0x727c, 0x2756, 0x7284, 0x274c, 0x728b, 0x2742, - 0x7293, 0x2738, 0x729b, 0x272e, 0x72a3, 0x2724, 0x72aa, 0x271a, - 0x72b2, 0x2711, 0x72ba, 0x2707, 0x72c1, 0x26fd, 0x72c9, 0x26f3, - 0x72d0, 0x26e9, 0x72d8, 0x26df, 0x72e0, 0x26d5, 0x72e7, 0x26cb, - 0x72ef, 0x26c1, 0x72f7, 0x26b7, 0x72fe, 0x26ad, 0x7306, 0x26a3, - 0x730d, 0x2699, 0x7315, 0x268f, 0x731d, 0x2685, 0x7324, 0x267b, - 0x732c, 0x2671, 0x7333, 0x2666, 0x733b, 0x265c, 0x7342, 0x2652, - 0x734a, 0x2648, 0x7351, 0x263e, 0x7359, 0x2634, 0x7360, 0x262a, - 0x7368, 0x2620, 0x736f, 0x2616, 0x7377, 0x260c, 0x737e, 0x2602, - 0x7386, 0x25f8, 0x738d, 0x25ed, 0x7395, 0x25e3, 0x739c, 0x25d9, - 0x73a3, 0x25cf, 0x73ab, 0x25c5, 0x73b2, 0x25bb, 0x73ba, 0x25b1, - 0x73c1, 0x25a6, 0x73c8, 0x259c, 0x73d0, 0x2592, 0x73d7, 0x2588, - 0x73df, 0x257e, 0x73e6, 0x2574, 0x73ed, 0x2569, 0x73f5, 0x255f, - 0x73fc, 0x2555, 0x7403, 0x254b, 0x740b, 0x2541, 0x7412, 0x2536, - 0x7419, 0x252c, 0x7420, 0x2522, 0x7428, 0x2518, 0x742f, 0x250d, - 0x7436, 0x2503, 0x743e, 0x24f9, 0x7445, 0x24ef, 0x744c, 0x24e4, - 0x7453, 0x24da, 0x745b, 0x24d0, 0x7462, 0x24c5, 0x7469, 0x24bb, - 0x7470, 0x24b1, 0x7477, 0x24a7, 0x747f, 0x249c, 0x7486, 0x2492, - 0x748d, 0x2488, 0x7494, 0x247d, 0x749b, 0x2473, 0x74a2, 0x2469, - 0x74aa, 0x245e, 0x74b1, 0x2454, 0x74b8, 0x244a, 0x74bf, 0x243f, - 0x74c6, 0x2435, 0x74cd, 0x242b, 0x74d4, 0x2420, 0x74db, 0x2416, - 0x74e2, 0x240b, 0x74ea, 0x2401, 0x74f1, 0x23f7, 0x74f8, 0x23ec, - 0x74ff, 0x23e2, 0x7506, 0x23d7, 0x750d, 0x23cd, 0x7514, 0x23c3, - 0x751b, 0x23b8, 0x7522, 0x23ae, 0x7529, 0x23a3, 0x7530, 0x2399, - 0x7537, 0x238e, 0x753e, 0x2384, 0x7545, 0x237a, 0x754c, 0x236f, - 0x7553, 0x2365, 0x755a, 0x235a, 0x7561, 0x2350, 0x7567, 0x2345, - 0x756e, 0x233b, 0x7575, 0x2330, 0x757c, 0x2326, 0x7583, 0x231b, - 0x758a, 0x2311, 0x7591, 0x2306, 0x7598, 0x22fc, 0x759f, 0x22f1, - 0x75a5, 0x22e7, 0x75ac, 0x22dc, 0x75b3, 0x22d2, 0x75ba, 0x22c7, - 0x75c1, 0x22bc, 0x75c8, 0x22b2, 0x75ce, 0x22a7, 0x75d5, 0x229d, - 0x75dc, 0x2292, 0x75e3, 0x2288, 0x75ea, 0x227d, 0x75f0, 0x2272, - 0x75f7, 0x2268, 0x75fe, 0x225d, 0x7605, 0x2253, 0x760b, 0x2248, - 0x7612, 0x223d, 0x7619, 0x2233, 0x7620, 0x2228, 0x7626, 0x221e, - 0x762d, 0x2213, 0x7634, 0x2208, 0x763a, 0x21fe, 0x7641, 0x21f3, - 0x7648, 0x21e8, 0x764e, 0x21de, 0x7655, 0x21d3, 0x765c, 0x21c8, - 0x7662, 0x21be, 0x7669, 0x21b3, 0x766f, 0x21a8, 0x7676, 0x219e, - 0x767d, 0x2193, 0x7683, 0x2188, 0x768a, 0x217d, 0x7690, 0x2173, - 0x7697, 0x2168, 0x769d, 0x215d, 0x76a4, 0x2153, 0x76ab, 0x2148, - 0x76b1, 0x213d, 0x76b8, 0x2132, 0x76be, 0x2128, 0x76c5, 0x211d, - 0x76cb, 0x2112, 0x76d2, 0x2107, 0x76d8, 0x20fd, 0x76df, 0x20f2, - 0x76e5, 0x20e7, 0x76eb, 0x20dc, 0x76f2, 0x20d1, 0x76f8, 0x20c7, - 0x76ff, 0x20bc, 0x7705, 0x20b1, 0x770c, 0x20a6, 0x7712, 0x209b, - 0x7718, 0x2091, 0x771f, 0x2086, 0x7725, 0x207b, 0x772c, 0x2070, - 0x7732, 0x2065, 0x7738, 0x205b, 0x773f, 0x2050, 0x7745, 0x2045, - 0x774b, 0x203a, 0x7752, 0x202f, 0x7758, 0x2024, 0x775e, 0x2019, - 0x7765, 0x200f, 0x776b, 0x2004, 0x7771, 0x1ff9, 0x7777, 0x1fee, - 0x777e, 0x1fe3, 0x7784, 0x1fd8, 0x778a, 0x1fcd, 0x7790, 0x1fc2, - 0x7797, 0x1fb7, 0x779d, 0x1fac, 0x77a3, 0x1fa2, 0x77a9, 0x1f97, - 0x77b0, 0x1f8c, 0x77b6, 0x1f81, 0x77bc, 0x1f76, 0x77c2, 0x1f6b, - 0x77c8, 0x1f60, 0x77ce, 0x1f55, 0x77d5, 0x1f4a, 0x77db, 0x1f3f, - 0x77e1, 0x1f34, 0x77e7, 0x1f29, 0x77ed, 0x1f1e, 0x77f3, 0x1f13, - 0x77f9, 0x1f08, 0x77ff, 0x1efd, 0x7805, 0x1ef2, 0x780b, 0x1ee7, - 0x7812, 0x1edc, 0x7818, 0x1ed1, 0x781e, 0x1ec6, 0x7824, 0x1ebb, - 0x782a, 0x1eb0, 0x7830, 0x1ea5, 0x7836, 0x1e9a, 0x783c, 0x1e8f, - 0x7842, 0x1e84, 0x7848, 0x1e79, 0x784e, 0x1e6e, 0x7854, 0x1e63, - 0x785a, 0x1e58, 0x7860, 0x1e4d, 0x7866, 0x1e42, 0x786b, 0x1e36, - 0x7871, 0x1e2b, 0x7877, 0x1e20, 0x787d, 0x1e15, 0x7883, 0x1e0a, - 0x7889, 0x1dff, 0x788f, 0x1df4, 0x7895, 0x1de9, 0x789b, 0x1dde, - 0x78a1, 0x1dd3, 0x78a6, 0x1dc7, 0x78ac, 0x1dbc, 0x78b2, 0x1db1, - 0x78b8, 0x1da6, 0x78be, 0x1d9b, 0x78c3, 0x1d90, 0x78c9, 0x1d85, - 0x78cf, 0x1d79, 0x78d5, 0x1d6e, 0x78db, 0x1d63, 0x78e0, 0x1d58, - 0x78e6, 0x1d4d, 0x78ec, 0x1d42, 0x78f2, 0x1d36, 0x78f7, 0x1d2b, - 0x78fd, 0x1d20, 0x7903, 0x1d15, 0x7909, 0x1d0a, 0x790e, 0x1cff, - 0x7914, 0x1cf3, 0x791a, 0x1ce8, 0x791f, 0x1cdd, 0x7925, 0x1cd2, - 0x792b, 0x1cc6, 0x7930, 0x1cbb, 0x7936, 0x1cb0, 0x793b, 0x1ca5, - 0x7941, 0x1c99, 0x7947, 0x1c8e, 0x794c, 0x1c83, 0x7952, 0x1c78, - 0x7958, 0x1c6c, 0x795d, 0x1c61, 0x7963, 0x1c56, 0x7968, 0x1c4b, - 0x796e, 0x1c3f, 0x7973, 0x1c34, 0x7979, 0x1c29, 0x797e, 0x1c1e, - 0x7984, 0x1c12, 0x7989, 0x1c07, 0x798f, 0x1bfc, 0x7994, 0x1bf0, - 0x799a, 0x1be5, 0x799f, 0x1bda, 0x79a5, 0x1bce, 0x79aa, 0x1bc3, - 0x79b0, 0x1bb8, 0x79b5, 0x1bac, 0x79bb, 0x1ba1, 0x79c0, 0x1b96, - 0x79c5, 0x1b8a, 0x79cb, 0x1b7f, 0x79d0, 0x1b74, 0x79d6, 0x1b68, - 0x79db, 0x1b5d, 0x79e0, 0x1b52, 0x79e6, 0x1b46, 0x79eb, 0x1b3b, - 0x79f0, 0x1b30, 0x79f6, 0x1b24, 0x79fb, 0x1b19, 0x7a00, 0x1b0d, - 0x7a06, 0x1b02, 0x7a0b, 0x1af7, 0x7a10, 0x1aeb, 0x7a16, 0x1ae0, - 0x7a1b, 0x1ad4, 0x7a20, 0x1ac9, 0x7a25, 0x1abe, 0x7a2b, 0x1ab2, - 0x7a30, 0x1aa7, 0x7a35, 0x1a9b, 0x7a3a, 0x1a90, 0x7a3f, 0x1a84, - 0x7a45, 0x1a79, 0x7a4a, 0x1a6e, 0x7a4f, 0x1a62, 0x7a54, 0x1a57, - 0x7a59, 0x1a4b, 0x7a5f, 0x1a40, 0x7a64, 0x1a34, 0x7a69, 0x1a29, - 0x7a6e, 0x1a1d, 0x7a73, 0x1a12, 0x7a78, 0x1a06, 0x7a7d, 0x19fb, - 0x7a82, 0x19ef, 0x7a88, 0x19e4, 0x7a8d, 0x19d8, 0x7a92, 0x19cd, - 0x7a97, 0x19c1, 0x7a9c, 0x19b6, 0x7aa1, 0x19aa, 0x7aa6, 0x199f, - 0x7aab, 0x1993, 0x7ab0, 0x1988, 0x7ab5, 0x197c, 0x7aba, 0x1971, - 0x7abf, 0x1965, 0x7ac4, 0x195a, 0x7ac9, 0x194e, 0x7ace, 0x1943, - 0x7ad3, 0x1937, 0x7ad8, 0x192c, 0x7add, 0x1920, 0x7ae2, 0x1914, - 0x7ae6, 0x1909, 0x7aeb, 0x18fd, 0x7af0, 0x18f2, 0x7af5, 0x18e6, - 0x7afa, 0x18db, 0x7aff, 0x18cf, 0x7b04, 0x18c3, 0x7b09, 0x18b8, - 0x7b0e, 0x18ac, 0x7b12, 0x18a1, 0x7b17, 0x1895, 0x7b1c, 0x1889, - 0x7b21, 0x187e, 0x7b26, 0x1872, 0x7b2a, 0x1867, 0x7b2f, 0x185b, - 0x7b34, 0x184f, 0x7b39, 0x1844, 0x7b3e, 0x1838, 0x7b42, 0x182d, - 0x7b47, 0x1821, 0x7b4c, 0x1815, 0x7b50, 0x180a, 0x7b55, 0x17fe, - 0x7b5a, 0x17f2, 0x7b5f, 0x17e7, 0x7b63, 0x17db, 0x7b68, 0x17cf, - 0x7b6d, 0x17c4, 0x7b71, 0x17b8, 0x7b76, 0x17ac, 0x7b7b, 0x17a1, - 0x7b7f, 0x1795, 0x7b84, 0x1789, 0x7b88, 0x177e, 0x7b8d, 0x1772, - 0x7b92, 0x1766, 0x7b96, 0x175b, 0x7b9b, 0x174f, 0x7b9f, 0x1743, - 0x7ba4, 0x1737, 0x7ba9, 0x172c, 0x7bad, 0x1720, 0x7bb2, 0x1714, - 0x7bb6, 0x1709, 0x7bbb, 0x16fd, 0x7bbf, 0x16f1, 0x7bc4, 0x16e5, - 0x7bc8, 0x16da, 0x7bcd, 0x16ce, 0x7bd1, 0x16c2, 0x7bd6, 0x16b6, - 0x7bda, 0x16ab, 0x7bde, 0x169f, 0x7be3, 0x1693, 0x7be7, 0x1687, - 0x7bec, 0x167c, 0x7bf0, 0x1670, 0x7bf5, 0x1664, 0x7bf9, 0x1658, - 0x7bfd, 0x164c, 0x7c02, 0x1641, 0x7c06, 0x1635, 0x7c0a, 0x1629, - 0x7c0f, 0x161d, 0x7c13, 0x1612, 0x7c17, 0x1606, 0x7c1c, 0x15fa, - 0x7c20, 0x15ee, 0x7c24, 0x15e2, 0x7c29, 0x15d7, 0x7c2d, 0x15cb, - 0x7c31, 0x15bf, 0x7c36, 0x15b3, 0x7c3a, 0x15a7, 0x7c3e, 0x159b, - 0x7c42, 0x1590, 0x7c46, 0x1584, 0x7c4b, 0x1578, 0x7c4f, 0x156c, - 0x7c53, 0x1560, 0x7c57, 0x1554, 0x7c5b, 0x1549, 0x7c60, 0x153d, - 0x7c64, 0x1531, 0x7c68, 0x1525, 0x7c6c, 0x1519, 0x7c70, 0x150d, - 0x7c74, 0x1501, 0x7c79, 0x14f6, 0x7c7d, 0x14ea, 0x7c81, 0x14de, - 0x7c85, 0x14d2, 0x7c89, 0x14c6, 0x7c8d, 0x14ba, 0x7c91, 0x14ae, - 0x7c95, 0x14a2, 0x7c99, 0x1496, 0x7c9d, 0x148b, 0x7ca1, 0x147f, - 0x7ca5, 0x1473, 0x7ca9, 0x1467, 0x7cad, 0x145b, 0x7cb1, 0x144f, - 0x7cb5, 0x1443, 0x7cb9, 0x1437, 0x7cbd, 0x142b, 0x7cc1, 0x141f, - 0x7cc5, 0x1413, 0x7cc9, 0x1407, 0x7ccd, 0x13fb, 0x7cd1, 0x13f0, - 0x7cd5, 0x13e4, 0x7cd9, 0x13d8, 0x7cdd, 0x13cc, 0x7ce0, 0x13c0, - 0x7ce4, 0x13b4, 0x7ce8, 0x13a8, 0x7cec, 0x139c, 0x7cf0, 0x1390, - 0x7cf4, 0x1384, 0x7cf8, 0x1378, 0x7cfb, 0x136c, 0x7cff, 0x1360, - 0x7d03, 0x1354, 0x7d07, 0x1348, 0x7d0b, 0x133c, 0x7d0e, 0x1330, - 0x7d12, 0x1324, 0x7d16, 0x1318, 0x7d1a, 0x130c, 0x7d1d, 0x1300, - 0x7d21, 0x12f4, 0x7d25, 0x12e8, 0x7d28, 0x12dc, 0x7d2c, 0x12d0, - 0x7d30, 0x12c4, 0x7d34, 0x12b8, 0x7d37, 0x12ac, 0x7d3b, 0x12a0, - 0x7d3f, 0x1294, 0x7d42, 0x1288, 0x7d46, 0x127c, 0x7d49, 0x1270, - 0x7d4d, 0x1264, 0x7d51, 0x1258, 0x7d54, 0x124c, 0x7d58, 0x1240, - 0x7d5b, 0x1234, 0x7d5f, 0x1228, 0x7d63, 0x121c, 0x7d66, 0x1210, - 0x7d6a, 0x1204, 0x7d6d, 0x11f7, 0x7d71, 0x11eb, 0x7d74, 0x11df, - 0x7d78, 0x11d3, 0x7d7b, 0x11c7, 0x7d7f, 0x11bb, 0x7d82, 0x11af, - 0x7d86, 0x11a3, 0x7d89, 0x1197, 0x7d8d, 0x118b, 0x7d90, 0x117f, - 0x7d93, 0x1173, 0x7d97, 0x1167, 0x7d9a, 0x115a, 0x7d9e, 0x114e, - 0x7da1, 0x1142, 0x7da4, 0x1136, 0x7da8, 0x112a, 0x7dab, 0x111e, - 0x7daf, 0x1112, 0x7db2, 0x1106, 0x7db5, 0x10fa, 0x7db9, 0x10ed, - 0x7dbc, 0x10e1, 0x7dbf, 0x10d5, 0x7dc2, 0x10c9, 0x7dc6, 0x10bd, - 0x7dc9, 0x10b1, 0x7dcc, 0x10a5, 0x7dd0, 0x1099, 0x7dd3, 0x108c, - 0x7dd6, 0x1080, 0x7dd9, 0x1074, 0x7ddd, 0x1068, 0x7de0, 0x105c, - 0x7de3, 0x1050, 0x7de6, 0x1044, 0x7de9, 0x1037, 0x7ded, 0x102b, - 0x7df0, 0x101f, 0x7df3, 0x1013, 0x7df6, 0x1007, 0x7df9, 0xffb, - 0x7dfc, 0xfee, 0x7dff, 0xfe2, 0x7e03, 0xfd6, 0x7e06, 0xfca, - 0x7e09, 0xfbe, 0x7e0c, 0xfb2, 0x7e0f, 0xfa5, 0x7e12, 0xf99, - 0x7e15, 0xf8d, 0x7e18, 0xf81, 0x7e1b, 0xf75, 0x7e1e, 0xf68, - 0x7e21, 0xf5c, 0x7e24, 0xf50, 0x7e27, 0xf44, 0x7e2a, 0xf38, - 0x7e2d, 0xf2b, 0x7e30, 0xf1f, 0x7e33, 0xf13, 0x7e36, 0xf07, - 0x7e39, 0xefb, 0x7e3c, 0xeee, 0x7e3f, 0xee2, 0x7e42, 0xed6, - 0x7e45, 0xeca, 0x7e48, 0xebd, 0x7e4a, 0xeb1, 0x7e4d, 0xea5, - 0x7e50, 0xe99, 0x7e53, 0xe8c, 0x7e56, 0xe80, 0x7e59, 0xe74, - 0x7e5c, 0xe68, 0x7e5e, 0xe5c, 0x7e61, 0xe4f, 0x7e64, 0xe43, - 0x7e67, 0xe37, 0x7e6a, 0xe2b, 0x7e6c, 0xe1e, 0x7e6f, 0xe12, - 0x7e72, 0xe06, 0x7e75, 0xdf9, 0x7e77, 0xded, 0x7e7a, 0xde1, - 0x7e7d, 0xdd5, 0x7e80, 0xdc8, 0x7e82, 0xdbc, 0x7e85, 0xdb0, - 0x7e88, 0xda4, 0x7e8a, 0xd97, 0x7e8d, 0xd8b, 0x7e90, 0xd7f, - 0x7e92, 0xd72, 0x7e95, 0xd66, 0x7e98, 0xd5a, 0x7e9a, 0xd4e, - 0x7e9d, 0xd41, 0x7e9f, 0xd35, 0x7ea2, 0xd29, 0x7ea5, 0xd1c, - 0x7ea7, 0xd10, 0x7eaa, 0xd04, 0x7eac, 0xcf8, 0x7eaf, 0xceb, - 0x7eb1, 0xcdf, 0x7eb4, 0xcd3, 0x7eb6, 0xcc6, 0x7eb9, 0xcba, - 0x7ebb, 0xcae, 0x7ebe, 0xca1, 0x7ec0, 0xc95, 0x7ec3, 0xc89, - 0x7ec5, 0xc7c, 0x7ec8, 0xc70, 0x7eca, 0xc64, 0x7ecc, 0xc57, - 0x7ecf, 0xc4b, 0x7ed1, 0xc3f, 0x7ed4, 0xc32, 0x7ed6, 0xc26, - 0x7ed8, 0xc1a, 0x7edb, 0xc0d, 0x7edd, 0xc01, 0x7ee0, 0xbf5, - 0x7ee2, 0xbe8, 0x7ee4, 0xbdc, 0x7ee7, 0xbd0, 0x7ee9, 0xbc3, - 0x7eeb, 0xbb7, 0x7eed, 0xbab, 0x7ef0, 0xb9e, 0x7ef2, 0xb92, - 0x7ef4, 0xb85, 0x7ef7, 0xb79, 0x7ef9, 0xb6d, 0x7efb, 0xb60, - 0x7efd, 0xb54, 0x7f00, 0xb48, 0x7f02, 0xb3b, 0x7f04, 0xb2f, - 0x7f06, 0xb23, 0x7f08, 0xb16, 0x7f0a, 0xb0a, 0x7f0d, 0xafd, - 0x7f0f, 0xaf1, 0x7f11, 0xae5, 0x7f13, 0xad8, 0x7f15, 0xacc, - 0x7f17, 0xac0, 0x7f19, 0xab3, 0x7f1c, 0xaa7, 0x7f1e, 0xa9a, - 0x7f20, 0xa8e, 0x7f22, 0xa82, 0x7f24, 0xa75, 0x7f26, 0xa69, - 0x7f28, 0xa5c, 0x7f2a, 0xa50, 0x7f2c, 0xa44, 0x7f2e, 0xa37, - 0x7f30, 0xa2b, 0x7f32, 0xa1e, 0x7f34, 0xa12, 0x7f36, 0xa06, - 0x7f38, 0x9f9, 0x7f3a, 0x9ed, 0x7f3c, 0x9e0, 0x7f3e, 0x9d4, - 0x7f40, 0x9c7, 0x7f42, 0x9bb, 0x7f43, 0x9af, 0x7f45, 0x9a2, - 0x7f47, 0x996, 0x7f49, 0x989, 0x7f4b, 0x97d, 0x7f4d, 0x970, - 0x7f4f, 0x964, 0x7f51, 0x958, 0x7f52, 0x94b, 0x7f54, 0x93f, - 0x7f56, 0x932, 0x7f58, 0x926, 0x7f5a, 0x919, 0x7f5b, 0x90d, - 0x7f5d, 0x901, 0x7f5f, 0x8f4, 0x7f61, 0x8e8, 0x7f62, 0x8db, - 0x7f64, 0x8cf, 0x7f66, 0x8c2, 0x7f68, 0x8b6, 0x7f69, 0x8a9, - 0x7f6b, 0x89d, 0x7f6d, 0x891, 0x7f6e, 0x884, 0x7f70, 0x878, - 0x7f72, 0x86b, 0x7f73, 0x85f, 0x7f75, 0x852, 0x7f77, 0x846, - 0x7f78, 0x839, 0x7f7a, 0x82d, 0x7f7b, 0x820, 0x7f7d, 0x814, - 0x7f7f, 0x807, 0x7f80, 0x7fb, 0x7f82, 0x7ef, 0x7f83, 0x7e2, - 0x7f85, 0x7d6, 0x7f86, 0x7c9, 0x7f88, 0x7bd, 0x7f89, 0x7b0, - 0x7f8b, 0x7a4, 0x7f8c, 0x797, 0x7f8e, 0x78b, 0x7f8f, 0x77e, - 0x7f91, 0x772, 0x7f92, 0x765, 0x7f94, 0x759, 0x7f95, 0x74c, - 0x7f97, 0x740, 0x7f98, 0x733, 0x7f99, 0x727, 0x7f9b, 0x71a, - 0x7f9c, 0x70e, 0x7f9e, 0x701, 0x7f9f, 0x6f5, 0x7fa0, 0x6e8, - 0x7fa2, 0x6dc, 0x7fa3, 0x6cf, 0x7fa4, 0x6c3, 0x7fa6, 0x6b6, - 0x7fa7, 0x6aa, 0x7fa8, 0x69d, 0x7faa, 0x691, 0x7fab, 0x684, - 0x7fac, 0x678, 0x7fad, 0x66b, 0x7faf, 0x65f, 0x7fb0, 0x652, - 0x7fb1, 0x646, 0x7fb2, 0x639, 0x7fb4, 0x62d, 0x7fb5, 0x620, - 0x7fb6, 0x614, 0x7fb7, 0x607, 0x7fb8, 0x5fb, 0x7fb9, 0x5ee, - 0x7fbb, 0x5e2, 0x7fbc, 0x5d5, 0x7fbd, 0x5c9, 0x7fbe, 0x5bc, - 0x7fbf, 0x5b0, 0x7fc0, 0x5a3, 0x7fc1, 0x597, 0x7fc3, 0x58a, - 0x7fc4, 0x57e, 0x7fc5, 0x571, 0x7fc6, 0x565, 0x7fc7, 0x558, - 0x7fc8, 0x54c, 0x7fc9, 0x53f, 0x7fca, 0x533, 0x7fcb, 0x526, - 0x7fcc, 0x51a, 0x7fcd, 0x50d, 0x7fce, 0x500, 0x7fcf, 0x4f4, - 0x7fd0, 0x4e7, 0x7fd1, 0x4db, 0x7fd2, 0x4ce, 0x7fd3, 0x4c2, - 0x7fd4, 0x4b5, 0x7fd5, 0x4a9, 0x7fd5, 0x49c, 0x7fd6, 0x490, - 0x7fd7, 0x483, 0x7fd8, 0x477, 0x7fd9, 0x46a, 0x7fda, 0x45e, - 0x7fdb, 0x451, 0x7fdc, 0x444, 0x7fdc, 0x438, 0x7fdd, 0x42b, - 0x7fde, 0x41f, 0x7fdf, 0x412, 0x7fe0, 0x406, 0x7fe0, 0x3f9, - 0x7fe1, 0x3ed, 0x7fe2, 0x3e0, 0x7fe3, 0x3d4, 0x7fe3, 0x3c7, - 0x7fe4, 0x3bb, 0x7fe5, 0x3ae, 0x7fe6, 0x3a1, 0x7fe6, 0x395, - 0x7fe7, 0x388, 0x7fe8, 0x37c, 0x7fe8, 0x36f, 0x7fe9, 0x363, - 0x7fea, 0x356, 0x7fea, 0x34a, 0x7feb, 0x33d, 0x7fec, 0x330, - 0x7fec, 0x324, 0x7fed, 0x317, 0x7fed, 0x30b, 0x7fee, 0x2fe, - 0x7fef, 0x2f2, 0x7fef, 0x2e5, 0x7ff0, 0x2d9, 0x7ff0, 0x2cc, - 0x7ff1, 0x2c0, 0x7ff1, 0x2b3, 0x7ff2, 0x2a6, 0x7ff2, 0x29a, - 0x7ff3, 0x28d, 0x7ff3, 0x281, 0x7ff4, 0x274, 0x7ff4, 0x268, - 0x7ff5, 0x25b, 0x7ff5, 0x24e, 0x7ff6, 0x242, 0x7ff6, 0x235, - 0x7ff7, 0x229, 0x7ff7, 0x21c, 0x7ff7, 0x210, 0x7ff8, 0x203, - 0x7ff8, 0x1f7, 0x7ff9, 0x1ea, 0x7ff9, 0x1dd, 0x7ff9, 0x1d1, - 0x7ffa, 0x1c4, 0x7ffa, 0x1b8, 0x7ffa, 0x1ab, 0x7ffb, 0x19f, - 0x7ffb, 0x192, 0x7ffb, 0x186, 0x7ffc, 0x179, 0x7ffc, 0x16c, - 0x7ffc, 0x160, 0x7ffc, 0x153, 0x7ffd, 0x147, 0x7ffd, 0x13a, - 0x7ffd, 0x12e, 0x7ffd, 0x121, 0x7ffe, 0x114, 0x7ffe, 0x108, - 0x7ffe, 0xfb, 0x7ffe, 0xef, 0x7ffe, 0xe2, 0x7fff, 0xd6, - 0x7fff, 0xc9, 0x7fff, 0xbc, 0x7fff, 0xb0, 0x7fff, 0xa3, - 0x7fff, 0x97, 0x7fff, 0x8a, 0x7fff, 0x7e, 0x7fff, 0x71, - 0x7fff, 0x65, 0x7fff, 0x58, 0x7fff, 0x4b, 0x7fff, 0x3f, - 0x7fff, 0x32, 0x7fff, 0x26, 0x7fff, 0x19, 0x7fff, 0xd, - 0x7fff, 0x0, 0x7fff, 0xfff3, 0x7fff, 0xffe7, 0x7fff, 0xffda, - 0x7fff, 0xffce, 0x7fff, 0xffc1, 0x7fff, 0xffb5, 0x7fff, 0xffa8, - 0x7fff, 0xff9b, 0x7fff, 0xff8f, 0x7fff, 0xff82, 0x7fff, 0xff76, - 0x7fff, 0xff69, 0x7fff, 0xff5d, 0x7fff, 0xff50, 0x7fff, 0xff44, - 0x7fff, 0xff37, 0x7fff, 0xff2a, 0x7ffe, 0xff1e, 0x7ffe, 0xff11, - 0x7ffe, 0xff05, 0x7ffe, 0xfef8, 0x7ffe, 0xfeec, 0x7ffd, 0xfedf, - 0x7ffd, 0xfed2, 0x7ffd, 0xfec6, 0x7ffd, 0xfeb9, 0x7ffc, 0xfead, - 0x7ffc, 0xfea0, 0x7ffc, 0xfe94, 0x7ffc, 0xfe87, 0x7ffb, 0xfe7a, - 0x7ffb, 0xfe6e, 0x7ffb, 0xfe61, 0x7ffa, 0xfe55, 0x7ffa, 0xfe48, - 0x7ffa, 0xfe3c, 0x7ff9, 0xfe2f, 0x7ff9, 0xfe23, 0x7ff9, 0xfe16, - 0x7ff8, 0xfe09, 0x7ff8, 0xfdfd, 0x7ff7, 0xfdf0, 0x7ff7, 0xfde4, - 0x7ff7, 0xfdd7, 0x7ff6, 0xfdcb, 0x7ff6, 0xfdbe, 0x7ff5, 0xfdb2, - 0x7ff5, 0xfda5, 0x7ff4, 0xfd98, 0x7ff4, 0xfd8c, 0x7ff3, 0xfd7f, - 0x7ff3, 0xfd73, 0x7ff2, 0xfd66, 0x7ff2, 0xfd5a, 0x7ff1, 0xfd4d, - 0x7ff1, 0xfd40, 0x7ff0, 0xfd34, 0x7ff0, 0xfd27, 0x7fef, 0xfd1b, - 0x7fef, 0xfd0e, 0x7fee, 0xfd02, 0x7fed, 0xfcf5, 0x7fed, 0xfce9, - 0x7fec, 0xfcdc, 0x7fec, 0xfcd0, 0x7feb, 0xfcc3, 0x7fea, 0xfcb6, - 0x7fea, 0xfcaa, 0x7fe9, 0xfc9d, 0x7fe8, 0xfc91, 0x7fe8, 0xfc84, - 0x7fe7, 0xfc78, 0x7fe6, 0xfc6b, 0x7fe6, 0xfc5f, 0x7fe5, 0xfc52, - 0x7fe4, 0xfc45, 0x7fe3, 0xfc39, 0x7fe3, 0xfc2c, 0x7fe2, 0xfc20, - 0x7fe1, 0xfc13, 0x7fe0, 0xfc07, 0x7fe0, 0xfbfa, 0x7fdf, 0xfbee, - 0x7fde, 0xfbe1, 0x7fdd, 0xfbd5, 0x7fdc, 0xfbc8, 0x7fdc, 0xfbbc, - 0x7fdb, 0xfbaf, 0x7fda, 0xfba2, 0x7fd9, 0xfb96, 0x7fd8, 0xfb89, - 0x7fd7, 0xfb7d, 0x7fd6, 0xfb70, 0x7fd5, 0xfb64, 0x7fd5, 0xfb57, - 0x7fd4, 0xfb4b, 0x7fd3, 0xfb3e, 0x7fd2, 0xfb32, 0x7fd1, 0xfb25, - 0x7fd0, 0xfb19, 0x7fcf, 0xfb0c, 0x7fce, 0xfb00, 0x7fcd, 0xfaf3, - 0x7fcc, 0xfae6, 0x7fcb, 0xfada, 0x7fca, 0xfacd, 0x7fc9, 0xfac1, - 0x7fc8, 0xfab4, 0x7fc7, 0xfaa8, 0x7fc6, 0xfa9b, 0x7fc5, 0xfa8f, - 0x7fc4, 0xfa82, 0x7fc3, 0xfa76, 0x7fc1, 0xfa69, 0x7fc0, 0xfa5d, - 0x7fbf, 0xfa50, 0x7fbe, 0xfa44, 0x7fbd, 0xfa37, 0x7fbc, 0xfa2b, - 0x7fbb, 0xfa1e, 0x7fb9, 0xfa12, 0x7fb8, 0xfa05, 0x7fb7, 0xf9f9, - 0x7fb6, 0xf9ec, 0x7fb5, 0xf9e0, 0x7fb4, 0xf9d3, 0x7fb2, 0xf9c7, - 0x7fb1, 0xf9ba, 0x7fb0, 0xf9ae, 0x7faf, 0xf9a1, 0x7fad, 0xf995, - 0x7fac, 0xf988, 0x7fab, 0xf97c, 0x7faa, 0xf96f, 0x7fa8, 0xf963, - 0x7fa7, 0xf956, 0x7fa6, 0xf94a, 0x7fa4, 0xf93d, 0x7fa3, 0xf931, - 0x7fa2, 0xf924, 0x7fa0, 0xf918, 0x7f9f, 0xf90b, 0x7f9e, 0xf8ff, - 0x7f9c, 0xf8f2, 0x7f9b, 0xf8e6, 0x7f99, 0xf8d9, 0x7f98, 0xf8cd, - 0x7f97, 0xf8c0, 0x7f95, 0xf8b4, 0x7f94, 0xf8a7, 0x7f92, 0xf89b, - 0x7f91, 0xf88e, 0x7f8f, 0xf882, 0x7f8e, 0xf875, 0x7f8c, 0xf869, - 0x7f8b, 0xf85c, 0x7f89, 0xf850, 0x7f88, 0xf843, 0x7f86, 0xf837, - 0x7f85, 0xf82a, 0x7f83, 0xf81e, 0x7f82, 0xf811, 0x7f80, 0xf805, - 0x7f7f, 0xf7f9, 0x7f7d, 0xf7ec, 0x7f7b, 0xf7e0, 0x7f7a, 0xf7d3, - 0x7f78, 0xf7c7, 0x7f77, 0xf7ba, 0x7f75, 0xf7ae, 0x7f73, 0xf7a1, - 0x7f72, 0xf795, 0x7f70, 0xf788, 0x7f6e, 0xf77c, 0x7f6d, 0xf76f, - 0x7f6b, 0xf763, 0x7f69, 0xf757, 0x7f68, 0xf74a, 0x7f66, 0xf73e, - 0x7f64, 0xf731, 0x7f62, 0xf725, 0x7f61, 0xf718, 0x7f5f, 0xf70c, - 0x7f5d, 0xf6ff, 0x7f5b, 0xf6f3, 0x7f5a, 0xf6e7, 0x7f58, 0xf6da, - 0x7f56, 0xf6ce, 0x7f54, 0xf6c1, 0x7f52, 0xf6b5, 0x7f51, 0xf6a8, - 0x7f4f, 0xf69c, 0x7f4d, 0xf690, 0x7f4b, 0xf683, 0x7f49, 0xf677, - 0x7f47, 0xf66a, 0x7f45, 0xf65e, 0x7f43, 0xf651, 0x7f42, 0xf645, - 0x7f40, 0xf639, 0x7f3e, 0xf62c, 0x7f3c, 0xf620, 0x7f3a, 0xf613, - 0x7f38, 0xf607, 0x7f36, 0xf5fa, 0x7f34, 0xf5ee, 0x7f32, 0xf5e2, - 0x7f30, 0xf5d5, 0x7f2e, 0xf5c9, 0x7f2c, 0xf5bc, 0x7f2a, 0xf5b0, - 0x7f28, 0xf5a4, 0x7f26, 0xf597, 0x7f24, 0xf58b, 0x7f22, 0xf57e, - 0x7f20, 0xf572, 0x7f1e, 0xf566, 0x7f1c, 0xf559, 0x7f19, 0xf54d, - 0x7f17, 0xf540, 0x7f15, 0xf534, 0x7f13, 0xf528, 0x7f11, 0xf51b, - 0x7f0f, 0xf50f, 0x7f0d, 0xf503, 0x7f0a, 0xf4f6, 0x7f08, 0xf4ea, - 0x7f06, 0xf4dd, 0x7f04, 0xf4d1, 0x7f02, 0xf4c5, 0x7f00, 0xf4b8, - 0x7efd, 0xf4ac, 0x7efb, 0xf4a0, 0x7ef9, 0xf493, 0x7ef7, 0xf487, - 0x7ef4, 0xf47b, 0x7ef2, 0xf46e, 0x7ef0, 0xf462, 0x7eed, 0xf455, - 0x7eeb, 0xf449, 0x7ee9, 0xf43d, 0x7ee7, 0xf430, 0x7ee4, 0xf424, - 0x7ee2, 0xf418, 0x7ee0, 0xf40b, 0x7edd, 0xf3ff, 0x7edb, 0xf3f3, - 0x7ed8, 0xf3e6, 0x7ed6, 0xf3da, 0x7ed4, 0xf3ce, 0x7ed1, 0xf3c1, - 0x7ecf, 0xf3b5, 0x7ecc, 0xf3a9, 0x7eca, 0xf39c, 0x7ec8, 0xf390, - 0x7ec5, 0xf384, 0x7ec3, 0xf377, 0x7ec0, 0xf36b, 0x7ebe, 0xf35f, - 0x7ebb, 0xf352, 0x7eb9, 0xf346, 0x7eb6, 0xf33a, 0x7eb4, 0xf32d, - 0x7eb1, 0xf321, 0x7eaf, 0xf315, 0x7eac, 0xf308, 0x7eaa, 0xf2fc, - 0x7ea7, 0xf2f0, 0x7ea5, 0xf2e4, 0x7ea2, 0xf2d7, 0x7e9f, 0xf2cb, - 0x7e9d, 0xf2bf, 0x7e9a, 0xf2b2, 0x7e98, 0xf2a6, 0x7e95, 0xf29a, - 0x7e92, 0xf28e, 0x7e90, 0xf281, 0x7e8d, 0xf275, 0x7e8a, 0xf269, - 0x7e88, 0xf25c, 0x7e85, 0xf250, 0x7e82, 0xf244, 0x7e80, 0xf238, - 0x7e7d, 0xf22b, 0x7e7a, 0xf21f, 0x7e77, 0xf213, 0x7e75, 0xf207, - 0x7e72, 0xf1fa, 0x7e6f, 0xf1ee, 0x7e6c, 0xf1e2, 0x7e6a, 0xf1d5, - 0x7e67, 0xf1c9, 0x7e64, 0xf1bd, 0x7e61, 0xf1b1, 0x7e5e, 0xf1a4, - 0x7e5c, 0xf198, 0x7e59, 0xf18c, 0x7e56, 0xf180, 0x7e53, 0xf174, - 0x7e50, 0xf167, 0x7e4d, 0xf15b, 0x7e4a, 0xf14f, 0x7e48, 0xf143, - 0x7e45, 0xf136, 0x7e42, 0xf12a, 0x7e3f, 0xf11e, 0x7e3c, 0xf112, - 0x7e39, 0xf105, 0x7e36, 0xf0f9, 0x7e33, 0xf0ed, 0x7e30, 0xf0e1, - 0x7e2d, 0xf0d5, 0x7e2a, 0xf0c8, 0x7e27, 0xf0bc, 0x7e24, 0xf0b0, - 0x7e21, 0xf0a4, 0x7e1e, 0xf098, 0x7e1b, 0xf08b, 0x7e18, 0xf07f, - 0x7e15, 0xf073, 0x7e12, 0xf067, 0x7e0f, 0xf05b, 0x7e0c, 0xf04e, - 0x7e09, 0xf042, 0x7e06, 0xf036, 0x7e03, 0xf02a, 0x7dff, 0xf01e, - 0x7dfc, 0xf012, 0x7df9, 0xf005, 0x7df6, 0xeff9, 0x7df3, 0xefed, - 0x7df0, 0xefe1, 0x7ded, 0xefd5, 0x7de9, 0xefc9, 0x7de6, 0xefbc, - 0x7de3, 0xefb0, 0x7de0, 0xefa4, 0x7ddd, 0xef98, 0x7dd9, 0xef8c, - 0x7dd6, 0xef80, 0x7dd3, 0xef74, 0x7dd0, 0xef67, 0x7dcc, 0xef5b, - 0x7dc9, 0xef4f, 0x7dc6, 0xef43, 0x7dc2, 0xef37, 0x7dbf, 0xef2b, - 0x7dbc, 0xef1f, 0x7db9, 0xef13, 0x7db5, 0xef06, 0x7db2, 0xeefa, - 0x7daf, 0xeeee, 0x7dab, 0xeee2, 0x7da8, 0xeed6, 0x7da4, 0xeeca, - 0x7da1, 0xeebe, 0x7d9e, 0xeeb2, 0x7d9a, 0xeea6, 0x7d97, 0xee99, - 0x7d93, 0xee8d, 0x7d90, 0xee81, 0x7d8d, 0xee75, 0x7d89, 0xee69, - 0x7d86, 0xee5d, 0x7d82, 0xee51, 0x7d7f, 0xee45, 0x7d7b, 0xee39, - 0x7d78, 0xee2d, 0x7d74, 0xee21, 0x7d71, 0xee15, 0x7d6d, 0xee09, - 0x7d6a, 0xedfc, 0x7d66, 0xedf0, 0x7d63, 0xede4, 0x7d5f, 0xedd8, - 0x7d5b, 0xedcc, 0x7d58, 0xedc0, 0x7d54, 0xedb4, 0x7d51, 0xeda8, - 0x7d4d, 0xed9c, 0x7d49, 0xed90, 0x7d46, 0xed84, 0x7d42, 0xed78, - 0x7d3f, 0xed6c, 0x7d3b, 0xed60, 0x7d37, 0xed54, 0x7d34, 0xed48, - 0x7d30, 0xed3c, 0x7d2c, 0xed30, 0x7d28, 0xed24, 0x7d25, 0xed18, - 0x7d21, 0xed0c, 0x7d1d, 0xed00, 0x7d1a, 0xecf4, 0x7d16, 0xece8, - 0x7d12, 0xecdc, 0x7d0e, 0xecd0, 0x7d0b, 0xecc4, 0x7d07, 0xecb8, - 0x7d03, 0xecac, 0x7cff, 0xeca0, 0x7cfb, 0xec94, 0x7cf8, 0xec88, - 0x7cf4, 0xec7c, 0x7cf0, 0xec70, 0x7cec, 0xec64, 0x7ce8, 0xec58, - 0x7ce4, 0xec4c, 0x7ce0, 0xec40, 0x7cdd, 0xec34, 0x7cd9, 0xec28, - 0x7cd5, 0xec1c, 0x7cd1, 0xec10, 0x7ccd, 0xec05, 0x7cc9, 0xebf9, - 0x7cc5, 0xebed, 0x7cc1, 0xebe1, 0x7cbd, 0xebd5, 0x7cb9, 0xebc9, - 0x7cb5, 0xebbd, 0x7cb1, 0xebb1, 0x7cad, 0xeba5, 0x7ca9, 0xeb99, - 0x7ca5, 0xeb8d, 0x7ca1, 0xeb81, 0x7c9d, 0xeb75, 0x7c99, 0xeb6a, - 0x7c95, 0xeb5e, 0x7c91, 0xeb52, 0x7c8d, 0xeb46, 0x7c89, 0xeb3a, - 0x7c85, 0xeb2e, 0x7c81, 0xeb22, 0x7c7d, 0xeb16, 0x7c79, 0xeb0a, - 0x7c74, 0xeaff, 0x7c70, 0xeaf3, 0x7c6c, 0xeae7, 0x7c68, 0xeadb, - 0x7c64, 0xeacf, 0x7c60, 0xeac3, 0x7c5b, 0xeab7, 0x7c57, 0xeaac, - 0x7c53, 0xeaa0, 0x7c4f, 0xea94, 0x7c4b, 0xea88, 0x7c46, 0xea7c, - 0x7c42, 0xea70, 0x7c3e, 0xea65, 0x7c3a, 0xea59, 0x7c36, 0xea4d, - 0x7c31, 0xea41, 0x7c2d, 0xea35, 0x7c29, 0xea29, 0x7c24, 0xea1e, - 0x7c20, 0xea12, 0x7c1c, 0xea06, 0x7c17, 0xe9fa, 0x7c13, 0xe9ee, - 0x7c0f, 0xe9e3, 0x7c0a, 0xe9d7, 0x7c06, 0xe9cb, 0x7c02, 0xe9bf, - 0x7bfd, 0xe9b4, 0x7bf9, 0xe9a8, 0x7bf5, 0xe99c, 0x7bf0, 0xe990, - 0x7bec, 0xe984, 0x7be7, 0xe979, 0x7be3, 0xe96d, 0x7bde, 0xe961, - 0x7bda, 0xe955, 0x7bd6, 0xe94a, 0x7bd1, 0xe93e, 0x7bcd, 0xe932, - 0x7bc8, 0xe926, 0x7bc4, 0xe91b, 0x7bbf, 0xe90f, 0x7bbb, 0xe903, - 0x7bb6, 0xe8f7, 0x7bb2, 0xe8ec, 0x7bad, 0xe8e0, 0x7ba9, 0xe8d4, - 0x7ba4, 0xe8c9, 0x7b9f, 0xe8bd, 0x7b9b, 0xe8b1, 0x7b96, 0xe8a5, - 0x7b92, 0xe89a, 0x7b8d, 0xe88e, 0x7b88, 0xe882, 0x7b84, 0xe877, - 0x7b7f, 0xe86b, 0x7b7b, 0xe85f, 0x7b76, 0xe854, 0x7b71, 0xe848, - 0x7b6d, 0xe83c, 0x7b68, 0xe831, 0x7b63, 0xe825, 0x7b5f, 0xe819, - 0x7b5a, 0xe80e, 0x7b55, 0xe802, 0x7b50, 0xe7f6, 0x7b4c, 0xe7eb, - 0x7b47, 0xe7df, 0x7b42, 0xe7d3, 0x7b3e, 0xe7c8, 0x7b39, 0xe7bc, - 0x7b34, 0xe7b1, 0x7b2f, 0xe7a5, 0x7b2a, 0xe799, 0x7b26, 0xe78e, - 0x7b21, 0xe782, 0x7b1c, 0xe777, 0x7b17, 0xe76b, 0x7b12, 0xe75f, - 0x7b0e, 0xe754, 0x7b09, 0xe748, 0x7b04, 0xe73d, 0x7aff, 0xe731, - 0x7afa, 0xe725, 0x7af5, 0xe71a, 0x7af0, 0xe70e, 0x7aeb, 0xe703, - 0x7ae6, 0xe6f7, 0x7ae2, 0xe6ec, 0x7add, 0xe6e0, 0x7ad8, 0xe6d4, - 0x7ad3, 0xe6c9, 0x7ace, 0xe6bd, 0x7ac9, 0xe6b2, 0x7ac4, 0xe6a6, - 0x7abf, 0xe69b, 0x7aba, 0xe68f, 0x7ab5, 0xe684, 0x7ab0, 0xe678, - 0x7aab, 0xe66d, 0x7aa6, 0xe661, 0x7aa1, 0xe656, 0x7a9c, 0xe64a, - 0x7a97, 0xe63f, 0x7a92, 0xe633, 0x7a8d, 0xe628, 0x7a88, 0xe61c, - 0x7a82, 0xe611, 0x7a7d, 0xe605, 0x7a78, 0xe5fa, 0x7a73, 0xe5ee, - 0x7a6e, 0xe5e3, 0x7a69, 0xe5d7, 0x7a64, 0xe5cc, 0x7a5f, 0xe5c0, - 0x7a59, 0xe5b5, 0x7a54, 0xe5a9, 0x7a4f, 0xe59e, 0x7a4a, 0xe592, - 0x7a45, 0xe587, 0x7a3f, 0xe57c, 0x7a3a, 0xe570, 0x7a35, 0xe565, - 0x7a30, 0xe559, 0x7a2b, 0xe54e, 0x7a25, 0xe542, 0x7a20, 0xe537, - 0x7a1b, 0xe52c, 0x7a16, 0xe520, 0x7a10, 0xe515, 0x7a0b, 0xe509, - 0x7a06, 0xe4fe, 0x7a00, 0xe4f3, 0x79fb, 0xe4e7, 0x79f6, 0xe4dc, - 0x79f0, 0xe4d0, 0x79eb, 0xe4c5, 0x79e6, 0xe4ba, 0x79e0, 0xe4ae, - 0x79db, 0xe4a3, 0x79d6, 0xe498, 0x79d0, 0xe48c, 0x79cb, 0xe481, - 0x79c5, 0xe476, 0x79c0, 0xe46a, 0x79bb, 0xe45f, 0x79b5, 0xe454, - 0x79b0, 0xe448, 0x79aa, 0xe43d, 0x79a5, 0xe432, 0x799f, 0xe426, - 0x799a, 0xe41b, 0x7994, 0xe410, 0x798f, 0xe404, 0x7989, 0xe3f9, - 0x7984, 0xe3ee, 0x797e, 0xe3e2, 0x7979, 0xe3d7, 0x7973, 0xe3cc, - 0x796e, 0xe3c1, 0x7968, 0xe3b5, 0x7963, 0xe3aa, 0x795d, 0xe39f, - 0x7958, 0xe394, 0x7952, 0xe388, 0x794c, 0xe37d, 0x7947, 0xe372, - 0x7941, 0xe367, 0x793b, 0xe35b, 0x7936, 0xe350, 0x7930, 0xe345, - 0x792b, 0xe33a, 0x7925, 0xe32e, 0x791f, 0xe323, 0x791a, 0xe318, - 0x7914, 0xe30d, 0x790e, 0xe301, 0x7909, 0xe2f6, 0x7903, 0xe2eb, - 0x78fd, 0xe2e0, 0x78f7, 0xe2d5, 0x78f2, 0xe2ca, 0x78ec, 0xe2be, - 0x78e6, 0xe2b3, 0x78e0, 0xe2a8, 0x78db, 0xe29d, 0x78d5, 0xe292, - 0x78cf, 0xe287, 0x78c9, 0xe27b, 0x78c3, 0xe270, 0x78be, 0xe265, - 0x78b8, 0xe25a, 0x78b2, 0xe24f, 0x78ac, 0xe244, 0x78a6, 0xe239, - 0x78a1, 0xe22d, 0x789b, 0xe222, 0x7895, 0xe217, 0x788f, 0xe20c, - 0x7889, 0xe201, 0x7883, 0xe1f6, 0x787d, 0xe1eb, 0x7877, 0xe1e0, - 0x7871, 0xe1d5, 0x786b, 0xe1ca, 0x7866, 0xe1be, 0x7860, 0xe1b3, - 0x785a, 0xe1a8, 0x7854, 0xe19d, 0x784e, 0xe192, 0x7848, 0xe187, - 0x7842, 0xe17c, 0x783c, 0xe171, 0x7836, 0xe166, 0x7830, 0xe15b, - 0x782a, 0xe150, 0x7824, 0xe145, 0x781e, 0xe13a, 0x7818, 0xe12f, - 0x7812, 0xe124, 0x780b, 0xe119, 0x7805, 0xe10e, 0x77ff, 0xe103, - 0x77f9, 0xe0f8, 0x77f3, 0xe0ed, 0x77ed, 0xe0e2, 0x77e7, 0xe0d7, - 0x77e1, 0xe0cc, 0x77db, 0xe0c1, 0x77d5, 0xe0b6, 0x77ce, 0xe0ab, - 0x77c8, 0xe0a0, 0x77c2, 0xe095, 0x77bc, 0xe08a, 0x77b6, 0xe07f, - 0x77b0, 0xe074, 0x77a9, 0xe069, 0x77a3, 0xe05e, 0x779d, 0xe054, - 0x7797, 0xe049, 0x7790, 0xe03e, 0x778a, 0xe033, 0x7784, 0xe028, - 0x777e, 0xe01d, 0x7777, 0xe012, 0x7771, 0xe007, 0x776b, 0xdffc, - 0x7765, 0xdff1, 0x775e, 0xdfe7, 0x7758, 0xdfdc, 0x7752, 0xdfd1, - 0x774b, 0xdfc6, 0x7745, 0xdfbb, 0x773f, 0xdfb0, 0x7738, 0xdfa5, - 0x7732, 0xdf9b, 0x772c, 0xdf90, 0x7725, 0xdf85, 0x771f, 0xdf7a, - 0x7718, 0xdf6f, 0x7712, 0xdf65, 0x770c, 0xdf5a, 0x7705, 0xdf4f, - 0x76ff, 0xdf44, 0x76f8, 0xdf39, 0x76f2, 0xdf2f, 0x76eb, 0xdf24, - 0x76e5, 0xdf19, 0x76df, 0xdf0e, 0x76d8, 0xdf03, 0x76d2, 0xdef9, - 0x76cb, 0xdeee, 0x76c5, 0xdee3, 0x76be, 0xded8, 0x76b8, 0xdece, - 0x76b1, 0xdec3, 0x76ab, 0xdeb8, 0x76a4, 0xdead, 0x769d, 0xdea3, - 0x7697, 0xde98, 0x7690, 0xde8d, 0x768a, 0xde83, 0x7683, 0xde78, - 0x767d, 0xde6d, 0x7676, 0xde62, 0x766f, 0xde58, 0x7669, 0xde4d, - 0x7662, 0xde42, 0x765c, 0xde38, 0x7655, 0xde2d, 0x764e, 0xde22, - 0x7648, 0xde18, 0x7641, 0xde0d, 0x763a, 0xde02, 0x7634, 0xddf8, - 0x762d, 0xdded, 0x7626, 0xdde2, 0x7620, 0xddd8, 0x7619, 0xddcd, - 0x7612, 0xddc3, 0x760b, 0xddb8, 0x7605, 0xddad, 0x75fe, 0xdda3, - 0x75f7, 0xdd98, 0x75f0, 0xdd8e, 0x75ea, 0xdd83, 0x75e3, 0xdd78, - 0x75dc, 0xdd6e, 0x75d5, 0xdd63, 0x75ce, 0xdd59, 0x75c8, 0xdd4e, - 0x75c1, 0xdd44, 0x75ba, 0xdd39, 0x75b3, 0xdd2e, 0x75ac, 0xdd24, - 0x75a5, 0xdd19, 0x759f, 0xdd0f, 0x7598, 0xdd04, 0x7591, 0xdcfa, - 0x758a, 0xdcef, 0x7583, 0xdce5, 0x757c, 0xdcda, 0x7575, 0xdcd0, - 0x756e, 0xdcc5, 0x7567, 0xdcbb, 0x7561, 0xdcb0, 0x755a, 0xdca6, - 0x7553, 0xdc9b, 0x754c, 0xdc91, 0x7545, 0xdc86, 0x753e, 0xdc7c, - 0x7537, 0xdc72, 0x7530, 0xdc67, 0x7529, 0xdc5d, 0x7522, 0xdc52, - 0x751b, 0xdc48, 0x7514, 0xdc3d, 0x750d, 0xdc33, 0x7506, 0xdc29, - 0x74ff, 0xdc1e, 0x74f8, 0xdc14, 0x74f1, 0xdc09, 0x74ea, 0xdbff, - 0x74e2, 0xdbf5, 0x74db, 0xdbea, 0x74d4, 0xdbe0, 0x74cd, 0xdbd5, - 0x74c6, 0xdbcb, 0x74bf, 0xdbc1, 0x74b8, 0xdbb6, 0x74b1, 0xdbac, - 0x74aa, 0xdba2, 0x74a2, 0xdb97, 0x749b, 0xdb8d, 0x7494, 0xdb83, - 0x748d, 0xdb78, 0x7486, 0xdb6e, 0x747f, 0xdb64, 0x7477, 0xdb59, - 0x7470, 0xdb4f, 0x7469, 0xdb45, 0x7462, 0xdb3b, 0x745b, 0xdb30, - 0x7453, 0xdb26, 0x744c, 0xdb1c, 0x7445, 0xdb11, 0x743e, 0xdb07, - 0x7436, 0xdafd, 0x742f, 0xdaf3, 0x7428, 0xdae8, 0x7420, 0xdade, - 0x7419, 0xdad4, 0x7412, 0xdaca, 0x740b, 0xdabf, 0x7403, 0xdab5, - 0x73fc, 0xdaab, 0x73f5, 0xdaa1, 0x73ed, 0xda97, 0x73e6, 0xda8c, - 0x73df, 0xda82, 0x73d7, 0xda78, 0x73d0, 0xda6e, 0x73c8, 0xda64, - 0x73c1, 0xda5a, 0x73ba, 0xda4f, 0x73b2, 0xda45, 0x73ab, 0xda3b, - 0x73a3, 0xda31, 0x739c, 0xda27, 0x7395, 0xda1d, 0x738d, 0xda13, - 0x7386, 0xda08, 0x737e, 0xd9fe, 0x7377, 0xd9f4, 0x736f, 0xd9ea, - 0x7368, 0xd9e0, 0x7360, 0xd9d6, 0x7359, 0xd9cc, 0x7351, 0xd9c2, - 0x734a, 0xd9b8, 0x7342, 0xd9ae, 0x733b, 0xd9a4, 0x7333, 0xd99a, - 0x732c, 0xd98f, 0x7324, 0xd985, 0x731d, 0xd97b, 0x7315, 0xd971, - 0x730d, 0xd967, 0x7306, 0xd95d, 0x72fe, 0xd953, 0x72f7, 0xd949, - 0x72ef, 0xd93f, 0x72e7, 0xd935, 0x72e0, 0xd92b, 0x72d8, 0xd921, - 0x72d0, 0xd917, 0x72c9, 0xd90d, 0x72c1, 0xd903, 0x72ba, 0xd8f9, - 0x72b2, 0xd8ef, 0x72aa, 0xd8e6, 0x72a3, 0xd8dc, 0x729b, 0xd8d2, - 0x7293, 0xd8c8, 0x728b, 0xd8be, 0x7284, 0xd8b4, 0x727c, 0xd8aa, - 0x7274, 0xd8a0, 0x726d, 0xd896, 0x7265, 0xd88c, 0x725d, 0xd882, - 0x7255, 0xd878, 0x724e, 0xd86f, 0x7246, 0xd865, 0x723e, 0xd85b, - 0x7236, 0xd851, 0x722e, 0xd847, 0x7227, 0xd83d, 0x721f, 0xd833, - 0x7217, 0xd82a, 0x720f, 0xd820, 0x7207, 0xd816, 0x71ff, 0xd80c, - 0x71f8, 0xd802, 0x71f0, 0xd7f8, 0x71e8, 0xd7ef, 0x71e0, 0xd7e5, - 0x71d8, 0xd7db, 0x71d0, 0xd7d1, 0x71c8, 0xd7c8, 0x71c0, 0xd7be, - 0x71b9, 0xd7b4, 0x71b1, 0xd7aa, 0x71a9, 0xd7a0, 0x71a1, 0xd797, - 0x7199, 0xd78d, 0x7191, 0xd783, 0x7189, 0xd77a, 0x7181, 0xd770, - 0x7179, 0xd766, 0x7171, 0xd75c, 0x7169, 0xd753, 0x7161, 0xd749, - 0x7159, 0xd73f, 0x7151, 0xd736, 0x7149, 0xd72c, 0x7141, 0xd722, - 0x7139, 0xd719, 0x7131, 0xd70f, 0x7129, 0xd705, 0x7121, 0xd6fc, - 0x7119, 0xd6f2, 0x7111, 0xd6e8, 0x7109, 0xd6df, 0x7101, 0xd6d5, - 0x70f9, 0xd6cb, 0x70f0, 0xd6c2, 0x70e8, 0xd6b8, 0x70e0, 0xd6af, - 0x70d8, 0xd6a5, 0x70d0, 0xd69b, 0x70c8, 0xd692, 0x70c0, 0xd688, - 0x70b8, 0xd67f, 0x70af, 0xd675, 0x70a7, 0xd66c, 0x709f, 0xd662, - 0x7097, 0xd659, 0x708f, 0xd64f, 0x7087, 0xd645, 0x707e, 0xd63c, - 0x7076, 0xd632, 0x706e, 0xd629, 0x7066, 0xd61f, 0x705d, 0xd616, - 0x7055, 0xd60c, 0x704d, 0xd603, 0x7045, 0xd5f9, 0x703c, 0xd5f0, - 0x7034, 0xd5e6, 0x702c, 0xd5dd, 0x7024, 0xd5d4, 0x701b, 0xd5ca, - 0x7013, 0xd5c1, 0x700b, 0xd5b7, 0x7002, 0xd5ae, 0x6ffa, 0xd5a4, - 0x6ff2, 0xd59b, 0x6fea, 0xd592, 0x6fe1, 0xd588, 0x6fd9, 0xd57f, - 0x6fd0, 0xd575, 0x6fc8, 0xd56c, 0x6fc0, 0xd563, 0x6fb7, 0xd559, - 0x6faf, 0xd550, 0x6fa7, 0xd547, 0x6f9e, 0xd53d, 0x6f96, 0xd534, - 0x6f8d, 0xd52a, 0x6f85, 0xd521, 0x6f7d, 0xd518, 0x6f74, 0xd50e, - 0x6f6c, 0xd505, 0x6f63, 0xd4fc, 0x6f5b, 0xd4f3, 0x6f52, 0xd4e9, - 0x6f4a, 0xd4e0, 0x6f41, 0xd4d7, 0x6f39, 0xd4cd, 0x6f30, 0xd4c4, - 0x6f28, 0xd4bb, 0x6f20, 0xd4b2, 0x6f17, 0xd4a8, 0x6f0e, 0xd49f, - 0x6f06, 0xd496, 0x6efd, 0xd48d, 0x6ef5, 0xd483, 0x6eec, 0xd47a, - 0x6ee4, 0xd471, 0x6edb, 0xd468, 0x6ed3, 0xd45f, 0x6eca, 0xd455, - 0x6ec2, 0xd44c, 0x6eb9, 0xd443, 0x6eb0, 0xd43a, 0x6ea8, 0xd431, - 0x6e9f, 0xd428, 0x6e97, 0xd41e, 0x6e8e, 0xd415, 0x6e85, 0xd40c, - 0x6e7d, 0xd403, 0x6e74, 0xd3fa, 0x6e6b, 0xd3f1, 0x6e63, 0xd3e8, - 0x6e5a, 0xd3df, 0x6e51, 0xd3d5, 0x6e49, 0xd3cc, 0x6e40, 0xd3c3, - 0x6e37, 0xd3ba, 0x6e2f, 0xd3b1, 0x6e26, 0xd3a8, 0x6e1d, 0xd39f, - 0x6e15, 0xd396, 0x6e0c, 0xd38d, 0x6e03, 0xd384, 0x6dfa, 0xd37b, - 0x6df2, 0xd372, 0x6de9, 0xd369, 0x6de0, 0xd360, 0x6dd7, 0xd357, - 0x6dcf, 0xd34e, 0x6dc6, 0xd345, 0x6dbd, 0xd33c, 0x6db4, 0xd333, - 0x6dab, 0xd32a, 0x6da3, 0xd321, 0x6d9a, 0xd318, 0x6d91, 0xd30f, - 0x6d88, 0xd306, 0x6d7f, 0xd2fd, 0x6d76, 0xd2f4, 0x6d6e, 0xd2eb, - 0x6d65, 0xd2e2, 0x6d5c, 0xd2d9, 0x6d53, 0xd2d1, 0x6d4a, 0xd2c8, - 0x6d41, 0xd2bf, 0x6d38, 0xd2b6, 0x6d2f, 0xd2ad, 0x6d27, 0xd2a4, - 0x6d1e, 0xd29b, 0x6d15, 0xd292, 0x6d0c, 0xd28a, 0x6d03, 0xd281, - 0x6cfa, 0xd278, 0x6cf1, 0xd26f, 0x6ce8, 0xd266, 0x6cdf, 0xd25d, - 0x6cd6, 0xd255, 0x6ccd, 0xd24c, 0x6cc4, 0xd243, 0x6cbb, 0xd23a, - 0x6cb2, 0xd231, 0x6ca9, 0xd229, 0x6ca0, 0xd220, 0x6c97, 0xd217, - 0x6c8e, 0xd20e, 0x6c85, 0xd206, 0x6c7c, 0xd1fd, 0x6c73, 0xd1f4, - 0x6c6a, 0xd1eb, 0x6c61, 0xd1e3, 0x6c58, 0xd1da, 0x6c4f, 0xd1d1, - 0x6c46, 0xd1c9, 0x6c3d, 0xd1c0, 0x6c34, 0xd1b7, 0x6c2b, 0xd1af, - 0x6c21, 0xd1a6, 0x6c18, 0xd19d, 0x6c0f, 0xd195, 0x6c06, 0xd18c, - 0x6bfd, 0xd183, 0x6bf4, 0xd17b, 0x6beb, 0xd172, 0x6be2, 0xd169, - 0x6bd8, 0xd161, 0x6bcf, 0xd158, 0x6bc6, 0xd150, 0x6bbd, 0xd147, - 0x6bb4, 0xd13e, 0x6bab, 0xd136, 0x6ba1, 0xd12d, 0x6b98, 0xd125, - 0x6b8f, 0xd11c, 0x6b86, 0xd114, 0x6b7d, 0xd10b, 0x6b73, 0xd103, - 0x6b6a, 0xd0fa, 0x6b61, 0xd0f2, 0x6b58, 0xd0e9, 0x6b4e, 0xd0e0, - 0x6b45, 0xd0d8, 0x6b3c, 0xd0d0, 0x6b33, 0xd0c7, 0x6b29, 0xd0bf, - 0x6b20, 0xd0b6, 0x6b17, 0xd0ae, 0x6b0d, 0xd0a5, 0x6b04, 0xd09d, - 0x6afb, 0xd094, 0x6af2, 0xd08c, 0x6ae8, 0xd083, 0x6adf, 0xd07b, - 0x6ad6, 0xd073, 0x6acc, 0xd06a, 0x6ac3, 0xd062, 0x6ab9, 0xd059, - 0x6ab0, 0xd051, 0x6aa7, 0xd049, 0x6a9d, 0xd040, 0x6a94, 0xd038, - 0x6a8b, 0xd030, 0x6a81, 0xd027, 0x6a78, 0xd01f, 0x6a6e, 0xd016, - 0x6a65, 0xd00e, 0x6a5c, 0xd006, 0x6a52, 0xcffe, 0x6a49, 0xcff5, - 0x6a3f, 0xcfed, 0x6a36, 0xcfe5, 0x6a2c, 0xcfdc, 0x6a23, 0xcfd4, - 0x6a1a, 0xcfcc, 0x6a10, 0xcfc4, 0x6a07, 0xcfbb, 0x69fd, 0xcfb3, - 0x69f4, 0xcfab, 0x69ea, 0xcfa3, 0x69e1, 0xcf9a, 0x69d7, 0xcf92, - 0x69ce, 0xcf8a, 0x69c4, 0xcf82, 0x69bb, 0xcf79, 0x69b1, 0xcf71, - 0x69a7, 0xcf69, 0x699e, 0xcf61, 0x6994, 0xcf59, 0x698b, 0xcf51, - 0x6981, 0xcf48, 0x6978, 0xcf40, 0x696e, 0xcf38, 0x6965, 0xcf30, - 0x695b, 0xcf28, 0x6951, 0xcf20, 0x6948, 0xcf18, 0x693e, 0xcf10, - 0x6935, 0xcf07, 0x692b, 0xceff, 0x6921, 0xcef7, 0x6918, 0xceef, - 0x690e, 0xcee7, 0x6904, 0xcedf, 0x68fb, 0xced7, 0x68f1, 0xcecf, - 0x68e7, 0xcec7, 0x68de, 0xcebf, 0x68d4, 0xceb7, 0x68ca, 0xceaf, - 0x68c1, 0xcea7, 0x68b7, 0xce9f, 0x68ad, 0xce97, 0x68a4, 0xce8f, - 0x689a, 0xce87, 0x6890, 0xce7f, 0x6886, 0xce77, 0x687d, 0xce6f, - 0x6873, 0xce67, 0x6869, 0xce5f, 0x6860, 0xce57, 0x6856, 0xce4f, - 0x684c, 0xce47, 0x6842, 0xce40, 0x6838, 0xce38, 0x682f, 0xce30, - 0x6825, 0xce28, 0x681b, 0xce20, 0x6811, 0xce18, 0x6808, 0xce10, - 0x67fe, 0xce08, 0x67f4, 0xce01, 0x67ea, 0xcdf9, 0x67e0, 0xcdf1, - 0x67d6, 0xcde9, 0x67cd, 0xcde1, 0x67c3, 0xcdd9, 0x67b9, 0xcdd2, - 0x67af, 0xcdca, 0x67a5, 0xcdc2, 0x679b, 0xcdba, 0x6791, 0xcdb2, - 0x6788, 0xcdab, 0x677e, 0xcda3, 0x6774, 0xcd9b, 0x676a, 0xcd93, - 0x6760, 0xcd8c, 0x6756, 0xcd84, 0x674c, 0xcd7c, 0x6742, 0xcd75, - 0x6738, 0xcd6d, 0x672e, 0xcd65, 0x6724, 0xcd5d, 0x671a, 0xcd56, - 0x6711, 0xcd4e, 0x6707, 0xcd46, 0x66fd, 0xcd3f, 0x66f3, 0xcd37, - 0x66e9, 0xcd30, 0x66df, 0xcd28, 0x66d5, 0xcd20, 0x66cb, 0xcd19, - 0x66c1, 0xcd11, 0x66b7, 0xcd09, 0x66ad, 0xcd02, 0x66a3, 0xccfa, - 0x6699, 0xccf3, 0x668f, 0xcceb, 0x6685, 0xcce3, 0x667b, 0xccdc, - 0x6671, 0xccd4, 0x6666, 0xcccd, 0x665c, 0xccc5, 0x6652, 0xccbe, - 0x6648, 0xccb6, 0x663e, 0xccaf, 0x6634, 0xcca7, 0x662a, 0xcca0, - 0x6620, 0xcc98, 0x6616, 0xcc91, 0x660c, 0xcc89, 0x6602, 0xcc82, - 0x65f8, 0xcc7a, 0x65ed, 0xcc73, 0x65e3, 0xcc6b, 0x65d9, 0xcc64, - 0x65cf, 0xcc5d, 0x65c5, 0xcc55, 0x65bb, 0xcc4e, 0x65b1, 0xcc46, - 0x65a6, 0xcc3f, 0x659c, 0xcc38, 0x6592, 0xcc30, 0x6588, 0xcc29, - 0x657e, 0xcc21, 0x6574, 0xcc1a, 0x6569, 0xcc13, 0x655f, 0xcc0b, - 0x6555, 0xcc04, 0x654b, 0xcbfd, 0x6541, 0xcbf5, 0x6536, 0xcbee, - 0x652c, 0xcbe7, 0x6522, 0xcbe0, 0x6518, 0xcbd8, 0x650d, 0xcbd1, - 0x6503, 0xcbca, 0x64f9, 0xcbc2, 0x64ef, 0xcbbb, 0x64e4, 0xcbb4, - 0x64da, 0xcbad, 0x64d0, 0xcba5, 0x64c5, 0xcb9e, 0x64bb, 0xcb97, - 0x64b1, 0xcb90, 0x64a7, 0xcb89, 0x649c, 0xcb81, 0x6492, 0xcb7a, - 0x6488, 0xcb73, 0x647d, 0xcb6c, 0x6473, 0xcb65, 0x6469, 0xcb5e, - 0x645e, 0xcb56, 0x6454, 0xcb4f, 0x644a, 0xcb48, 0x643f, 0xcb41, - 0x6435, 0xcb3a, 0x642b, 0xcb33, 0x6420, 0xcb2c, 0x6416, 0xcb25, - 0x640b, 0xcb1e, 0x6401, 0xcb16, 0x63f7, 0xcb0f, 0x63ec, 0xcb08, - 0x63e2, 0xcb01, 0x63d7, 0xcafa, 0x63cd, 0xcaf3, 0x63c3, 0xcaec, - 0x63b8, 0xcae5, 0x63ae, 0xcade, 0x63a3, 0xcad7, 0x6399, 0xcad0, - 0x638e, 0xcac9, 0x6384, 0xcac2, 0x637a, 0xcabb, 0x636f, 0xcab4, - 0x6365, 0xcaad, 0x635a, 0xcaa6, 0x6350, 0xca9f, 0x6345, 0xca99, - 0x633b, 0xca92, 0x6330, 0xca8b, 0x6326, 0xca84, 0x631b, 0xca7d, - 0x6311, 0xca76, 0x6306, 0xca6f, 0x62fc, 0xca68, 0x62f1, 0xca61, - 0x62e7, 0xca5b, 0x62dc, 0xca54, 0x62d2, 0xca4d, 0x62c7, 0xca46, - 0x62bc, 0xca3f, 0x62b2, 0xca38, 0x62a7, 0xca32, 0x629d, 0xca2b, - 0x6292, 0xca24, 0x6288, 0xca1d, 0x627d, 0xca16, 0x6272, 0xca10, - 0x6268, 0xca09, 0x625d, 0xca02, 0x6253, 0xc9fb, 0x6248, 0xc9f5, - 0x623d, 0xc9ee, 0x6233, 0xc9e7, 0x6228, 0xc9e0, 0x621e, 0xc9da, - 0x6213, 0xc9d3, 0x6208, 0xc9cc, 0x61fe, 0xc9c6, 0x61f3, 0xc9bf, - 0x61e8, 0xc9b8, 0x61de, 0xc9b2, 0x61d3, 0xc9ab, 0x61c8, 0xc9a4, - 0x61be, 0xc99e, 0x61b3, 0xc997, 0x61a8, 0xc991, 0x619e, 0xc98a, - 0x6193, 0xc983, 0x6188, 0xc97d, 0x617d, 0xc976, 0x6173, 0xc970, - 0x6168, 0xc969, 0x615d, 0xc963, 0x6153, 0xc95c, 0x6148, 0xc955, - 0x613d, 0xc94f, 0x6132, 0xc948, 0x6128, 0xc942, 0x611d, 0xc93b, - 0x6112, 0xc935, 0x6107, 0xc92e, 0x60fd, 0xc928, 0x60f2, 0xc921, - 0x60e7, 0xc91b, 0x60dc, 0xc915, 0x60d1, 0xc90e, 0x60c7, 0xc908, - 0x60bc, 0xc901, 0x60b1, 0xc8fb, 0x60a6, 0xc8f4, 0x609b, 0xc8ee, - 0x6091, 0xc8e8, 0x6086, 0xc8e1, 0x607b, 0xc8db, 0x6070, 0xc8d4, - 0x6065, 0xc8ce, 0x605b, 0xc8c8, 0x6050, 0xc8c1, 0x6045, 0xc8bb, - 0x603a, 0xc8b5, 0x602f, 0xc8ae, 0x6024, 0xc8a8, 0x6019, 0xc8a2, - 0x600f, 0xc89b, 0x6004, 0xc895, 0x5ff9, 0xc88f, 0x5fee, 0xc889, - 0x5fe3, 0xc882, 0x5fd8, 0xc87c, 0x5fcd, 0xc876, 0x5fc2, 0xc870, - 0x5fb7, 0xc869, 0x5fac, 0xc863, 0x5fa2, 0xc85d, 0x5f97, 0xc857, - 0x5f8c, 0xc850, 0x5f81, 0xc84a, 0x5f76, 0xc844, 0x5f6b, 0xc83e, - 0x5f60, 0xc838, 0x5f55, 0xc832, 0x5f4a, 0xc82b, 0x5f3f, 0xc825, - 0x5f34, 0xc81f, 0x5f29, 0xc819, 0x5f1e, 0xc813, 0x5f13, 0xc80d, - 0x5f08, 0xc807, 0x5efd, 0xc801, 0x5ef2, 0xc7fb, 0x5ee7, 0xc7f5, - 0x5edc, 0xc7ee, 0x5ed1, 0xc7e8, 0x5ec6, 0xc7e2, 0x5ebb, 0xc7dc, - 0x5eb0, 0xc7d6, 0x5ea5, 0xc7d0, 0x5e9a, 0xc7ca, 0x5e8f, 0xc7c4, - 0x5e84, 0xc7be, 0x5e79, 0xc7b8, 0x5e6e, 0xc7b2, 0x5e63, 0xc7ac, - 0x5e58, 0xc7a6, 0x5e4d, 0xc7a0, 0x5e42, 0xc79a, 0x5e36, 0xc795, - 0x5e2b, 0xc78f, 0x5e20, 0xc789, 0x5e15, 0xc783, 0x5e0a, 0xc77d, - 0x5dff, 0xc777, 0x5df4, 0xc771, 0x5de9, 0xc76b, 0x5dde, 0xc765, - 0x5dd3, 0xc75f, 0x5dc7, 0xc75a, 0x5dbc, 0xc754, 0x5db1, 0xc74e, - 0x5da6, 0xc748, 0x5d9b, 0xc742, 0x5d90, 0xc73d, 0x5d85, 0xc737, - 0x5d79, 0xc731, 0x5d6e, 0xc72b, 0x5d63, 0xc725, 0x5d58, 0xc720, - 0x5d4d, 0xc71a, 0x5d42, 0xc714, 0x5d36, 0xc70e, 0x5d2b, 0xc709, - 0x5d20, 0xc703, 0x5d15, 0xc6fd, 0x5d0a, 0xc6f7, 0x5cff, 0xc6f2, - 0x5cf3, 0xc6ec, 0x5ce8, 0xc6e6, 0x5cdd, 0xc6e1, 0x5cd2, 0xc6db, - 0x5cc6, 0xc6d5, 0x5cbb, 0xc6d0, 0x5cb0, 0xc6ca, 0x5ca5, 0xc6c5, - 0x5c99, 0xc6bf, 0x5c8e, 0xc6b9, 0x5c83, 0xc6b4, 0x5c78, 0xc6ae, - 0x5c6c, 0xc6a8, 0x5c61, 0xc6a3, 0x5c56, 0xc69d, 0x5c4b, 0xc698, - 0x5c3f, 0xc692, 0x5c34, 0xc68d, 0x5c29, 0xc687, 0x5c1e, 0xc682, - 0x5c12, 0xc67c, 0x5c07, 0xc677, 0x5bfc, 0xc671, 0x5bf0, 0xc66c, - 0x5be5, 0xc666, 0x5bda, 0xc661, 0x5bce, 0xc65b, 0x5bc3, 0xc656, - 0x5bb8, 0xc650, 0x5bac, 0xc64b, 0x5ba1, 0xc645, 0x5b96, 0xc640, - 0x5b8a, 0xc63b, 0x5b7f, 0xc635, 0x5b74, 0xc630, 0x5b68, 0xc62a, - 0x5b5d, 0xc625, 0x5b52, 0xc620, 0x5b46, 0xc61a, 0x5b3b, 0xc615, - 0x5b30, 0xc610, 0x5b24, 0xc60a, 0x5b19, 0xc605, 0x5b0d, 0xc600, - 0x5b02, 0xc5fa, 0x5af7, 0xc5f5, 0x5aeb, 0xc5f0, 0x5ae0, 0xc5ea, - 0x5ad4, 0xc5e5, 0x5ac9, 0xc5e0, 0x5abe, 0xc5db, 0x5ab2, 0xc5d5, - 0x5aa7, 0xc5d0, 0x5a9b, 0xc5cb, 0x5a90, 0xc5c6, 0x5a84, 0xc5c1, - 0x5a79, 0xc5bb, 0x5a6e, 0xc5b6, 0x5a62, 0xc5b1, 0x5a57, 0xc5ac, - 0x5a4b, 0xc5a7, 0x5a40, 0xc5a1, 0x5a34, 0xc59c, 0x5a29, 0xc597, - 0x5a1d, 0xc592, 0x5a12, 0xc58d, 0x5a06, 0xc588, 0x59fb, 0xc583, - 0x59ef, 0xc57e, 0x59e4, 0xc578, 0x59d8, 0xc573, 0x59cd, 0xc56e, - 0x59c1, 0xc569, 0x59b6, 0xc564, 0x59aa, 0xc55f, 0x599f, 0xc55a, - 0x5993, 0xc555, 0x5988, 0xc550, 0x597c, 0xc54b, 0x5971, 0xc546, - 0x5965, 0xc541, 0x595a, 0xc53c, 0x594e, 0xc537, 0x5943, 0xc532, - 0x5937, 0xc52d, 0x592c, 0xc528, 0x5920, 0xc523, 0x5914, 0xc51e, - 0x5909, 0xc51a, 0x58fd, 0xc515, 0x58f2, 0xc510, 0x58e6, 0xc50b, - 0x58db, 0xc506, 0x58cf, 0xc501, 0x58c3, 0xc4fc, 0x58b8, 0xc4f7, - 0x58ac, 0xc4f2, 0x58a1, 0xc4ee, 0x5895, 0xc4e9, 0x5889, 0xc4e4, - 0x587e, 0xc4df, 0x5872, 0xc4da, 0x5867, 0xc4d6, 0x585b, 0xc4d1, - 0x584f, 0xc4cc, 0x5844, 0xc4c7, 0x5838, 0xc4c2, 0x582d, 0xc4be, - 0x5821, 0xc4b9, 0x5815, 0xc4b4, 0x580a, 0xc4b0, 0x57fe, 0xc4ab, - 0x57f2, 0xc4a6, 0x57e7, 0xc4a1, 0x57db, 0xc49d, 0x57cf, 0xc498, - 0x57c4, 0xc493, 0x57b8, 0xc48f, 0x57ac, 0xc48a, 0x57a1, 0xc485, - 0x5795, 0xc481, 0x5789, 0xc47c, 0x577e, 0xc478, 0x5772, 0xc473, - 0x5766, 0xc46e, 0x575b, 0xc46a, 0x574f, 0xc465, 0x5743, 0xc461, - 0x5737, 0xc45c, 0x572c, 0xc457, 0x5720, 0xc453, 0x5714, 0xc44e, - 0x5709, 0xc44a, 0x56fd, 0xc445, 0x56f1, 0xc441, 0x56e5, 0xc43c, - 0x56da, 0xc438, 0x56ce, 0xc433, 0x56c2, 0xc42f, 0x56b6, 0xc42a, - 0x56ab, 0xc426, 0x569f, 0xc422, 0x5693, 0xc41d, 0x5687, 0xc419, - 0x567c, 0xc414, 0x5670, 0xc410, 0x5664, 0xc40b, 0x5658, 0xc407, - 0x564c, 0xc403, 0x5641, 0xc3fe, 0x5635, 0xc3fa, 0x5629, 0xc3f6, - 0x561d, 0xc3f1, 0x5612, 0xc3ed, 0x5606, 0xc3e9, 0x55fa, 0xc3e4, - 0x55ee, 0xc3e0, 0x55e2, 0xc3dc, 0x55d7, 0xc3d7, 0x55cb, 0xc3d3, - 0x55bf, 0xc3cf, 0x55b3, 0xc3ca, 0x55a7, 0xc3c6, 0x559b, 0xc3c2, - 0x5590, 0xc3be, 0x5584, 0xc3ba, 0x5578, 0xc3b5, 0x556c, 0xc3b1, - 0x5560, 0xc3ad, 0x5554, 0xc3a9, 0x5549, 0xc3a5, 0x553d, 0xc3a0, - 0x5531, 0xc39c, 0x5525, 0xc398, 0x5519, 0xc394, 0x550d, 0xc390, - 0x5501, 0xc38c, 0x54f6, 0xc387, 0x54ea, 0xc383, 0x54de, 0xc37f, - 0x54d2, 0xc37b, 0x54c6, 0xc377, 0x54ba, 0xc373, 0x54ae, 0xc36f, - 0x54a2, 0xc36b, 0x5496, 0xc367, 0x548b, 0xc363, 0x547f, 0xc35f, - 0x5473, 0xc35b, 0x5467, 0xc357, 0x545b, 0xc353, 0x544f, 0xc34f, - 0x5443, 0xc34b, 0x5437, 0xc347, 0x542b, 0xc343, 0x541f, 0xc33f, - 0x5413, 0xc33b, 0x5407, 0xc337, 0x53fb, 0xc333, 0x53f0, 0xc32f, - 0x53e4, 0xc32b, 0x53d8, 0xc327, 0x53cc, 0xc323, 0x53c0, 0xc320, - 0x53b4, 0xc31c, 0x53a8, 0xc318, 0x539c, 0xc314, 0x5390, 0xc310, - 0x5384, 0xc30c, 0x5378, 0xc308, 0x536c, 0xc305, 0x5360, 0xc301, - 0x5354, 0xc2fd, 0x5348, 0xc2f9, 0x533c, 0xc2f5, 0x5330, 0xc2f2, - 0x5324, 0xc2ee, 0x5318, 0xc2ea, 0x530c, 0xc2e6, 0x5300, 0xc2e3, - 0x52f4, 0xc2df, 0x52e8, 0xc2db, 0x52dc, 0xc2d8, 0x52d0, 0xc2d4, - 0x52c4, 0xc2d0, 0x52b8, 0xc2cc, 0x52ac, 0xc2c9, 0x52a0, 0xc2c5, - 0x5294, 0xc2c1, 0x5288, 0xc2be, 0x527c, 0xc2ba, 0x5270, 0xc2b7, - 0x5264, 0xc2b3, 0x5258, 0xc2af, 0x524c, 0xc2ac, 0x5240, 0xc2a8, - 0x5234, 0xc2a5, 0x5228, 0xc2a1, 0x521c, 0xc29d, 0x5210, 0xc29a, - 0x5204, 0xc296, 0x51f7, 0xc293, 0x51eb, 0xc28f, 0x51df, 0xc28c, - 0x51d3, 0xc288, 0x51c7, 0xc285, 0x51bb, 0xc281, 0x51af, 0xc27e, - 0x51a3, 0xc27a, 0x5197, 0xc277, 0x518b, 0xc273, 0x517f, 0xc270, - 0x5173, 0xc26d, 0x5167, 0xc269, 0x515a, 0xc266, 0x514e, 0xc262, - 0x5142, 0xc25f, 0x5136, 0xc25c, 0x512a, 0xc258, 0x511e, 0xc255, - 0x5112, 0xc251, 0x5106, 0xc24e, 0x50fa, 0xc24b, 0x50ed, 0xc247, - 0x50e1, 0xc244, 0x50d5, 0xc241, 0x50c9, 0xc23e, 0x50bd, 0xc23a, - 0x50b1, 0xc237, 0x50a5, 0xc234, 0x5099, 0xc230, 0x508c, 0xc22d, - 0x5080, 0xc22a, 0x5074, 0xc227, 0x5068, 0xc223, 0x505c, 0xc220, - 0x5050, 0xc21d, 0x5044, 0xc21a, 0x5037, 0xc217, 0x502b, 0xc213, - 0x501f, 0xc210, 0x5013, 0xc20d, 0x5007, 0xc20a, 0x4ffb, 0xc207, - 0x4fee, 0xc204, 0x4fe2, 0xc201, 0x4fd6, 0xc1fd, 0x4fca, 0xc1fa, - 0x4fbe, 0xc1f7, 0x4fb2, 0xc1f4, 0x4fa5, 0xc1f1, 0x4f99, 0xc1ee, - 0x4f8d, 0xc1eb, 0x4f81, 0xc1e8, 0x4f75, 0xc1e5, 0x4f68, 0xc1e2, - 0x4f5c, 0xc1df, 0x4f50, 0xc1dc, 0x4f44, 0xc1d9, 0x4f38, 0xc1d6, - 0x4f2b, 0xc1d3, 0x4f1f, 0xc1d0, 0x4f13, 0xc1cd, 0x4f07, 0xc1ca, - 0x4efb, 0xc1c7, 0x4eee, 0xc1c4, 0x4ee2, 0xc1c1, 0x4ed6, 0xc1be, - 0x4eca, 0xc1bb, 0x4ebd, 0xc1b8, 0x4eb1, 0xc1b6, 0x4ea5, 0xc1b3, - 0x4e99, 0xc1b0, 0x4e8c, 0xc1ad, 0x4e80, 0xc1aa, 0x4e74, 0xc1a7, - 0x4e68, 0xc1a4, 0x4e5c, 0xc1a2, 0x4e4f, 0xc19f, 0x4e43, 0xc19c, - 0x4e37, 0xc199, 0x4e2b, 0xc196, 0x4e1e, 0xc194, 0x4e12, 0xc191, - 0x4e06, 0xc18e, 0x4df9, 0xc18b, 0x4ded, 0xc189, 0x4de1, 0xc186, - 0x4dd5, 0xc183, 0x4dc8, 0xc180, 0x4dbc, 0xc17e, 0x4db0, 0xc17b, - 0x4da4, 0xc178, 0x4d97, 0xc176, 0x4d8b, 0xc173, 0x4d7f, 0xc170, - 0x4d72, 0xc16e, 0x4d66, 0xc16b, 0x4d5a, 0xc168, 0x4d4e, 0xc166, - 0x4d41, 0xc163, 0x4d35, 0xc161, 0x4d29, 0xc15e, 0x4d1c, 0xc15b, - 0x4d10, 0xc159, 0x4d04, 0xc156, 0x4cf8, 0xc154, 0x4ceb, 0xc151, - 0x4cdf, 0xc14f, 0x4cd3, 0xc14c, 0x4cc6, 0xc14a, 0x4cba, 0xc147, - 0x4cae, 0xc145, 0x4ca1, 0xc142, 0x4c95, 0xc140, 0x4c89, 0xc13d, - 0x4c7c, 0xc13b, 0x4c70, 0xc138, 0x4c64, 0xc136, 0x4c57, 0xc134, - 0x4c4b, 0xc131, 0x4c3f, 0xc12f, 0x4c32, 0xc12c, 0x4c26, 0xc12a, - 0x4c1a, 0xc128, 0x4c0d, 0xc125, 0x4c01, 0xc123, 0x4bf5, 0xc120, - 0x4be8, 0xc11e, 0x4bdc, 0xc11c, 0x4bd0, 0xc119, 0x4bc3, 0xc117, - 0x4bb7, 0xc115, 0x4bab, 0xc113, 0x4b9e, 0xc110, 0x4b92, 0xc10e, - 0x4b85, 0xc10c, 0x4b79, 0xc109, 0x4b6d, 0xc107, 0x4b60, 0xc105, - 0x4b54, 0xc103, 0x4b48, 0xc100, 0x4b3b, 0xc0fe, 0x4b2f, 0xc0fc, - 0x4b23, 0xc0fa, 0x4b16, 0xc0f8, 0x4b0a, 0xc0f6, 0x4afd, 0xc0f3, - 0x4af1, 0xc0f1, 0x4ae5, 0xc0ef, 0x4ad8, 0xc0ed, 0x4acc, 0xc0eb, - 0x4ac0, 0xc0e9, 0x4ab3, 0xc0e7, 0x4aa7, 0xc0e4, 0x4a9a, 0xc0e2, - 0x4a8e, 0xc0e0, 0x4a82, 0xc0de, 0x4a75, 0xc0dc, 0x4a69, 0xc0da, - 0x4a5c, 0xc0d8, 0x4a50, 0xc0d6, 0x4a44, 0xc0d4, 0x4a37, 0xc0d2, - 0x4a2b, 0xc0d0, 0x4a1e, 0xc0ce, 0x4a12, 0xc0cc, 0x4a06, 0xc0ca, - 0x49f9, 0xc0c8, 0x49ed, 0xc0c6, 0x49e0, 0xc0c4, 0x49d4, 0xc0c2, - 0x49c7, 0xc0c0, 0x49bb, 0xc0be, 0x49af, 0xc0bd, 0x49a2, 0xc0bb, - 0x4996, 0xc0b9, 0x4989, 0xc0b7, 0x497d, 0xc0b5, 0x4970, 0xc0b3, - 0x4964, 0xc0b1, 0x4958, 0xc0af, 0x494b, 0xc0ae, 0x493f, 0xc0ac, - 0x4932, 0xc0aa, 0x4926, 0xc0a8, 0x4919, 0xc0a6, 0x490d, 0xc0a5, - 0x4901, 0xc0a3, 0x48f4, 0xc0a1, 0x48e8, 0xc09f, 0x48db, 0xc09e, - 0x48cf, 0xc09c, 0x48c2, 0xc09a, 0x48b6, 0xc098, 0x48a9, 0xc097, - 0x489d, 0xc095, 0x4891, 0xc093, 0x4884, 0xc092, 0x4878, 0xc090, - 0x486b, 0xc08e, 0x485f, 0xc08d, 0x4852, 0xc08b, 0x4846, 0xc089, - 0x4839, 0xc088, 0x482d, 0xc086, 0x4820, 0xc085, 0x4814, 0xc083, - 0x4807, 0xc081, 0x47fb, 0xc080, 0x47ef, 0xc07e, 0x47e2, 0xc07d, - 0x47d6, 0xc07b, 0x47c9, 0xc07a, 0x47bd, 0xc078, 0x47b0, 0xc077, - 0x47a4, 0xc075, 0x4797, 0xc074, 0x478b, 0xc072, 0x477e, 0xc071, - 0x4772, 0xc06f, 0x4765, 0xc06e, 0x4759, 0xc06c, 0x474c, 0xc06b, - 0x4740, 0xc069, 0x4733, 0xc068, 0x4727, 0xc067, 0x471a, 0xc065, - 0x470e, 0xc064, 0x4701, 0xc062, 0x46f5, 0xc061, 0x46e8, 0xc060, - 0x46dc, 0xc05e, 0x46cf, 0xc05d, 0x46c3, 0xc05c, 0x46b6, 0xc05a, - 0x46aa, 0xc059, 0x469d, 0xc058, 0x4691, 0xc056, 0x4684, 0xc055, - 0x4678, 0xc054, 0x466b, 0xc053, 0x465f, 0xc051, 0x4652, 0xc050, - 0x4646, 0xc04f, 0x4639, 0xc04e, 0x462d, 0xc04c, 0x4620, 0xc04b, - 0x4614, 0xc04a, 0x4607, 0xc049, 0x45fb, 0xc048, 0x45ee, 0xc047, - 0x45e2, 0xc045, 0x45d5, 0xc044, 0x45c9, 0xc043, 0x45bc, 0xc042, - 0x45b0, 0xc041, 0x45a3, 0xc040, 0x4597, 0xc03f, 0x458a, 0xc03d, - 0x457e, 0xc03c, 0x4571, 0xc03b, 0x4565, 0xc03a, 0x4558, 0xc039, - 0x454c, 0xc038, 0x453f, 0xc037, 0x4533, 0xc036, 0x4526, 0xc035, - 0x451a, 0xc034, 0x450d, 0xc033, 0x4500, 0xc032, 0x44f4, 0xc031, - 0x44e7, 0xc030, 0x44db, 0xc02f, 0x44ce, 0xc02e, 0x44c2, 0xc02d, - 0x44b5, 0xc02c, 0x44a9, 0xc02b, 0x449c, 0xc02b, 0x4490, 0xc02a, - 0x4483, 0xc029, 0x4477, 0xc028, 0x446a, 0xc027, 0x445e, 0xc026, - 0x4451, 0xc025, 0x4444, 0xc024, 0x4438, 0xc024, 0x442b, 0xc023, - 0x441f, 0xc022, 0x4412, 0xc021, 0x4406, 0xc020, 0x43f9, 0xc020, - 0x43ed, 0xc01f, 0x43e0, 0xc01e, 0x43d4, 0xc01d, 0x43c7, 0xc01d, - 0x43bb, 0xc01c, 0x43ae, 0xc01b, 0x43a1, 0xc01a, 0x4395, 0xc01a, - 0x4388, 0xc019, 0x437c, 0xc018, 0x436f, 0xc018, 0x4363, 0xc017, - 0x4356, 0xc016, 0x434a, 0xc016, 0x433d, 0xc015, 0x4330, 0xc014, - 0x4324, 0xc014, 0x4317, 0xc013, 0x430b, 0xc013, 0x42fe, 0xc012, - 0x42f2, 0xc011, 0x42e5, 0xc011, 0x42d9, 0xc010, 0x42cc, 0xc010, - 0x42c0, 0xc00f, 0x42b3, 0xc00f, 0x42a6, 0xc00e, 0x429a, 0xc00e, - 0x428d, 0xc00d, 0x4281, 0xc00d, 0x4274, 0xc00c, 0x4268, 0xc00c, - 0x425b, 0xc00b, 0x424e, 0xc00b, 0x4242, 0xc00a, 0x4235, 0xc00a, - 0x4229, 0xc009, 0x421c, 0xc009, 0x4210, 0xc009, 0x4203, 0xc008, - 0x41f7, 0xc008, 0x41ea, 0xc007, 0x41dd, 0xc007, 0x41d1, 0xc007, - 0x41c4, 0xc006, 0x41b8, 0xc006, 0x41ab, 0xc006, 0x419f, 0xc005, - 0x4192, 0xc005, 0x4186, 0xc005, 0x4179, 0xc004, 0x416c, 0xc004, - 0x4160, 0xc004, 0x4153, 0xc004, 0x4147, 0xc003, 0x413a, 0xc003, - 0x412e, 0xc003, 0x4121, 0xc003, 0x4114, 0xc002, 0x4108, 0xc002, - 0x40fb, 0xc002, 0x40ef, 0xc002, 0x40e2, 0xc002, 0x40d6, 0xc001, - 0x40c9, 0xc001, 0x40bc, 0xc001, 0x40b0, 0xc001, 0x40a3, 0xc001, - 0x4097, 0xc001, 0x408a, 0xc001, 0x407e, 0xc000, 0x4071, 0xc000, - 0x4065, 0xc000, 0x4058, 0xc000, 0x404b, 0xc000, 0x403f, 0xc000, - 0x4032, 0xc000, 0x4026, 0xc000, 0x4019, 0xc000, 0x400d, 0xc000, -}; - -/** -* @brief Initialization function for the Q15 RFFT/RIFFT. -* @param[in, out] *S points to an instance of the Q15 RFFT/RIFFT structure. -* @param[in] *S_CFFT points to an instance of the Q15 CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_q15( - arm_rfft_instance_q15 * S, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (q15_t *) realCoefAQ15; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (q15_t *) realCoefBQ15; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initialization of coef modifier depending on the FFT length */ - switch (S->fftLenReal) - { - case 8192: - S->twidCoefRModifier = 1u; - break; - case 2048u: - S->twidCoefRModifier = 4u; - break; - case 512u: - S->twidCoefRModifier = 16u; - break; - case 128u: - S->twidCoefRModifier = 64u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 1u, 1u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q15(S->pCfft, S->fftLenBy2, 0u, 1u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c deleted file mode 100644 index 400fe586c3..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_init_q31.c +++ /dev/null @@ -1,4274 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_init_q31.c -* -* Description: RFFT & RIFFT Q31 initialisation function -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/** - * @ingroup groupTransforms - */ - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** -* \par -* Generation floating point realCoefAQ31 array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-* {    
-*    pATable[2 * i] = 0.5 * (1.0 - sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pATable[2 * i + 1] = 0.5 * (-1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-* }
-* \par -* Convert to fixed point Q31 format -* round(pATable[i] * pow(2, 31)) -*/ - - -static const q31_t realCoefAQ31[8192] = { - 0x40000000, 0xc0000000, 0x3ff36f02, 0xc000013c, - 0x3fe6de05, 0xc00004ef, 0x3fda4d09, 0xc0000b1a, - 0x3fcdbc0f, 0xc00013bd, 0x3fc12b16, 0xc0001ed8, - 0x3fb49a1f, 0xc0002c6a, 0x3fa8092c, 0xc0003c74, - 0x3f9b783c, 0xc0004ef5, 0x3f8ee750, 0xc00063ee, - 0x3f825668, 0xc0007b5f, 0x3f75c585, 0xc0009547, - 0x3f6934a8, 0xc000b1a7, 0x3f5ca3d0, 0xc000d07e, - 0x3f5012fe, 0xc000f1ce, 0x3f438234, 0xc0011594, - 0x3f36f170, 0xc0013bd3, 0x3f2a60b4, 0xc0016489, - 0x3f1dd001, 0xc0018fb6, 0x3f113f56, 0xc001bd5c, - 0x3f04aeb5, 0xc001ed78, 0x3ef81e1d, 0xc002200d, - 0x3eeb8d8f, 0xc0025519, 0x3edefd0c, 0xc0028c9c, - 0x3ed26c94, 0xc002c697, 0x3ec5dc28, 0xc003030a, - 0x3eb94bc8, 0xc00341f4, 0x3eacbb74, 0xc0038356, - 0x3ea02b2e, 0xc003c72f, 0x3e939af5, 0xc0040d80, - 0x3e870aca, 0xc0045648, 0x3e7a7aae, 0xc004a188, - 0x3e6deaa1, 0xc004ef3f, 0x3e615aa3, 0xc0053f6e, - 0x3e54cab5, 0xc0059214, 0x3e483ad8, 0xc005e731, - 0x3e3bab0b, 0xc0063ec6, 0x3e2f1b50, 0xc00698d3, - 0x3e228ba7, 0xc006f556, 0x3e15fc11, 0xc0075452, - 0x3e096c8d, 0xc007b5c4, 0x3dfcdd1d, 0xc00819ae, - 0x3df04dc0, 0xc008800f, 0x3de3be78, 0xc008e8e8, - 0x3dd72f45, 0xc0095438, 0x3dcaa027, 0xc009c1ff, - 0x3dbe111e, 0xc00a323d, 0x3db1822c, 0xc00aa4f3, - 0x3da4f351, 0xc00b1a20, 0x3d98648d, 0xc00b91c4, - 0x3d8bd5e1, 0xc00c0be0, 0x3d7f474d, 0xc00c8872, - 0x3d72b8d2, 0xc00d077c, 0x3d662a70, 0xc00d88fd, - 0x3d599c28, 0xc00e0cf5, 0x3d4d0df9, 0xc00e9364, - 0x3d407fe6, 0xc00f1c4a, 0x3d33f1ed, 0xc00fa7a8, - 0x3d276410, 0xc010357c, 0x3d1ad650, 0xc010c5c7, - 0x3d0e48ab, 0xc011588a, 0x3d01bb24, 0xc011edc3, - 0x3cf52dbb, 0xc0128574, 0x3ce8a06f, 0xc0131f9b, - 0x3cdc1342, 0xc013bc39, 0x3ccf8634, 0xc0145b4e, - 0x3cc2f945, 0xc014fcda, 0x3cb66c77, 0xc015a0dd, - 0x3ca9dfc8, 0xc0164757, 0x3c9d533b, 0xc016f047, - 0x3c90c6cf, 0xc0179bae, 0x3c843a85, 0xc018498c, - 0x3c77ae5e, 0xc018f9e1, 0x3c6b2259, 0xc019acac, - 0x3c5e9678, 0xc01a61ee, 0x3c520aba, 0xc01b19a7, - 0x3c457f21, 0xc01bd3d6, 0x3c38f3ac, 0xc01c907c, - 0x3c2c685d, 0xc01d4f99, 0x3c1fdd34, 0xc01e112b, - 0x3c135231, 0xc01ed535, 0x3c06c754, 0xc01f9bb5, - 0x3bfa3c9f, 0xc02064ab, 0x3bedb212, 0xc0213018, - 0x3be127ac, 0xc021fdfb, 0x3bd49d70, 0xc022ce54, - 0x3bc8135c, 0xc023a124, 0x3bbb8973, 0xc024766a, - 0x3baeffb3, 0xc0254e27, 0x3ba2761e, 0xc0262859, - 0x3b95ecb4, 0xc0270502, 0x3b896375, 0xc027e421, - 0x3b7cda63, 0xc028c5b6, 0x3b70517d, 0xc029a9c1, - 0x3b63c8c4, 0xc02a9042, 0x3b574039, 0xc02b7939, - 0x3b4ab7db, 0xc02c64a6, 0x3b3e2fac, 0xc02d5289, - 0x3b31a7ac, 0xc02e42e2, 0x3b251fdc, 0xc02f35b1, - 0x3b18983b, 0xc0302af5, 0x3b0c10cb, 0xc03122b0, - 0x3aff898c, 0xc0321ce0, 0x3af3027e, 0xc0331986, - 0x3ae67ba2, 0xc03418a2, 0x3ad9f4f8, 0xc0351a33, - 0x3acd6e81, 0xc0361e3a, 0x3ac0e83d, 0xc03724b6, - 0x3ab4622d, 0xc0382da8, 0x3aa7dc52, 0xc0393910, - 0x3a9b56ab, 0xc03a46ed, 0x3a8ed139, 0xc03b573f, - 0x3a824bfd, 0xc03c6a07, 0x3a75c6f8, 0xc03d7f44, - 0x3a694229, 0xc03e96f6, 0x3a5cbd91, 0xc03fb11d, - 0x3a503930, 0xc040cdba, 0x3a43b508, 0xc041eccc, - 0x3a373119, 0xc0430e53, 0x3a2aad62, 0xc044324f, - 0x3a1e29e5, 0xc04558c0, 0x3a11a6a3, 0xc04681a6, - 0x3a05239a, 0xc047ad01, 0x39f8a0cd, 0xc048dad1, - 0x39ec1e3b, 0xc04a0b16, 0x39df9be6, 0xc04b3dcf, - 0x39d319cc, 0xc04c72fe, 0x39c697f0, 0xc04daaa1, - 0x39ba1651, 0xc04ee4b8, 0x39ad94f0, 0xc0502145, - 0x39a113cd, 0xc0516045, 0x399492ea, 0xc052a1bb, - 0x39881245, 0xc053e5a5, 0x397b91e1, 0xc0552c03, - 0x396f11bc, 0xc05674d6, 0x396291d9, 0xc057c01d, - 0x39561237, 0xc0590dd8, 0x394992d7, 0xc05a5e07, - 0x393d13b8, 0xc05bb0ab, 0x393094dd, 0xc05d05c3, - 0x39241645, 0xc05e5d4e, 0x391797f0, 0xc05fb74e, - 0x390b19e0, 0xc06113c2, 0x38fe9c15, 0xc06272aa, - 0x38f21e8e, 0xc063d405, 0x38e5a14d, 0xc06537d4, - 0x38d92452, 0xc0669e18, 0x38cca79e, 0xc06806ce, - 0x38c02b31, 0xc06971f9, 0x38b3af0c, 0xc06adf97, - 0x38a7332e, 0xc06c4fa8, 0x389ab799, 0xc06dc22e, - 0x388e3c4d, 0xc06f3726, 0x3881c14b, 0xc070ae92, - 0x38754692, 0xc0722871, 0x3868cc24, 0xc073a4c3, - 0x385c5201, 0xc0752389, 0x384fd829, 0xc076a4c2, - 0x38435e9d, 0xc078286e, 0x3836e55d, 0xc079ae8c, - 0x382a6c6a, 0xc07b371e, 0x381df3c5, 0xc07cc223, - 0x38117b6d, 0xc07e4f9b, 0x38050364, 0xc07fdf85, - 0x37f88ba9, 0xc08171e2, 0x37ec143e, 0xc08306b2, - 0x37df9d22, 0xc0849df4, 0x37d32657, 0xc08637a9, - 0x37c6afdc, 0xc087d3d0, 0x37ba39b3, 0xc089726a, - 0x37adc3db, 0xc08b1376, 0x37a14e55, 0xc08cb6f5, - 0x3794d922, 0xc08e5ce5, 0x37886442, 0xc0900548, - 0x377befb5, 0xc091b01d, 0x376f7b7d, 0xc0935d64, - 0x37630799, 0xc0950d1d, 0x3756940a, 0xc096bf48, - 0x374a20d0, 0xc09873e4, 0x373daded, 0xc09a2af3, - 0x37313b60, 0xc09be473, 0x3724c92a, 0xc09da065, - 0x3718574b, 0xc09f5ec8, 0x370be5c4, 0xc0a11f9d, - 0x36ff7496, 0xc0a2e2e3, 0x36f303c0, 0xc0a4a89b, - 0x36e69344, 0xc0a670c4, 0x36da2321, 0xc0a83b5e, - 0x36cdb359, 0xc0aa086a, 0x36c143ec, 0xc0abd7e6, - 0x36b4d4d9, 0xc0ada9d4, 0x36a86623, 0xc0af7e33, - 0x369bf7c9, 0xc0b15502, 0x368f89cb, 0xc0b32e42, - 0x36831c2b, 0xc0b509f3, 0x3676aee8, 0xc0b6e815, - 0x366a4203, 0xc0b8c8a7, 0x365dd57d, 0xc0baabaa, - 0x36516956, 0xc0bc911d, 0x3644fd8f, 0xc0be7901, - 0x36389228, 0xc0c06355, 0x362c2721, 0xc0c25019, - 0x361fbc7b, 0xc0c43f4d, 0x36135237, 0xc0c630f2, - 0x3606e854, 0xc0c82506, 0x35fa7ed4, 0xc0ca1b8a, - 0x35ee15b7, 0xc0cc147f, 0x35e1acfd, 0xc0ce0fe3, - 0x35d544a7, 0xc0d00db6, 0x35c8dcb6, 0xc0d20dfa, - 0x35bc7529, 0xc0d410ad, 0x35b00e02, 0xc0d615cf, - 0x35a3a740, 0xc0d81d61, 0x359740e5, 0xc0da2762, - 0x358adaf0, 0xc0dc33d2, 0x357e7563, 0xc0de42b2, - 0x3572103d, 0xc0e05401, 0x3565ab80, 0xc0e267be, - 0x3559472b, 0xc0e47deb, 0x354ce33f, 0xc0e69686, - 0x35407fbd, 0xc0e8b190, 0x35341ca5, 0xc0eacf09, - 0x3527b9f7, 0xc0eceef1, 0x351b57b5, 0xc0ef1147, - 0x350ef5de, 0xc0f1360b, 0x35029473, 0xc0f35d3e, - 0x34f63374, 0xc0f586df, 0x34e9d2e3, 0xc0f7b2ee, - 0x34dd72be, 0xc0f9e16b, 0x34d11308, 0xc0fc1257, - 0x34c4b3c0, 0xc0fe45b0, 0x34b854e7, 0xc1007b77, - 0x34abf67e, 0xc102b3ac, 0x349f9884, 0xc104ee4f, - 0x34933afa, 0xc1072b5f, 0x3486dde1, 0xc1096add, - 0x347a8139, 0xc10bacc8, 0x346e2504, 0xc10df120, - 0x3461c940, 0xc11037e6, 0x34556def, 0xc1128119, - 0x34491311, 0xc114ccb9, 0x343cb8a7, 0xc1171ac6, - 0x34305eb0, 0xc1196b3f, 0x3424052f, 0xc11bbe26, - 0x3417ac22, 0xc11e1379, 0x340b538b, 0xc1206b39, - 0x33fefb6a, 0xc122c566, 0x33f2a3bf, 0xc12521ff, - 0x33e64c8c, 0xc1278104, 0x33d9f5cf, 0xc129e276, - 0x33cd9f8b, 0xc12c4653, 0x33c149bf, 0xc12eac9d, - 0x33b4f46c, 0xc1311553, 0x33a89f92, 0xc1338075, - 0x339c4b32, 0xc135ee02, 0x338ff74d, 0xc1385dfb, - 0x3383a3e2, 0xc13ad060, 0x337750f2, 0xc13d4530, - 0x336afe7e, 0xc13fbc6c, 0x335eac86, 0xc1423613, - 0x33525b0b, 0xc144b225, 0x33460a0d, 0xc14730a3, - 0x3339b98d, 0xc149b18b, 0x332d698a, 0xc14c34df, - 0x33211a07, 0xc14eba9d, 0x3314cb02, 0xc15142c6, - 0x33087c7d, 0xc153cd5a, 0x32fc2e77, 0xc1565a58, - 0x32efe0f2, 0xc158e9c1, 0x32e393ef, 0xc15b7b94, - 0x32d7476c, 0xc15e0fd1, 0x32cafb6b, 0xc160a678, - 0x32beafed, 0xc1633f8a, 0x32b264f2, 0xc165db05, - 0x32a61a7a, 0xc16878eb, 0x3299d085, 0xc16b193a, - 0x328d8715, 0xc16dbbf3, 0x32813e2a, 0xc1706115, - 0x3274f5c3, 0xc17308a1, 0x3268ade3, 0xc175b296, - 0x325c6688, 0xc1785ef4, 0x32501fb5, 0xc17b0dbb, - 0x3243d968, 0xc17dbeec, 0x323793a3, 0xc1807285, - 0x322b4e66, 0xc1832888, 0x321f09b1, 0xc185e0f3, - 0x3212c585, 0xc1889bc6, 0x320681e3, 0xc18b5903, - 0x31fa3ecb, 0xc18e18a7, 0x31edfc3d, 0xc190dab4, - 0x31e1ba3a, 0xc1939f29, 0x31d578c2, 0xc1966606, - 0x31c937d6, 0xc1992f4c, 0x31bcf777, 0xc19bfaf9, - 0x31b0b7a4, 0xc19ec90d, 0x31a4785e, 0xc1a1998a, - 0x319839a6, 0xc1a46c6e, 0x318bfb7d, 0xc1a741b9, - 0x317fbde2, 0xc1aa196c, 0x317380d6, 0xc1acf386, - 0x31674459, 0xc1afd007, 0x315b086d, 0xc1b2aef0, - 0x314ecd11, 0xc1b5903f, 0x31429247, 0xc1b873f5, - 0x3136580d, 0xc1bb5a11, 0x312a1e66, 0xc1be4294, - 0x311de551, 0xc1c12d7e, 0x3111accf, 0xc1c41ace, - 0x310574e0, 0xc1c70a84, 0x30f93d86, 0xc1c9fca0, - 0x30ed06bf, 0xc1ccf122, 0x30e0d08d, 0xc1cfe80a, - 0x30d49af1, 0xc1d2e158, 0x30c865ea, 0xc1d5dd0c, - 0x30bc317a, 0xc1d8db25, 0x30affda0, 0xc1dbdba3, - 0x30a3ca5d, 0xc1dede87, 0x309797b2, 0xc1e1e3d0, - 0x308b659f, 0xc1e4eb7e, 0x307f3424, 0xc1e7f591, - 0x30730342, 0xc1eb0209, 0x3066d2fa, 0xc1ee10e5, - 0x305aa34c, 0xc1f12227, 0x304e7438, 0xc1f435cc, - 0x304245c0, 0xc1f74bd6, 0x303617e2, 0xc1fa6445, - 0x3029eaa1, 0xc1fd7f17, 0x301dbdfb, 0xc2009c4e, - 0x301191f3, 0xc203bbe8, 0x30056687, 0xc206dde6, - 0x2ff93bba, 0xc20a0248, 0x2fed118a, 0xc20d290d, - 0x2fe0e7f9, 0xc2105236, 0x2fd4bf08, 0xc2137dc2, - 0x2fc896b5, 0xc216abb1, 0x2fbc6f03, 0xc219dc03, - 0x2fb047f2, 0xc21d0eb8, 0x2fa42181, 0xc22043d0, - 0x2f97fbb2, 0xc2237b4b, 0x2f8bd685, 0xc226b528, - 0x2f7fb1fa, 0xc229f167, 0x2f738e12, 0xc22d3009, - 0x2f676ace, 0xc230710d, 0x2f5b482d, 0xc233b473, - 0x2f4f2630, 0xc236fa3b, 0x2f4304d8, 0xc23a4265, - 0x2f36e426, 0xc23d8cf1, 0x2f2ac419, 0xc240d9de, - 0x2f1ea4b2, 0xc244292c, 0x2f1285f2, 0xc2477adc, - 0x2f0667d9, 0xc24aceed, 0x2efa4a67, 0xc24e255e, - 0x2eee2d9d, 0xc2517e31, 0x2ee2117c, 0xc254d965, - 0x2ed5f604, 0xc25836f9, 0x2ec9db35, 0xc25b96ee, - 0x2ebdc110, 0xc25ef943, 0x2eb1a796, 0xc2625df8, - 0x2ea58ec6, 0xc265c50e, 0x2e9976a1, 0xc2692e83, - 0x2e8d5f29, 0xc26c9a58, 0x2e81485c, 0xc270088e, - 0x2e75323c, 0xc2737922, 0x2e691cc9, 0xc276ec16, - 0x2e5d0804, 0xc27a616a, 0x2e50f3ed, 0xc27dd91c, - 0x2e44e084, 0xc281532e, 0x2e38cdcb, 0xc284cf9f, - 0x2e2cbbc1, 0xc2884e6e, 0x2e20aa67, 0xc28bcf9c, - 0x2e1499bd, 0xc28f5329, 0x2e0889c4, 0xc292d914, - 0x2dfc7a7c, 0xc296615d, 0x2df06be6, 0xc299ec05, - 0x2de45e03, 0xc29d790a, 0x2dd850d2, 0xc2a1086d, - 0x2dcc4454, 0xc2a49a2e, 0x2dc0388a, 0xc2a82e4d, - 0x2db42d74, 0xc2abc4c9, 0x2da82313, 0xc2af5da2, - 0x2d9c1967, 0xc2b2f8d8, 0x2d901070, 0xc2b6966c, - 0x2d84082f, 0xc2ba365c, 0x2d7800a5, 0xc2bdd8a9, - 0x2d6bf9d1, 0xc2c17d52, 0x2d5ff3b5, 0xc2c52459, - 0x2d53ee51, 0xc2c8cdbb, 0x2d47e9a5, 0xc2cc7979, - 0x2d3be5b1, 0xc2d02794, 0x2d2fe277, 0xc2d3d80a, - 0x2d23dff7, 0xc2d78add, 0x2d17de31, 0xc2db400a, - 0x2d0bdd25, 0xc2def794, 0x2cffdcd4, 0xc2e2b178, - 0x2cf3dd3f, 0xc2e66db8, 0x2ce7de66, 0xc2ea2c53, - 0x2cdbe04a, 0xc2eded49, 0x2ccfe2ea, 0xc2f1b099, - 0x2cc3e648, 0xc2f57644, 0x2cb7ea63, 0xc2f93e4a, - 0x2cabef3d, 0xc2fd08a9, 0x2c9ff4d6, 0xc300d563, - 0x2c93fb2e, 0xc304a477, 0x2c880245, 0xc30875e5, - 0x2c7c0a1d, 0xc30c49ad, 0x2c7012b5, 0xc3101fce, - 0x2c641c0e, 0xc313f848, 0x2c582629, 0xc317d31c, - 0x2c4c3106, 0xc31bb049, 0x2c403ca5, 0xc31f8fcf, - 0x2c344908, 0xc32371ae, 0x2c28562d, 0xc32755e5, - 0x2c1c6417, 0xc32b3c75, 0x2c1072c4, 0xc32f255e, - 0x2c048237, 0xc333109e, 0x2bf8926f, 0xc336fe37, - 0x2beca36c, 0xc33aee27, 0x2be0b52f, 0xc33ee070, - 0x2bd4c7ba, 0xc342d510, 0x2bc8db0b, 0xc346cc07, - 0x2bbcef23, 0xc34ac556, 0x2bb10404, 0xc34ec0fc, - 0x2ba519ad, 0xc352bef9, 0x2b99301f, 0xc356bf4d, - 0x2b8d475b, 0xc35ac1f7, 0x2b815f60, 0xc35ec6f8, - 0x2b75782f, 0xc362ce50, 0x2b6991ca, 0xc366d7fd, - 0x2b5dac2f, 0xc36ae401, 0x2b51c760, 0xc36ef25b, - 0x2b45e35d, 0xc373030a, 0x2b3a0027, 0xc377160f, - 0x2b2e1dbe, 0xc37b2b6a, 0x2b223c22, 0xc37f4319, - 0x2b165b54, 0xc3835d1e, 0x2b0a7b54, 0xc3877978, - 0x2afe9c24, 0xc38b9827, 0x2af2bdc3, 0xc38fb92a, - 0x2ae6e031, 0xc393dc82, 0x2adb0370, 0xc398022f, - 0x2acf277f, 0xc39c2a2f, 0x2ac34c60, 0xc3a05484, - 0x2ab77212, 0xc3a4812c, 0x2aab9896, 0xc3a8b028, - 0x2a9fbfed, 0xc3ace178, 0x2a93e817, 0xc3b1151b, - 0x2a881114, 0xc3b54b11, 0x2a7c3ae5, 0xc3b9835a, - 0x2a70658a, 0xc3bdbdf6, 0x2a649105, 0xc3c1fae5, - 0x2a58bd54, 0xc3c63a26, 0x2a4cea79, 0xc3ca7bba, - 0x2a411874, 0xc3cebfa0, 0x2a354746, 0xc3d305d8, - 0x2a2976ef, 0xc3d74e62, 0x2a1da770, 0xc3db993e, - 0x2a11d8c8, 0xc3dfe66c, 0x2a060af9, 0xc3e435ea, - 0x29fa3e03, 0xc3e887bb, 0x29ee71e6, 0xc3ecdbdc, - 0x29e2a6a3, 0xc3f1324e, 0x29d6dc3b, 0xc3f58b10, - 0x29cb12ad, 0xc3f9e624, 0x29bf49fa, 0xc3fe4388, - 0x29b38223, 0xc402a33c, 0x29a7bb28, 0xc4070540, - 0x299bf509, 0xc40b6994, 0x29902fc7, 0xc40fd037, - 0x29846b63, 0xc414392b, 0x2978a7dd, 0xc418a46d, - 0x296ce535, 0xc41d11ff, 0x2961236c, 0xc42181e0, - 0x29556282, 0xc425f410, 0x2949a278, 0xc42a688f, - 0x293de34e, 0xc42edf5c, 0x29322505, 0xc4335877, - 0x2926679c, 0xc437d3e1, 0x291aab16, 0xc43c5199, - 0x290eef71, 0xc440d19e, 0x290334af, 0xc44553f2, - 0x28f77acf, 0xc449d892, 0x28ebc1d3, 0xc44e5f80, - 0x28e009ba, 0xc452e8bc, 0x28d45286, 0xc4577444, - 0x28c89c37, 0xc45c0219, 0x28bce6cd, 0xc460923b, - 0x28b13248, 0xc46524a9, 0x28a57ea9, 0xc469b963, - 0x2899cbf1, 0xc46e5069, 0x288e1a20, 0xc472e9bc, - 0x28826936, 0xc477855a, 0x2876b934, 0xc47c2344, - 0x286b0a1a, 0xc480c379, 0x285f5be9, 0xc48565f9, - 0x2853aea1, 0xc48a0ac4, 0x28480243, 0xc48eb1db, - 0x283c56cf, 0xc4935b3c, 0x2830ac45, 0xc49806e7, - 0x282502a7, 0xc49cb4dd, 0x281959f4, 0xc4a1651c, - 0x280db22d, 0xc4a617a6, 0x28020b52, 0xc4aacc7a, - 0x27f66564, 0xc4af8397, 0x27eac063, 0xc4b43cfd, - 0x27df1c50, 0xc4b8f8ad, 0x27d3792b, 0xc4bdb6a6, - 0x27c7d6f4, 0xc4c276e8, 0x27bc35ad, 0xc4c73972, - 0x27b09555, 0xc4cbfe45, 0x27a4f5ed, 0xc4d0c560, - 0x27995776, 0xc4d58ec3, 0x278db9ef, 0xc4da5a6f, - 0x27821d59, 0xc4df2862, 0x277681b6, 0xc4e3f89c, - 0x276ae704, 0xc4e8cb1e, 0x275f4d45, 0xc4ed9fe7, - 0x2753b479, 0xc4f276f7, 0x27481ca1, 0xc4f7504e, - 0x273c85bc, 0xc4fc2bec, 0x2730efcc, 0xc50109d0, - 0x27255ad1, 0xc505e9fb, 0x2719c6cb, 0xc50acc6b, - 0x270e33bb, 0xc50fb121, 0x2702a1a1, 0xc514981d, - 0x26f7107e, 0xc519815f, 0x26eb8052, 0xc51e6ce6, - 0x26dff11d, 0xc5235ab2, 0x26d462e1, 0xc5284ac3, - 0x26c8d59c, 0xc52d3d18, 0x26bd4951, 0xc53231b3, - 0x26b1bdff, 0xc5372891, 0x26a633a6, 0xc53c21b4, - 0x269aaa48, 0xc5411d1b, 0x268f21e5, 0xc5461ac6, - 0x26839a7c, 0xc54b1ab4, 0x26781410, 0xc5501ce5, - 0x266c8e9f, 0xc555215a, 0x26610a2a, 0xc55a2812, - 0x265586b3, 0xc55f310d, 0x264a0438, 0xc5643c4a, - 0x263e82bc, 0xc56949ca, 0x2633023e, 0xc56e598c, - 0x262782be, 0xc5736b90, 0x261c043d, 0xc5787fd6, - 0x261086bc, 0xc57d965d, 0x26050a3b, 0xc582af26, - 0x25f98ebb, 0xc587ca31, 0x25ee143b, 0xc58ce77c, - 0x25e29abc, 0xc5920708, 0x25d72240, 0xc59728d5, - 0x25cbaac5, 0xc59c4ce3, 0x25c0344d, 0xc5a17330, - 0x25b4bed8, 0xc5a69bbe, 0x25a94a67, 0xc5abc68c, - 0x259dd6f9, 0xc5b0f399, 0x25926490, 0xc5b622e6, - 0x2586f32c, 0xc5bb5472, 0x257b82cd, 0xc5c0883d, - 0x25701374, 0xc5c5be47, 0x2564a521, 0xc5caf690, - 0x255937d5, 0xc5d03118, 0x254dcb8f, 0xc5d56ddd, - 0x25426051, 0xc5daace1, 0x2536f61b, 0xc5dfee22, - 0x252b8cee, 0xc5e531a1, 0x252024c9, 0xc5ea775e, - 0x2514bdad, 0xc5efbf58, 0x2509579b, 0xc5f5098f, - 0x24fdf294, 0xc5fa5603, 0x24f28e96, 0xc5ffa4b3, - 0x24e72ba4, 0xc604f5a0, 0x24dbc9bd, 0xc60a48c9, - 0x24d068e2, 0xc60f9e2e, 0x24c50914, 0xc614f5cf, - 0x24b9aa52, 0xc61a4fac, 0x24ae4c9d, 0xc61fabc4, - 0x24a2eff6, 0xc6250a18, 0x2497945d, 0xc62a6aa6, - 0x248c39d3, 0xc62fcd6f, 0x2480e057, 0xc6353273, - 0x247587eb, 0xc63a99b1, 0x246a308f, 0xc6400329, - 0x245eda43, 0xc6456edb, 0x24538507, 0xc64adcc7, - 0x244830dd, 0xc6504ced, 0x243cddc4, 0xc655bf4c, - 0x24318bbe, 0xc65b33e4, 0x24263ac9, 0xc660aab5, - 0x241aeae8, 0xc66623be, 0x240f9c1a, 0xc66b9f01, - 0x24044e60, 0xc6711c7b, 0x23f901ba, 0xc6769c2e, - 0x23edb628, 0xc67c1e18, 0x23e26bac, 0xc681a23a, - 0x23d72245, 0xc6872894, 0x23cbd9f4, 0xc68cb124, - 0x23c092b9, 0xc6923bec, 0x23b54c95, 0xc697c8eb, - 0x23aa0788, 0xc69d5820, 0x239ec393, 0xc6a2e98b, - 0x239380b6, 0xc6a87d2d, 0x23883ef2, 0xc6ae1304, - 0x237cfe47, 0xc6b3ab12, 0x2371beb5, 0xc6b94554, - 0x2366803c, 0xc6bee1cd, 0x235b42df, 0xc6c4807a, - 0x2350069b, 0xc6ca215c, 0x2344cb73, 0xc6cfc472, - 0x23399167, 0xc6d569be, 0x232e5876, 0xc6db113d, - 0x232320a2, 0xc6e0baf0, 0x2317e9eb, 0xc6e666d7, - 0x230cb451, 0xc6ec14f2, 0x23017fd5, 0xc6f1c540, - 0x22f64c77, 0xc6f777c1, 0x22eb1a37, 0xc6fd2c75, - 0x22dfe917, 0xc702e35c, 0x22d4b916, 0xc7089c75, - 0x22c98a35, 0xc70e57c0, 0x22be5c74, 0xc714153e, - 0x22b32fd4, 0xc719d4ed, 0x22a80456, 0xc71f96ce, - 0x229cd9f8, 0xc7255ae0, 0x2291b0bd, 0xc72b2123, - 0x228688a4, 0xc730e997, 0x227b61af, 0xc736b43c, - 0x22703bdc, 0xc73c8111, 0x2265172e, 0xc7425016, - 0x2259f3a3, 0xc748214c, 0x224ed13d, 0xc74df4b1, - 0x2243affc, 0xc753ca46, 0x22388fe1, 0xc759a20a, - 0x222d70eb, 0xc75f7bfe, 0x2222531c, 0xc7655820, - 0x22173674, 0xc76b3671, 0x220c1af3, 0xc77116f0, - 0x22010099, 0xc776f99d, 0x21f5e768, 0xc77cde79, - 0x21eacf5f, 0xc782c582, 0x21dfb87f, 0xc788aeb9, - 0x21d4a2c8, 0xc78e9a1d, 0x21c98e3b, 0xc79487ae, - 0x21be7ad8, 0xc79a776c, 0x21b368a0, 0xc7a06957, - 0x21a85793, 0xc7a65d6e, 0x219d47b1, 0xc7ac53b1, - 0x219238fb, 0xc7b24c20, 0x21872b72, 0xc7b846ba, - 0x217c1f15, 0xc7be4381, 0x217113e5, 0xc7c44272, - 0x216609e3, 0xc7ca438f, 0x215b0110, 0xc7d046d6, - 0x214ff96a, 0xc7d64c47, 0x2144f2f3, 0xc7dc53e3, - 0x2139edac, 0xc7e25daa, 0x212ee995, 0xc7e8699a, - 0x2123e6ad, 0xc7ee77b3, 0x2118e4f6, 0xc7f487f6, - 0x210de470, 0xc7fa9a62, 0x2102e51c, 0xc800aef7, - 0x20f7e6f9, 0xc806c5b5, 0x20ecea09, 0xc80cde9b, - 0x20e1ee4b, 0xc812f9a9, 0x20d6f3c1, 0xc81916df, - 0x20cbfa6a, 0xc81f363d, 0x20c10247, 0xc82557c3, - 0x20b60b58, 0xc82b7b70, 0x20ab159e, 0xc831a143, - 0x20a0211a, 0xc837c93e, 0x20952dcb, 0xc83df35f, - 0x208a3bb2, 0xc8441fa6, 0x207f4acf, 0xc84a4e14, - 0x20745b24, 0xc8507ea7, 0x20696cb0, 0xc856b160, - 0x205e7f74, 0xc85ce63e, 0x2053936f, 0xc8631d42, - 0x2048a8a4, 0xc869566a, 0x203dbf11, 0xc86f91b7, - 0x2032d6b8, 0xc875cf28, 0x2027ef99, 0xc87c0ebd, - 0x201d09b4, 0xc8825077, 0x2012250a, 0xc8889454, - 0x2007419b, 0xc88eda54, 0x1ffc5f67, 0xc8952278, - 0x1ff17e70, 0xc89b6cbf, 0x1fe69eb4, 0xc8a1b928, - 0x1fdbc036, 0xc8a807b4, 0x1fd0e2f5, 0xc8ae5862, - 0x1fc606f1, 0xc8b4ab32, 0x1fbb2c2c, 0xc8bb0023, - 0x1fb052a5, 0xc8c15736, 0x1fa57a5d, 0xc8c7b06b, - 0x1f9aa354, 0xc8ce0bc0, 0x1f8fcd8b, 0xc8d46936, - 0x1f84f902, 0xc8dac8cd, 0x1f7a25ba, 0xc8e12a84, - 0x1f6f53b3, 0xc8e78e5b, 0x1f6482ed, 0xc8edf452, - 0x1f59b369, 0xc8f45c68, 0x1f4ee527, 0xc8fac69e, - 0x1f441828, 0xc90132f2, 0x1f394c6b, 0xc907a166, - 0x1f2e81f3, 0xc90e11f7, 0x1f23b8be, 0xc91484a8, - 0x1f18f0ce, 0xc91af976, 0x1f0e2a22, 0xc9217062, - 0x1f0364bc, 0xc927e96b, 0x1ef8a09b, 0xc92e6492, - 0x1eedddc0, 0xc934e1d6, 0x1ee31c2b, 0xc93b6137, - 0x1ed85bdd, 0xc941e2b4, 0x1ecd9cd7, 0xc948664d, - 0x1ec2df18, 0xc94eec03, 0x1eb822a1, 0xc95573d4, - 0x1ead6773, 0xc95bfdc1, 0x1ea2ad8d, 0xc96289c9, - 0x1e97f4f1, 0xc96917ec, 0x1e8d3d9e, 0xc96fa82a, - 0x1e828796, 0xc9763a83, 0x1e77d2d8, 0xc97ccef5, - 0x1e6d1f65, 0xc9836582, 0x1e626d3e, 0xc989fe29, - 0x1e57bc62, 0xc99098e9, 0x1e4d0cd2, 0xc99735c2, - 0x1e425e8f, 0xc99dd4b4, 0x1e37b199, 0xc9a475bf, - 0x1e2d05f1, 0xc9ab18e3, 0x1e225b96, 0xc9b1be1e, - 0x1e17b28a, 0xc9b86572, 0x1e0d0acc, 0xc9bf0edd, - 0x1e02645d, 0xc9c5ba60, 0x1df7bf3e, 0xc9cc67fa, - 0x1ded1b6e, 0xc9d317ab, 0x1de278ef, 0xc9d9c973, - 0x1dd7d7c1, 0xc9e07d51, 0x1dcd37e4, 0xc9e73346, - 0x1dc29958, 0xc9edeb50, 0x1db7fc1e, 0xc9f4a570, - 0x1dad6036, 0xc9fb61a5, 0x1da2c5a2, 0xca021fef, - 0x1d982c60, 0xca08e04f, 0x1d8d9472, 0xca0fa2c3, - 0x1d82fdd8, 0xca16674b, 0x1d786892, 0xca1d2de7, - 0x1d6dd4a2, 0xca23f698, 0x1d634206, 0xca2ac15b, - 0x1d58b0c0, 0xca318e32, 0x1d4e20d0, 0xca385d1d, - 0x1d439236, 0xca3f2e19, 0x1d3904f4, 0xca460129, - 0x1d2e7908, 0xca4cd64b, 0x1d23ee74, 0xca53ad7e, - 0x1d196538, 0xca5a86c4, 0x1d0edd55, 0xca61621b, - 0x1d0456ca, 0xca683f83, 0x1cf9d199, 0xca6f1efc, - 0x1cef4dc2, 0xca760086, 0x1ce4cb44, 0xca7ce420, - 0x1cda4a21, 0xca83c9ca, 0x1ccfca59, 0xca8ab184, - 0x1cc54bec, 0xca919b4e, 0x1cbacedb, 0xca988727, - 0x1cb05326, 0xca9f750f, 0x1ca5d8cd, 0xcaa66506, - 0x1c9b5fd2, 0xcaad570c, 0x1c90e834, 0xcab44b1f, - 0x1c8671f3, 0xcabb4141, 0x1c7bfd11, 0xcac23971, - 0x1c71898d, 0xcac933ae, 0x1c671768, 0xcad02ff8, - 0x1c5ca6a2, 0xcad72e4f, 0x1c52373c, 0xcade2eb3, - 0x1c47c936, 0xcae53123, 0x1c3d5c91, 0xcaec35a0, - 0x1c32f14d, 0xcaf33c28, 0x1c28876a, 0xcafa44bc, - 0x1c1e1ee9, 0xcb014f5b, 0x1c13b7c9, 0xcb085c05, - 0x1c09520d, 0xcb0f6aba, 0x1bfeedb3, 0xcb167b79, - 0x1bf48abd, 0xcb1d8e43, 0x1bea292b, 0xcb24a316, - 0x1bdfc8fc, 0xcb2bb9f4, 0x1bd56a32, 0xcb32d2da, - 0x1bcb0cce, 0xcb39edca, 0x1bc0b0ce, 0xcb410ac3, - 0x1bb65634, 0xcb4829c4, 0x1babfd01, 0xcb4f4acd, - 0x1ba1a534, 0xcb566ddf, 0x1b974ece, 0xcb5d92f8, - 0x1b8cf9cf, 0xcb64ba19, 0x1b82a638, 0xcb6be341, - 0x1b785409, 0xcb730e70, 0x1b6e0342, 0xcb7a3ba5, - 0x1b63b3e5, 0xcb816ae1, 0x1b5965f1, 0xcb889c23, - 0x1b4f1967, 0xcb8fcf6b, 0x1b44ce46, 0xcb9704b9, - 0x1b3a8491, 0xcb9e3c0b, 0x1b303c46, 0xcba57563, - 0x1b25f566, 0xcbacb0bf, 0x1b1baff2, 0xcbb3ee20, - 0x1b116beb, 0xcbbb2d85, 0x1b072950, 0xcbc26eee, - 0x1afce821, 0xcbc9b25a, 0x1af2a860, 0xcbd0f7ca, - 0x1ae86a0d, 0xcbd83f3d, 0x1ade2d28, 0xcbdf88b3, - 0x1ad3f1b1, 0xcbe6d42b, 0x1ac9b7a9, 0xcbee21a5, - 0x1abf7f11, 0xcbf57121, 0x1ab547e8, 0xcbfcc29f, - 0x1aab122f, 0xcc04161e, 0x1aa0dde7, 0xcc0b6b9e, - 0x1a96ab0f, 0xcc12c31f, 0x1a8c79a9, 0xcc1a1ca0, - 0x1a8249b4, 0xcc217822, 0x1a781b31, 0xcc28d5a3, - 0x1a6dee21, 0xcc303524, 0x1a63c284, 0xcc3796a5, - 0x1a599859, 0xcc3efa25, 0x1a4f6fa3, 0xcc465fa3, - 0x1a454860, 0xcc4dc720, 0x1a3b2292, 0xcc55309b, - 0x1a30fe38, 0xcc5c9c14, 0x1a26db54, 0xcc64098b, - 0x1a1cb9e5, 0xcc6b78ff, 0x1a1299ec, 0xcc72ea70, - 0x1a087b69, 0xcc7a5dde, 0x19fe5e5e, 0xcc81d349, - 0x19f442c9, 0xcc894aaf, 0x19ea28ac, 0xcc90c412, - 0x19e01006, 0xcc983f70, 0x19d5f8d9, 0xcc9fbcca, - 0x19cbe325, 0xcca73c1e, 0x19c1cee9, 0xccaebd6e, - 0x19b7bc27, 0xccb640b8, 0x19adaadf, 0xccbdc5fc, - 0x19a39b11, 0xccc54d3a, 0x19998cbe, 0xccccd671, - 0x198f7fe6, 0xccd461a2, 0x19857489, 0xccdbeecc, - 0x197b6aa8, 0xcce37def, 0x19716243, 0xcceb0f0a, - 0x19675b5a, 0xccf2a21d, 0x195d55ef, 0xccfa3729, - 0x19535201, 0xcd01ce2b, 0x19494f90, 0xcd096725, - 0x193f4e9e, 0xcd110216, 0x19354f2a, 0xcd189efe, - 0x192b5135, 0xcd203ddc, 0x192154bf, 0xcd27deb0, - 0x191759c9, 0xcd2f817b, 0x190d6053, 0xcd37263a, - 0x1903685d, 0xcd3eccef, 0x18f971e8, 0xcd467599, - 0x18ef7cf4, 0xcd4e2037, 0x18e58982, 0xcd55ccca, - 0x18db9792, 0xcd5d7b50, 0x18d1a724, 0xcd652bcb, - 0x18c7b838, 0xcd6cde39, 0x18bdcad0, 0xcd74929a, - 0x18b3deeb, 0xcd7c48ee, 0x18a9f48a, 0xcd840134, - 0x18a00bae, 0xcd8bbb6d, 0x18962456, 0xcd937798, - 0x188c3e83, 0xcd9b35b4, 0x18825a35, 0xcda2f5c2, - 0x1878776d, 0xcdaab7c0, 0x186e962b, 0xcdb27bb0, - 0x1864b670, 0xcdba4190, 0x185ad83c, 0xcdc20960, - 0x1850fb8e, 0xcdc9d320, 0x18472069, 0xcdd19ed0, - 0x183d46cc, 0xcdd96c6f, 0x18336eb7, 0xcde13bfd, - 0x1829982b, 0xcde90d79, 0x181fc328, 0xcdf0e0e4, - 0x1815efae, 0xcdf8b63d, 0x180c1dbf, 0xce008d84, - 0x18024d59, 0xce0866b8, 0x17f87e7f, 0xce1041d9, - 0x17eeb130, 0xce181ee8, 0x17e4e56c, 0xce1ffde2, - 0x17db1b34, 0xce27dec9, 0x17d15288, 0xce2fc19c, - 0x17c78b68, 0xce37a65b, 0x17bdc5d6, 0xce3f8d05, - 0x17b401d1, 0xce47759a, 0x17aa3f5a, 0xce4f6019, - 0x17a07e70, 0xce574c84, 0x1796bf16, 0xce5f3ad8, - 0x178d014a, 0xce672b16, 0x1783450d, 0xce6f1d3d, - 0x17798a60, 0xce77114e, 0x176fd143, 0xce7f0748, - 0x176619b6, 0xce86ff2a, 0x175c63ba, 0xce8ef8f4, - 0x1752af4f, 0xce96f4a7, 0x1748fc75, 0xce9ef241, - 0x173f4b2e, 0xcea6f1c2, 0x17359b78, 0xceaef32b, - 0x172bed55, 0xceb6f67a, 0x172240c5, 0xcebefbb0, - 0x171895c9, 0xcec702cb, 0x170eec60, 0xcecf0bcd, - 0x1705448b, 0xced716b4, 0x16fb9e4b, 0xcedf2380, - 0x16f1f99f, 0xcee73231, 0x16e85689, 0xceef42c7, - 0x16deb508, 0xcef75541, 0x16d5151d, 0xceff699f, - 0x16cb76c9, 0xcf077fe1, 0x16c1da0b, 0xcf0f9805, - 0x16b83ee4, 0xcf17b20d, 0x16aea555, 0xcf1fcdf8, - 0x16a50d5d, 0xcf27ebc5, 0x169b76fe, 0xcf300b74, - 0x1691e237, 0xcf382d05, 0x16884f09, 0xcf405077, - 0x167ebd74, 0xcf4875ca, 0x16752d79, 0xcf509cfe, - 0x166b9f18, 0xcf58c613, 0x16621251, 0xcf60f108, - 0x16588725, 0xcf691ddd, 0x164efd94, 0xcf714c91, - 0x1645759f, 0xcf797d24, 0x163bef46, 0xcf81af97, - 0x16326a88, 0xcf89e3e8, 0x1628e767, 0xcf921a17, - 0x161f65e4, 0xcf9a5225, 0x1615e5fd, 0xcfa28c10, - 0x160c67b4, 0xcfaac7d8, 0x1602eb0a, 0xcfb3057d, - 0x15f96ffd, 0xcfbb4500, 0x15eff690, 0xcfc3865e, - 0x15e67ec1, 0xcfcbc999, 0x15dd0892, 0xcfd40eaf, - 0x15d39403, 0xcfdc55a1, 0x15ca2115, 0xcfe49e6d, - 0x15c0afc6, 0xcfece915, 0x15b74019, 0xcff53597, - 0x15add20d, 0xcffd83f4, 0x15a465a3, 0xd005d42a, - 0x159afadb, 0xd00e2639, 0x159191b5, 0xd0167a22, - 0x15882a32, 0xd01ecfe4, 0x157ec452, 0xd027277e, - 0x15756016, 0xd02f80f1, 0x156bfd7d, 0xd037dc3b, - 0x15629c89, 0xd040395d, 0x15593d3a, 0xd0489856, - 0x154fdf8f, 0xd050f926, 0x15468389, 0xd0595bcd, - 0x153d292a, 0xd061c04a, 0x1533d070, 0xd06a269d, - 0x152a795d, 0xd0728ec6, 0x152123f0, 0xd07af8c4, - 0x1517d02b, 0xd0836497, 0x150e7e0d, 0xd08bd23f, - 0x15052d97, 0xd09441bb, 0x14fbdec9, 0xd09cb30b, - 0x14f291a4, 0xd0a5262f, 0x14e94627, 0xd0ad9b26, - 0x14dffc54, 0xd0b611f1, 0x14d6b42b, 0xd0be8a8d, - 0x14cd6dab, 0xd0c704fd, 0x14c428d6, 0xd0cf813e, - 0x14bae5ab, 0xd0d7ff51, 0x14b1a42c, 0xd0e07f36, - 0x14a86458, 0xd0e900ec, 0x149f2630, 0xd0f18472, - 0x1495e9b3, 0xd0fa09c9, 0x148caee4, 0xd10290f0, - 0x148375c1, 0xd10b19e7, 0x147a3e4b, 0xd113a4ad, - 0x14710883, 0xd11c3142, 0x1467d469, 0xd124bfa6, - 0x145ea1fd, 0xd12d4fd9, 0x14557140, 0xd135e1d9, - 0x144c4232, 0xd13e75a8, 0x144314d3, 0xd1470b44, - 0x1439e923, 0xd14fa2ad, 0x1430bf24, 0xd1583be2, - 0x142796d5, 0xd160d6e5, 0x141e7037, 0xd16973b3, - 0x14154b4a, 0xd172124d, 0x140c280e, 0xd17ab2b3, - 0x14030684, 0xd18354e4, 0x13f9e6ad, 0xd18bf8e0, - 0x13f0c887, 0xd1949ea6, 0x13e7ac15, 0xd19d4636, - 0x13de9156, 0xd1a5ef90, 0x13d5784a, 0xd1ae9ab4, - 0x13cc60f2, 0xd1b747a0, 0x13c34b4f, 0xd1bff656, - 0x13ba3760, 0xd1c8a6d4, 0x13b12526, 0xd1d1591a, - 0x13a814a2, 0xd1da0d28, 0x139f05d3, 0xd1e2c2fd, - 0x1395f8ba, 0xd1eb7a9a, 0x138ced57, 0xd1f433fd, - 0x1383e3ab, 0xd1fcef27, 0x137adbb6, 0xd205ac17, - 0x1371d579, 0xd20e6acc, 0x1368d0f3, 0xd2172b48, - 0x135fce26, 0xd21fed88, 0x1356cd11, 0xd228b18d, - 0x134dcdb4, 0xd2317756, 0x1344d011, 0xd23a3ee4, - 0x133bd427, 0xd2430835, 0x1332d9f7, 0xd24bd34a, - 0x1329e181, 0xd254a021, 0x1320eac6, 0xd25d6ebc, - 0x1317f5c6, 0xd2663f19, 0x130f0280, 0xd26f1138, - 0x130610f7, 0xd277e518, 0x12fd2129, 0xd280babb, - 0x12f43318, 0xd289921e, 0x12eb46c3, 0xd2926b41, - 0x12e25c2b, 0xd29b4626, 0x12d97350, 0xd2a422ca, - 0x12d08c33, 0xd2ad012e, 0x12c7a6d4, 0xd2b5e151, - 0x12bec333, 0xd2bec333, 0x12b5e151, 0xd2c7a6d4, - 0x12ad012e, 0xd2d08c33, 0x12a422ca, 0xd2d97350, - 0x129b4626, 0xd2e25c2b, 0x12926b41, 0xd2eb46c3, - 0x1289921e, 0xd2f43318, 0x1280babb, 0xd2fd2129, - 0x1277e518, 0xd30610f7, 0x126f1138, 0xd30f0280, - 0x12663f19, 0xd317f5c6, 0x125d6ebc, 0xd320eac6, - 0x1254a021, 0xd329e181, 0x124bd34a, 0xd332d9f7, - 0x12430835, 0xd33bd427, 0x123a3ee4, 0xd344d011, - 0x12317756, 0xd34dcdb4, 0x1228b18d, 0xd356cd11, - 0x121fed88, 0xd35fce26, 0x12172b48, 0xd368d0f3, - 0x120e6acc, 0xd371d579, 0x1205ac17, 0xd37adbb6, - 0x11fcef27, 0xd383e3ab, 0x11f433fd, 0xd38ced57, - 0x11eb7a9a, 0xd395f8ba, 0x11e2c2fd, 0xd39f05d3, - 0x11da0d28, 0xd3a814a2, 0x11d1591a, 0xd3b12526, - 0x11c8a6d4, 0xd3ba3760, 0x11bff656, 0xd3c34b4f, - 0x11b747a0, 0xd3cc60f2, 0x11ae9ab4, 0xd3d5784a, - 0x11a5ef90, 0xd3de9156, 0x119d4636, 0xd3e7ac15, - 0x11949ea6, 0xd3f0c887, 0x118bf8e0, 0xd3f9e6ad, - 0x118354e4, 0xd4030684, 0x117ab2b3, 0xd40c280e, - 0x1172124d, 0xd4154b4a, 0x116973b3, 0xd41e7037, - 0x1160d6e5, 0xd42796d5, 0x11583be2, 0xd430bf24, - 0x114fa2ad, 0xd439e923, 0x11470b44, 0xd44314d3, - 0x113e75a8, 0xd44c4232, 0x1135e1d9, 0xd4557140, - 0x112d4fd9, 0xd45ea1fd, 0x1124bfa6, 0xd467d469, - 0x111c3142, 0xd4710883, 0x1113a4ad, 0xd47a3e4b, - 0x110b19e7, 0xd48375c1, 0x110290f0, 0xd48caee4, - 0x10fa09c9, 0xd495e9b3, 0x10f18472, 0xd49f2630, - 0x10e900ec, 0xd4a86458, 0x10e07f36, 0xd4b1a42c, - 0x10d7ff51, 0xd4bae5ab, 0x10cf813e, 0xd4c428d6, - 0x10c704fd, 0xd4cd6dab, 0x10be8a8d, 0xd4d6b42b, - 0x10b611f1, 0xd4dffc54, 0x10ad9b26, 0xd4e94627, - 0x10a5262f, 0xd4f291a4, 0x109cb30b, 0xd4fbdec9, - 0x109441bb, 0xd5052d97, 0x108bd23f, 0xd50e7e0d, - 0x10836497, 0xd517d02b, 0x107af8c4, 0xd52123f0, - 0x10728ec6, 0xd52a795d, 0x106a269d, 0xd533d070, - 0x1061c04a, 0xd53d292a, 0x10595bcd, 0xd5468389, - 0x1050f926, 0xd54fdf8f, 0x10489856, 0xd5593d3a, - 0x1040395d, 0xd5629c89, 0x1037dc3b, 0xd56bfd7d, - 0x102f80f1, 0xd5756016, 0x1027277e, 0xd57ec452, - 0x101ecfe4, 0xd5882a32, 0x10167a22, 0xd59191b5, - 0x100e2639, 0xd59afadb, 0x1005d42a, 0xd5a465a3, - 0xffd83f4, 0xd5add20d, 0xff53597, 0xd5b74019, - 0xfece915, 0xd5c0afc6, 0xfe49e6d, 0xd5ca2115, - 0xfdc55a1, 0xd5d39403, 0xfd40eaf, 0xd5dd0892, - 0xfcbc999, 0xd5e67ec1, 0xfc3865e, 0xd5eff690, - 0xfbb4500, 0xd5f96ffd, 0xfb3057d, 0xd602eb0a, - 0xfaac7d8, 0xd60c67b4, 0xfa28c10, 0xd615e5fd, - 0xf9a5225, 0xd61f65e4, 0xf921a17, 0xd628e767, - 0xf89e3e8, 0xd6326a88, 0xf81af97, 0xd63bef46, - 0xf797d24, 0xd645759f, 0xf714c91, 0xd64efd94, - 0xf691ddd, 0xd6588725, 0xf60f108, 0xd6621251, - 0xf58c613, 0xd66b9f18, 0xf509cfe, 0xd6752d79, - 0xf4875ca, 0xd67ebd74, 0xf405077, 0xd6884f09, - 0xf382d05, 0xd691e237, 0xf300b74, 0xd69b76fe, - 0xf27ebc5, 0xd6a50d5d, 0xf1fcdf8, 0xd6aea555, - 0xf17b20d, 0xd6b83ee4, 0xf0f9805, 0xd6c1da0b, - 0xf077fe1, 0xd6cb76c9, 0xeff699f, 0xd6d5151d, - 0xef75541, 0xd6deb508, 0xeef42c7, 0xd6e85689, - 0xee73231, 0xd6f1f99f, 0xedf2380, 0xd6fb9e4b, - 0xed716b4, 0xd705448b, 0xecf0bcd, 0xd70eec60, - 0xec702cb, 0xd71895c9, 0xebefbb0, 0xd72240c5, - 0xeb6f67a, 0xd72bed55, 0xeaef32b, 0xd7359b78, - 0xea6f1c2, 0xd73f4b2e, 0xe9ef241, 0xd748fc75, - 0xe96f4a7, 0xd752af4f, 0xe8ef8f4, 0xd75c63ba, - 0xe86ff2a, 0xd76619b6, 0xe7f0748, 0xd76fd143, - 0xe77114e, 0xd7798a60, 0xe6f1d3d, 0xd783450d, - 0xe672b16, 0xd78d014a, 0xe5f3ad8, 0xd796bf16, - 0xe574c84, 0xd7a07e70, 0xe4f6019, 0xd7aa3f5a, - 0xe47759a, 0xd7b401d1, 0xe3f8d05, 0xd7bdc5d6, - 0xe37a65b, 0xd7c78b68, 0xe2fc19c, 0xd7d15288, - 0xe27dec9, 0xd7db1b34, 0xe1ffde2, 0xd7e4e56c, - 0xe181ee8, 0xd7eeb130, 0xe1041d9, 0xd7f87e7f, - 0xe0866b8, 0xd8024d59, 0xe008d84, 0xd80c1dbf, - 0xdf8b63d, 0xd815efae, 0xdf0e0e4, 0xd81fc328, - 0xde90d79, 0xd829982b, 0xde13bfd, 0xd8336eb7, - 0xdd96c6f, 0xd83d46cc, 0xdd19ed0, 0xd8472069, - 0xdc9d320, 0xd850fb8e, 0xdc20960, 0xd85ad83c, - 0xdba4190, 0xd864b670, 0xdb27bb0, 0xd86e962b, - 0xdaab7c0, 0xd878776d, 0xda2f5c2, 0xd8825a35, - 0xd9b35b4, 0xd88c3e83, 0xd937798, 0xd8962456, - 0xd8bbb6d, 0xd8a00bae, 0xd840134, 0xd8a9f48a, - 0xd7c48ee, 0xd8b3deeb, 0xd74929a, 0xd8bdcad0, - 0xd6cde39, 0xd8c7b838, 0xd652bcb, 0xd8d1a724, - 0xd5d7b50, 0xd8db9792, 0xd55ccca, 0xd8e58982, - 0xd4e2037, 0xd8ef7cf4, 0xd467599, 0xd8f971e8, - 0xd3eccef, 0xd903685d, 0xd37263a, 0xd90d6053, - 0xd2f817b, 0xd91759c9, 0xd27deb0, 0xd92154bf, - 0xd203ddc, 0xd92b5135, 0xd189efe, 0xd9354f2a, - 0xd110216, 0xd93f4e9e, 0xd096725, 0xd9494f90, - 0xd01ce2b, 0xd9535201, 0xcfa3729, 0xd95d55ef, - 0xcf2a21d, 0xd9675b5a, 0xceb0f0a, 0xd9716243, - 0xce37def, 0xd97b6aa8, 0xcdbeecc, 0xd9857489, - 0xcd461a2, 0xd98f7fe6, 0xcccd671, 0xd9998cbe, - 0xcc54d3a, 0xd9a39b11, 0xcbdc5fc, 0xd9adaadf, - 0xcb640b8, 0xd9b7bc27, 0xcaebd6e, 0xd9c1cee9, - 0xca73c1e, 0xd9cbe325, 0xc9fbcca, 0xd9d5f8d9, - 0xc983f70, 0xd9e01006, 0xc90c412, 0xd9ea28ac, - 0xc894aaf, 0xd9f442c9, 0xc81d349, 0xd9fe5e5e, - 0xc7a5dde, 0xda087b69, 0xc72ea70, 0xda1299ec, - 0xc6b78ff, 0xda1cb9e5, 0xc64098b, 0xda26db54, - 0xc5c9c14, 0xda30fe38, 0xc55309b, 0xda3b2292, - 0xc4dc720, 0xda454860, 0xc465fa3, 0xda4f6fa3, - 0xc3efa25, 0xda599859, 0xc3796a5, 0xda63c284, - 0xc303524, 0xda6dee21, 0xc28d5a3, 0xda781b31, - 0xc217822, 0xda8249b4, 0xc1a1ca0, 0xda8c79a9, - 0xc12c31f, 0xda96ab0f, 0xc0b6b9e, 0xdaa0dde7, - 0xc04161e, 0xdaab122f, 0xbfcc29f, 0xdab547e8, - 0xbf57121, 0xdabf7f11, 0xbee21a5, 0xdac9b7a9, - 0xbe6d42b, 0xdad3f1b1, 0xbdf88b3, 0xdade2d28, - 0xbd83f3d, 0xdae86a0d, 0xbd0f7ca, 0xdaf2a860, - 0xbc9b25a, 0xdafce821, 0xbc26eee, 0xdb072950, - 0xbbb2d85, 0xdb116beb, 0xbb3ee20, 0xdb1baff2, - 0xbacb0bf, 0xdb25f566, 0xba57563, 0xdb303c46, - 0xb9e3c0b, 0xdb3a8491, 0xb9704b9, 0xdb44ce46, - 0xb8fcf6b, 0xdb4f1967, 0xb889c23, 0xdb5965f1, - 0xb816ae1, 0xdb63b3e5, 0xb7a3ba5, 0xdb6e0342, - 0xb730e70, 0xdb785409, 0xb6be341, 0xdb82a638, - 0xb64ba19, 0xdb8cf9cf, 0xb5d92f8, 0xdb974ece, - 0xb566ddf, 0xdba1a534, 0xb4f4acd, 0xdbabfd01, - 0xb4829c4, 0xdbb65634, 0xb410ac3, 0xdbc0b0ce, - 0xb39edca, 0xdbcb0cce, 0xb32d2da, 0xdbd56a32, - 0xb2bb9f4, 0xdbdfc8fc, 0xb24a316, 0xdbea292b, - 0xb1d8e43, 0xdbf48abd, 0xb167b79, 0xdbfeedb3, - 0xb0f6aba, 0xdc09520d, 0xb085c05, 0xdc13b7c9, - 0xb014f5b, 0xdc1e1ee9, 0xafa44bc, 0xdc28876a, - 0xaf33c28, 0xdc32f14d, 0xaec35a0, 0xdc3d5c91, - 0xae53123, 0xdc47c936, 0xade2eb3, 0xdc52373c, - 0xad72e4f, 0xdc5ca6a2, 0xad02ff8, 0xdc671768, - 0xac933ae, 0xdc71898d, 0xac23971, 0xdc7bfd11, - 0xabb4141, 0xdc8671f3, 0xab44b1f, 0xdc90e834, - 0xaad570c, 0xdc9b5fd2, 0xaa66506, 0xdca5d8cd, - 0xa9f750f, 0xdcb05326, 0xa988727, 0xdcbacedb, - 0xa919b4e, 0xdcc54bec, 0xa8ab184, 0xdccfca59, - 0xa83c9ca, 0xdcda4a21, 0xa7ce420, 0xdce4cb44, - 0xa760086, 0xdcef4dc2, 0xa6f1efc, 0xdcf9d199, - 0xa683f83, 0xdd0456ca, 0xa61621b, 0xdd0edd55, - 0xa5a86c4, 0xdd196538, 0xa53ad7e, 0xdd23ee74, - 0xa4cd64b, 0xdd2e7908, 0xa460129, 0xdd3904f4, - 0xa3f2e19, 0xdd439236, 0xa385d1d, 0xdd4e20d0, - 0xa318e32, 0xdd58b0c0, 0xa2ac15b, 0xdd634206, - 0xa23f698, 0xdd6dd4a2, 0xa1d2de7, 0xdd786892, - 0xa16674b, 0xdd82fdd8, 0xa0fa2c3, 0xdd8d9472, - 0xa08e04f, 0xdd982c60, 0xa021fef, 0xdda2c5a2, - 0x9fb61a5, 0xddad6036, 0x9f4a570, 0xddb7fc1e, - 0x9edeb50, 0xddc29958, 0x9e73346, 0xddcd37e4, - 0x9e07d51, 0xddd7d7c1, 0x9d9c973, 0xdde278ef, - 0x9d317ab, 0xdded1b6e, 0x9cc67fa, 0xddf7bf3e, - 0x9c5ba60, 0xde02645d, 0x9bf0edd, 0xde0d0acc, - 0x9b86572, 0xde17b28a, 0x9b1be1e, 0xde225b96, - 0x9ab18e3, 0xde2d05f1, 0x9a475bf, 0xde37b199, - 0x99dd4b4, 0xde425e8f, 0x99735c2, 0xde4d0cd2, - 0x99098e9, 0xde57bc62, 0x989fe29, 0xde626d3e, - 0x9836582, 0xde6d1f65, 0x97ccef5, 0xde77d2d8, - 0x9763a83, 0xde828796, 0x96fa82a, 0xde8d3d9e, - 0x96917ec, 0xde97f4f1, 0x96289c9, 0xdea2ad8d, - 0x95bfdc1, 0xdead6773, 0x95573d4, 0xdeb822a1, - 0x94eec03, 0xdec2df18, 0x948664d, 0xdecd9cd7, - 0x941e2b4, 0xded85bdd, 0x93b6137, 0xdee31c2b, - 0x934e1d6, 0xdeedddc0, 0x92e6492, 0xdef8a09b, - 0x927e96b, 0xdf0364bc, 0x9217062, 0xdf0e2a22, - 0x91af976, 0xdf18f0ce, 0x91484a8, 0xdf23b8be, - 0x90e11f7, 0xdf2e81f3, 0x907a166, 0xdf394c6b, - 0x90132f2, 0xdf441828, 0x8fac69e, 0xdf4ee527, - 0x8f45c68, 0xdf59b369, 0x8edf452, 0xdf6482ed, - 0x8e78e5b, 0xdf6f53b3, 0x8e12a84, 0xdf7a25ba, - 0x8dac8cd, 0xdf84f902, 0x8d46936, 0xdf8fcd8b, - 0x8ce0bc0, 0xdf9aa354, 0x8c7b06b, 0xdfa57a5d, - 0x8c15736, 0xdfb052a5, 0x8bb0023, 0xdfbb2c2c, - 0x8b4ab32, 0xdfc606f1, 0x8ae5862, 0xdfd0e2f5, - 0x8a807b4, 0xdfdbc036, 0x8a1b928, 0xdfe69eb4, - 0x89b6cbf, 0xdff17e70, 0x8952278, 0xdffc5f67, - 0x88eda54, 0xe007419b, 0x8889454, 0xe012250a, - 0x8825077, 0xe01d09b4, 0x87c0ebd, 0xe027ef99, - 0x875cf28, 0xe032d6b8, 0x86f91b7, 0xe03dbf11, - 0x869566a, 0xe048a8a4, 0x8631d42, 0xe053936f, - 0x85ce63e, 0xe05e7f74, 0x856b160, 0xe0696cb0, - 0x8507ea7, 0xe0745b24, 0x84a4e14, 0xe07f4acf, - 0x8441fa6, 0xe08a3bb2, 0x83df35f, 0xe0952dcb, - 0x837c93e, 0xe0a0211a, 0x831a143, 0xe0ab159e, - 0x82b7b70, 0xe0b60b58, 0x82557c3, 0xe0c10247, - 0x81f363d, 0xe0cbfa6a, 0x81916df, 0xe0d6f3c1, - 0x812f9a9, 0xe0e1ee4b, 0x80cde9b, 0xe0ecea09, - 0x806c5b5, 0xe0f7e6f9, 0x800aef7, 0xe102e51c, - 0x7fa9a62, 0xe10de470, 0x7f487f6, 0xe118e4f6, - 0x7ee77b3, 0xe123e6ad, 0x7e8699a, 0xe12ee995, - 0x7e25daa, 0xe139edac, 0x7dc53e3, 0xe144f2f3, - 0x7d64c47, 0xe14ff96a, 0x7d046d6, 0xe15b0110, - 0x7ca438f, 0xe16609e3, 0x7c44272, 0xe17113e5, - 0x7be4381, 0xe17c1f15, 0x7b846ba, 0xe1872b72, - 0x7b24c20, 0xe19238fb, 0x7ac53b1, 0xe19d47b1, - 0x7a65d6e, 0xe1a85793, 0x7a06957, 0xe1b368a0, - 0x79a776c, 0xe1be7ad8, 0x79487ae, 0xe1c98e3b, - 0x78e9a1d, 0xe1d4a2c8, 0x788aeb9, 0xe1dfb87f, - 0x782c582, 0xe1eacf5f, 0x77cde79, 0xe1f5e768, - 0x776f99d, 0xe2010099, 0x77116f0, 0xe20c1af3, - 0x76b3671, 0xe2173674, 0x7655820, 0xe222531c, - 0x75f7bfe, 0xe22d70eb, 0x759a20a, 0xe2388fe1, - 0x753ca46, 0xe243affc, 0x74df4b1, 0xe24ed13d, - 0x748214c, 0xe259f3a3, 0x7425016, 0xe265172e, - 0x73c8111, 0xe2703bdc, 0x736b43c, 0xe27b61af, - 0x730e997, 0xe28688a4, 0x72b2123, 0xe291b0bd, - 0x7255ae0, 0xe29cd9f8, 0x71f96ce, 0xe2a80456, - 0x719d4ed, 0xe2b32fd4, 0x714153e, 0xe2be5c74, - 0x70e57c0, 0xe2c98a35, 0x7089c75, 0xe2d4b916, - 0x702e35c, 0xe2dfe917, 0x6fd2c75, 0xe2eb1a37, - 0x6f777c1, 0xe2f64c77, 0x6f1c540, 0xe3017fd5, - 0x6ec14f2, 0xe30cb451, 0x6e666d7, 0xe317e9eb, - 0x6e0baf0, 0xe32320a2, 0x6db113d, 0xe32e5876, - 0x6d569be, 0xe3399167, 0x6cfc472, 0xe344cb73, - 0x6ca215c, 0xe350069b, 0x6c4807a, 0xe35b42df, - 0x6bee1cd, 0xe366803c, 0x6b94554, 0xe371beb5, - 0x6b3ab12, 0xe37cfe47, 0x6ae1304, 0xe3883ef2, - 0x6a87d2d, 0xe39380b6, 0x6a2e98b, 0xe39ec393, - 0x69d5820, 0xe3aa0788, 0x697c8eb, 0xe3b54c95, - 0x6923bec, 0xe3c092b9, 0x68cb124, 0xe3cbd9f4, - 0x6872894, 0xe3d72245, 0x681a23a, 0xe3e26bac, - 0x67c1e18, 0xe3edb628, 0x6769c2e, 0xe3f901ba, - 0x6711c7b, 0xe4044e60, 0x66b9f01, 0xe40f9c1a, - 0x66623be, 0xe41aeae8, 0x660aab5, 0xe4263ac9, - 0x65b33e4, 0xe4318bbe, 0x655bf4c, 0xe43cddc4, - 0x6504ced, 0xe44830dd, 0x64adcc7, 0xe4538507, - 0x6456edb, 0xe45eda43, 0x6400329, 0xe46a308f, - 0x63a99b1, 0xe47587eb, 0x6353273, 0xe480e057, - 0x62fcd6f, 0xe48c39d3, 0x62a6aa6, 0xe497945d, - 0x6250a18, 0xe4a2eff6, 0x61fabc4, 0xe4ae4c9d, - 0x61a4fac, 0xe4b9aa52, 0x614f5cf, 0xe4c50914, - 0x60f9e2e, 0xe4d068e2, 0x60a48c9, 0xe4dbc9bd, - 0x604f5a0, 0xe4e72ba4, 0x5ffa4b3, 0xe4f28e96, - 0x5fa5603, 0xe4fdf294, 0x5f5098f, 0xe509579b, - 0x5efbf58, 0xe514bdad, 0x5ea775e, 0xe52024c9, - 0x5e531a1, 0xe52b8cee, 0x5dfee22, 0xe536f61b, - 0x5daace1, 0xe5426051, 0x5d56ddd, 0xe54dcb8f, - 0x5d03118, 0xe55937d5, 0x5caf690, 0xe564a521, - 0x5c5be47, 0xe5701374, 0x5c0883d, 0xe57b82cd, - 0x5bb5472, 0xe586f32c, 0x5b622e6, 0xe5926490, - 0x5b0f399, 0xe59dd6f9, 0x5abc68c, 0xe5a94a67, - 0x5a69bbe, 0xe5b4bed8, 0x5a17330, 0xe5c0344d, - 0x59c4ce3, 0xe5cbaac5, 0x59728d5, 0xe5d72240, - 0x5920708, 0xe5e29abc, 0x58ce77c, 0xe5ee143b, - 0x587ca31, 0xe5f98ebb, 0x582af26, 0xe6050a3b, - 0x57d965d, 0xe61086bc, 0x5787fd6, 0xe61c043d, - 0x5736b90, 0xe62782be, 0x56e598c, 0xe633023e, - 0x56949ca, 0xe63e82bc, 0x5643c4a, 0xe64a0438, - 0x55f310d, 0xe65586b3, 0x55a2812, 0xe6610a2a, - 0x555215a, 0xe66c8e9f, 0x5501ce5, 0xe6781410, - 0x54b1ab4, 0xe6839a7c, 0x5461ac6, 0xe68f21e5, - 0x5411d1b, 0xe69aaa48, 0x53c21b4, 0xe6a633a6, - 0x5372891, 0xe6b1bdff, 0x53231b3, 0xe6bd4951, - 0x52d3d18, 0xe6c8d59c, 0x5284ac3, 0xe6d462e1, - 0x5235ab2, 0xe6dff11d, 0x51e6ce6, 0xe6eb8052, - 0x519815f, 0xe6f7107e, 0x514981d, 0xe702a1a1, - 0x50fb121, 0xe70e33bb, 0x50acc6b, 0xe719c6cb, - 0x505e9fb, 0xe7255ad1, 0x50109d0, 0xe730efcc, - 0x4fc2bec, 0xe73c85bc, 0x4f7504e, 0xe7481ca1, - 0x4f276f7, 0xe753b479, 0x4ed9fe7, 0xe75f4d45, - 0x4e8cb1e, 0xe76ae704, 0x4e3f89c, 0xe77681b6, - 0x4df2862, 0xe7821d59, 0x4da5a6f, 0xe78db9ef, - 0x4d58ec3, 0xe7995776, 0x4d0c560, 0xe7a4f5ed, - 0x4cbfe45, 0xe7b09555, 0x4c73972, 0xe7bc35ad, - 0x4c276e8, 0xe7c7d6f4, 0x4bdb6a6, 0xe7d3792b, - 0x4b8f8ad, 0xe7df1c50, 0x4b43cfd, 0xe7eac063, - 0x4af8397, 0xe7f66564, 0x4aacc7a, 0xe8020b52, - 0x4a617a6, 0xe80db22d, 0x4a1651c, 0xe81959f4, - 0x49cb4dd, 0xe82502a7, 0x49806e7, 0xe830ac45, - 0x4935b3c, 0xe83c56cf, 0x48eb1db, 0xe8480243, - 0x48a0ac4, 0xe853aea1, 0x48565f9, 0xe85f5be9, - 0x480c379, 0xe86b0a1a, 0x47c2344, 0xe876b934, - 0x477855a, 0xe8826936, 0x472e9bc, 0xe88e1a20, - 0x46e5069, 0xe899cbf1, 0x469b963, 0xe8a57ea9, - 0x46524a9, 0xe8b13248, 0x460923b, 0xe8bce6cd, - 0x45c0219, 0xe8c89c37, 0x4577444, 0xe8d45286, - 0x452e8bc, 0xe8e009ba, 0x44e5f80, 0xe8ebc1d3, - 0x449d892, 0xe8f77acf, 0x44553f2, 0xe90334af, - 0x440d19e, 0xe90eef71, 0x43c5199, 0xe91aab16, - 0x437d3e1, 0xe926679c, 0x4335877, 0xe9322505, - 0x42edf5c, 0xe93de34e, 0x42a688f, 0xe949a278, - 0x425f410, 0xe9556282, 0x42181e0, 0xe961236c, - 0x41d11ff, 0xe96ce535, 0x418a46d, 0xe978a7dd, - 0x414392b, 0xe9846b63, 0x40fd037, 0xe9902fc7, - 0x40b6994, 0xe99bf509, 0x4070540, 0xe9a7bb28, - 0x402a33c, 0xe9b38223, 0x3fe4388, 0xe9bf49fa, - 0x3f9e624, 0xe9cb12ad, 0x3f58b10, 0xe9d6dc3b, - 0x3f1324e, 0xe9e2a6a3, 0x3ecdbdc, 0xe9ee71e6, - 0x3e887bb, 0xe9fa3e03, 0x3e435ea, 0xea060af9, - 0x3dfe66c, 0xea11d8c8, 0x3db993e, 0xea1da770, - 0x3d74e62, 0xea2976ef, 0x3d305d8, 0xea354746, - 0x3cebfa0, 0xea411874, 0x3ca7bba, 0xea4cea79, - 0x3c63a26, 0xea58bd54, 0x3c1fae5, 0xea649105, - 0x3bdbdf6, 0xea70658a, 0x3b9835a, 0xea7c3ae5, - 0x3b54b11, 0xea881114, 0x3b1151b, 0xea93e817, - 0x3ace178, 0xea9fbfed, 0x3a8b028, 0xeaab9896, - 0x3a4812c, 0xeab77212, 0x3a05484, 0xeac34c60, - 0x39c2a2f, 0xeacf277f, 0x398022f, 0xeadb0370, - 0x393dc82, 0xeae6e031, 0x38fb92a, 0xeaf2bdc3, - 0x38b9827, 0xeafe9c24, 0x3877978, 0xeb0a7b54, - 0x3835d1e, 0xeb165b54, 0x37f4319, 0xeb223c22, - 0x37b2b6a, 0xeb2e1dbe, 0x377160f, 0xeb3a0027, - 0x373030a, 0xeb45e35d, 0x36ef25b, 0xeb51c760, - 0x36ae401, 0xeb5dac2f, 0x366d7fd, 0xeb6991ca, - 0x362ce50, 0xeb75782f, 0x35ec6f8, 0xeb815f60, - 0x35ac1f7, 0xeb8d475b, 0x356bf4d, 0xeb99301f, - 0x352bef9, 0xeba519ad, 0x34ec0fc, 0xebb10404, - 0x34ac556, 0xebbcef23, 0x346cc07, 0xebc8db0b, - 0x342d510, 0xebd4c7ba, 0x33ee070, 0xebe0b52f, - 0x33aee27, 0xebeca36c, 0x336fe37, 0xebf8926f, - 0x333109e, 0xec048237, 0x32f255e, 0xec1072c4, - 0x32b3c75, 0xec1c6417, 0x32755e5, 0xec28562d, - 0x32371ae, 0xec344908, 0x31f8fcf, 0xec403ca5, - 0x31bb049, 0xec4c3106, 0x317d31c, 0xec582629, - 0x313f848, 0xec641c0e, 0x3101fce, 0xec7012b5, - 0x30c49ad, 0xec7c0a1d, 0x30875e5, 0xec880245, - 0x304a477, 0xec93fb2e, 0x300d563, 0xec9ff4d6, - 0x2fd08a9, 0xecabef3d, 0x2f93e4a, 0xecb7ea63, - 0x2f57644, 0xecc3e648, 0x2f1b099, 0xeccfe2ea, - 0x2eded49, 0xecdbe04a, 0x2ea2c53, 0xece7de66, - 0x2e66db8, 0xecf3dd3f, 0x2e2b178, 0xecffdcd4, - 0x2def794, 0xed0bdd25, 0x2db400a, 0xed17de31, - 0x2d78add, 0xed23dff7, 0x2d3d80a, 0xed2fe277, - 0x2d02794, 0xed3be5b1, 0x2cc7979, 0xed47e9a5, - 0x2c8cdbb, 0xed53ee51, 0x2c52459, 0xed5ff3b5, - 0x2c17d52, 0xed6bf9d1, 0x2bdd8a9, 0xed7800a5, - 0x2ba365c, 0xed84082f, 0x2b6966c, 0xed901070, - 0x2b2f8d8, 0xed9c1967, 0x2af5da2, 0xeda82313, - 0x2abc4c9, 0xedb42d74, 0x2a82e4d, 0xedc0388a, - 0x2a49a2e, 0xedcc4454, 0x2a1086d, 0xedd850d2, - 0x29d790a, 0xede45e03, 0x299ec05, 0xedf06be6, - 0x296615d, 0xedfc7a7c, 0x292d914, 0xee0889c4, - 0x28f5329, 0xee1499bd, 0x28bcf9c, 0xee20aa67, - 0x2884e6e, 0xee2cbbc1, 0x284cf9f, 0xee38cdcb, - 0x281532e, 0xee44e084, 0x27dd91c, 0xee50f3ed, - 0x27a616a, 0xee5d0804, 0x276ec16, 0xee691cc9, - 0x2737922, 0xee75323c, 0x270088e, 0xee81485c, - 0x26c9a58, 0xee8d5f29, 0x2692e83, 0xee9976a1, - 0x265c50e, 0xeea58ec6, 0x2625df8, 0xeeb1a796, - 0x25ef943, 0xeebdc110, 0x25b96ee, 0xeec9db35, - 0x25836f9, 0xeed5f604, 0x254d965, 0xeee2117c, - 0x2517e31, 0xeeee2d9d, 0x24e255e, 0xeefa4a67, - 0x24aceed, 0xef0667d9, 0x2477adc, 0xef1285f2, - 0x244292c, 0xef1ea4b2, 0x240d9de, 0xef2ac419, - 0x23d8cf1, 0xef36e426, 0x23a4265, 0xef4304d8, - 0x236fa3b, 0xef4f2630, 0x233b473, 0xef5b482d, - 0x230710d, 0xef676ace, 0x22d3009, 0xef738e12, - 0x229f167, 0xef7fb1fa, 0x226b528, 0xef8bd685, - 0x2237b4b, 0xef97fbb2, 0x22043d0, 0xefa42181, - 0x21d0eb8, 0xefb047f2, 0x219dc03, 0xefbc6f03, - 0x216abb1, 0xefc896b5, 0x2137dc2, 0xefd4bf08, - 0x2105236, 0xefe0e7f9, 0x20d290d, 0xefed118a, - 0x20a0248, 0xeff93bba, 0x206dde6, 0xf0056687, - 0x203bbe8, 0xf01191f3, 0x2009c4e, 0xf01dbdfb, - 0x1fd7f17, 0xf029eaa1, 0x1fa6445, 0xf03617e2, - 0x1f74bd6, 0xf04245c0, 0x1f435cc, 0xf04e7438, - 0x1f12227, 0xf05aa34c, 0x1ee10e5, 0xf066d2fa, - 0x1eb0209, 0xf0730342, 0x1e7f591, 0xf07f3424, - 0x1e4eb7e, 0xf08b659f, 0x1e1e3d0, 0xf09797b2, - 0x1dede87, 0xf0a3ca5d, 0x1dbdba3, 0xf0affda0, - 0x1d8db25, 0xf0bc317a, 0x1d5dd0c, 0xf0c865ea, - 0x1d2e158, 0xf0d49af1, 0x1cfe80a, 0xf0e0d08d, - 0x1ccf122, 0xf0ed06bf, 0x1c9fca0, 0xf0f93d86, - 0x1c70a84, 0xf10574e0, 0x1c41ace, 0xf111accf, - 0x1c12d7e, 0xf11de551, 0x1be4294, 0xf12a1e66, - 0x1bb5a11, 0xf136580d, 0x1b873f5, 0xf1429247, - 0x1b5903f, 0xf14ecd11, 0x1b2aef0, 0xf15b086d, - 0x1afd007, 0xf1674459, 0x1acf386, 0xf17380d6, - 0x1aa196c, 0xf17fbde2, 0x1a741b9, 0xf18bfb7d, - 0x1a46c6e, 0xf19839a6, 0x1a1998a, 0xf1a4785e, - 0x19ec90d, 0xf1b0b7a4, 0x19bfaf9, 0xf1bcf777, - 0x1992f4c, 0xf1c937d6, 0x1966606, 0xf1d578c2, - 0x1939f29, 0xf1e1ba3a, 0x190dab4, 0xf1edfc3d, - 0x18e18a7, 0xf1fa3ecb, 0x18b5903, 0xf20681e3, - 0x1889bc6, 0xf212c585, 0x185e0f3, 0xf21f09b1, - 0x1832888, 0xf22b4e66, 0x1807285, 0xf23793a3, - 0x17dbeec, 0xf243d968, 0x17b0dbb, 0xf2501fb5, - 0x1785ef4, 0xf25c6688, 0x175b296, 0xf268ade3, - 0x17308a1, 0xf274f5c3, 0x1706115, 0xf2813e2a, - 0x16dbbf3, 0xf28d8715, 0x16b193a, 0xf299d085, - 0x16878eb, 0xf2a61a7a, 0x165db05, 0xf2b264f2, - 0x1633f8a, 0xf2beafed, 0x160a678, 0xf2cafb6b, - 0x15e0fd1, 0xf2d7476c, 0x15b7b94, 0xf2e393ef, - 0x158e9c1, 0xf2efe0f2, 0x1565a58, 0xf2fc2e77, - 0x153cd5a, 0xf3087c7d, 0x15142c6, 0xf314cb02, - 0x14eba9d, 0xf3211a07, 0x14c34df, 0xf32d698a, - 0x149b18b, 0xf339b98d, 0x14730a3, 0xf3460a0d, - 0x144b225, 0xf3525b0b, 0x1423613, 0xf35eac86, - 0x13fbc6c, 0xf36afe7e, 0x13d4530, 0xf37750f2, - 0x13ad060, 0xf383a3e2, 0x1385dfb, 0xf38ff74d, - 0x135ee02, 0xf39c4b32, 0x1338075, 0xf3a89f92, - 0x1311553, 0xf3b4f46c, 0x12eac9d, 0xf3c149bf, - 0x12c4653, 0xf3cd9f8b, 0x129e276, 0xf3d9f5cf, - 0x1278104, 0xf3e64c8c, 0x12521ff, 0xf3f2a3bf, - 0x122c566, 0xf3fefb6a, 0x1206b39, 0xf40b538b, - 0x11e1379, 0xf417ac22, 0x11bbe26, 0xf424052f, - 0x1196b3f, 0xf4305eb0, 0x1171ac6, 0xf43cb8a7, - 0x114ccb9, 0xf4491311, 0x1128119, 0xf4556def, - 0x11037e6, 0xf461c940, 0x10df120, 0xf46e2504, - 0x10bacc8, 0xf47a8139, 0x1096add, 0xf486dde1, - 0x1072b5f, 0xf4933afa, 0x104ee4f, 0xf49f9884, - 0x102b3ac, 0xf4abf67e, 0x1007b77, 0xf4b854e7, - 0xfe45b0, 0xf4c4b3c0, 0xfc1257, 0xf4d11308, - 0xf9e16b, 0xf4dd72be, 0xf7b2ee, 0xf4e9d2e3, - 0xf586df, 0xf4f63374, 0xf35d3e, 0xf5029473, - 0xf1360b, 0xf50ef5de, 0xef1147, 0xf51b57b5, - 0xeceef1, 0xf527b9f7, 0xeacf09, 0xf5341ca5, - 0xe8b190, 0xf5407fbd, 0xe69686, 0xf54ce33f, - 0xe47deb, 0xf559472b, 0xe267be, 0xf565ab80, - 0xe05401, 0xf572103d, 0xde42b2, 0xf57e7563, - 0xdc33d2, 0xf58adaf0, 0xda2762, 0xf59740e5, - 0xd81d61, 0xf5a3a740, 0xd615cf, 0xf5b00e02, - 0xd410ad, 0xf5bc7529, 0xd20dfa, 0xf5c8dcb6, - 0xd00db6, 0xf5d544a7, 0xce0fe3, 0xf5e1acfd, - 0xcc147f, 0xf5ee15b7, 0xca1b8a, 0xf5fa7ed4, - 0xc82506, 0xf606e854, 0xc630f2, 0xf6135237, - 0xc43f4d, 0xf61fbc7b, 0xc25019, 0xf62c2721, - 0xc06355, 0xf6389228, 0xbe7901, 0xf644fd8f, - 0xbc911d, 0xf6516956, 0xbaabaa, 0xf65dd57d, - 0xb8c8a7, 0xf66a4203, 0xb6e815, 0xf676aee8, - 0xb509f3, 0xf6831c2b, 0xb32e42, 0xf68f89cb, - 0xb15502, 0xf69bf7c9, 0xaf7e33, 0xf6a86623, - 0xada9d4, 0xf6b4d4d9, 0xabd7e6, 0xf6c143ec, - 0xaa086a, 0xf6cdb359, 0xa83b5e, 0xf6da2321, - 0xa670c4, 0xf6e69344, 0xa4a89b, 0xf6f303c0, - 0xa2e2e3, 0xf6ff7496, 0xa11f9d, 0xf70be5c4, - 0x9f5ec8, 0xf718574b, 0x9da065, 0xf724c92a, - 0x9be473, 0xf7313b60, 0x9a2af3, 0xf73daded, - 0x9873e4, 0xf74a20d0, 0x96bf48, 0xf756940a, - 0x950d1d, 0xf7630799, 0x935d64, 0xf76f7b7d, - 0x91b01d, 0xf77befb5, 0x900548, 0xf7886442, - 0x8e5ce5, 0xf794d922, 0x8cb6f5, 0xf7a14e55, - 0x8b1376, 0xf7adc3db, 0x89726a, 0xf7ba39b3, - 0x87d3d0, 0xf7c6afdc, 0x8637a9, 0xf7d32657, - 0x849df4, 0xf7df9d22, 0x8306b2, 0xf7ec143e, - 0x8171e2, 0xf7f88ba9, 0x7fdf85, 0xf8050364, - 0x7e4f9b, 0xf8117b6d, 0x7cc223, 0xf81df3c5, - 0x7b371e, 0xf82a6c6a, 0x79ae8c, 0xf836e55d, - 0x78286e, 0xf8435e9d, 0x76a4c2, 0xf84fd829, - 0x752389, 0xf85c5201, 0x73a4c3, 0xf868cc24, - 0x722871, 0xf8754692, 0x70ae92, 0xf881c14b, - 0x6f3726, 0xf88e3c4d, 0x6dc22e, 0xf89ab799, - 0x6c4fa8, 0xf8a7332e, 0x6adf97, 0xf8b3af0c, - 0x6971f9, 0xf8c02b31, 0x6806ce, 0xf8cca79e, - 0x669e18, 0xf8d92452, 0x6537d4, 0xf8e5a14d, - 0x63d405, 0xf8f21e8e, 0x6272aa, 0xf8fe9c15, - 0x6113c2, 0xf90b19e0, 0x5fb74e, 0xf91797f0, - 0x5e5d4e, 0xf9241645, 0x5d05c3, 0xf93094dd, - 0x5bb0ab, 0xf93d13b8, 0x5a5e07, 0xf94992d7, - 0x590dd8, 0xf9561237, 0x57c01d, 0xf96291d9, - 0x5674d6, 0xf96f11bc, 0x552c03, 0xf97b91e1, - 0x53e5a5, 0xf9881245, 0x52a1bb, 0xf99492ea, - 0x516045, 0xf9a113cd, 0x502145, 0xf9ad94f0, - 0x4ee4b8, 0xf9ba1651, 0x4daaa1, 0xf9c697f0, - 0x4c72fe, 0xf9d319cc, 0x4b3dcf, 0xf9df9be6, - 0x4a0b16, 0xf9ec1e3b, 0x48dad1, 0xf9f8a0cd, - 0x47ad01, 0xfa05239a, 0x4681a6, 0xfa11a6a3, - 0x4558c0, 0xfa1e29e5, 0x44324f, 0xfa2aad62, - 0x430e53, 0xfa373119, 0x41eccc, 0xfa43b508, - 0x40cdba, 0xfa503930, 0x3fb11d, 0xfa5cbd91, - 0x3e96f6, 0xfa694229, 0x3d7f44, 0xfa75c6f8, - 0x3c6a07, 0xfa824bfd, 0x3b573f, 0xfa8ed139, - 0x3a46ed, 0xfa9b56ab, 0x393910, 0xfaa7dc52, - 0x382da8, 0xfab4622d, 0x3724b6, 0xfac0e83d, - 0x361e3a, 0xfacd6e81, 0x351a33, 0xfad9f4f8, - 0x3418a2, 0xfae67ba2, 0x331986, 0xfaf3027e, - 0x321ce0, 0xfaff898c, 0x3122b0, 0xfb0c10cb, - 0x302af5, 0xfb18983b, 0x2f35b1, 0xfb251fdc, - 0x2e42e2, 0xfb31a7ac, 0x2d5289, 0xfb3e2fac, - 0x2c64a6, 0xfb4ab7db, 0x2b7939, 0xfb574039, - 0x2a9042, 0xfb63c8c4, 0x29a9c1, 0xfb70517d, - 0x28c5b6, 0xfb7cda63, 0x27e421, 0xfb896375, - 0x270502, 0xfb95ecb4, 0x262859, 0xfba2761e, - 0x254e27, 0xfbaeffb3, 0x24766a, 0xfbbb8973, - 0x23a124, 0xfbc8135c, 0x22ce54, 0xfbd49d70, - 0x21fdfb, 0xfbe127ac, 0x213018, 0xfbedb212, - 0x2064ab, 0xfbfa3c9f, 0x1f9bb5, 0xfc06c754, - 0x1ed535, 0xfc135231, 0x1e112b, 0xfc1fdd34, - 0x1d4f99, 0xfc2c685d, 0x1c907c, 0xfc38f3ac, - 0x1bd3d6, 0xfc457f21, 0x1b19a7, 0xfc520aba, - 0x1a61ee, 0xfc5e9678, 0x19acac, 0xfc6b2259, - 0x18f9e1, 0xfc77ae5e, 0x18498c, 0xfc843a85, - 0x179bae, 0xfc90c6cf, 0x16f047, 0xfc9d533b, - 0x164757, 0xfca9dfc8, 0x15a0dd, 0xfcb66c77, - 0x14fcda, 0xfcc2f945, 0x145b4e, 0xfccf8634, - 0x13bc39, 0xfcdc1342, 0x131f9b, 0xfce8a06f, - 0x128574, 0xfcf52dbb, 0x11edc3, 0xfd01bb24, - 0x11588a, 0xfd0e48ab, 0x10c5c7, 0xfd1ad650, - 0x10357c, 0xfd276410, 0xfa7a8, 0xfd33f1ed, - 0xf1c4a, 0xfd407fe6, 0xe9364, 0xfd4d0df9, - 0xe0cf5, 0xfd599c28, 0xd88fd, 0xfd662a70, - 0xd077c, 0xfd72b8d2, 0xc8872, 0xfd7f474d, - 0xc0be0, 0xfd8bd5e1, 0xb91c4, 0xfd98648d, - 0xb1a20, 0xfda4f351, 0xaa4f3, 0xfdb1822c, - 0xa323d, 0xfdbe111e, 0x9c1ff, 0xfdcaa027, - 0x95438, 0xfdd72f45, 0x8e8e8, 0xfde3be78, - 0x8800f, 0xfdf04dc0, 0x819ae, 0xfdfcdd1d, - 0x7b5c4, 0xfe096c8d, 0x75452, 0xfe15fc11, - 0x6f556, 0xfe228ba7, 0x698d3, 0xfe2f1b50, - 0x63ec6, 0xfe3bab0b, 0x5e731, 0xfe483ad8, - 0x59214, 0xfe54cab5, 0x53f6e, 0xfe615aa3, - 0x4ef3f, 0xfe6deaa1, 0x4a188, 0xfe7a7aae, - 0x45648, 0xfe870aca, 0x40d80, 0xfe939af5, - 0x3c72f, 0xfea02b2e, 0x38356, 0xfeacbb74, - 0x341f4, 0xfeb94bc8, 0x3030a, 0xfec5dc28, - 0x2c697, 0xfed26c94, 0x28c9c, 0xfedefd0c, - 0x25519, 0xfeeb8d8f, 0x2200d, 0xfef81e1d, - 0x1ed78, 0xff04aeb5, 0x1bd5c, 0xff113f56, - 0x18fb6, 0xff1dd001, 0x16489, 0xff2a60b4, - 0x13bd3, 0xff36f170, 0x11594, 0xff438234, - 0xf1ce, 0xff5012fe, 0xd07e, 0xff5ca3d0, - 0xb1a7, 0xff6934a8, 0x9547, 0xff75c585, - 0x7b5f, 0xff825668, 0x63ee, 0xff8ee750, - 0x4ef5, 0xff9b783c, 0x3c74, 0xffa8092c, - 0x2c6a, 0xffb49a1f, 0x1ed8, 0xffc12b16, - 0x13bd, 0xffcdbc0f, 0xb1a, 0xffda4d09, - 0x4ef, 0xffe6de05, 0x13c, 0xfff36f02, - 0x0, 0x0, 0x13c, 0xc90fe, - 0x4ef, 0x1921fb, 0xb1a, 0x25b2f7, - 0x13bd, 0x3243f1, 0x1ed8, 0x3ed4ea, - 0x2c6a, 0x4b65e1, 0x3c74, 0x57f6d4, - 0x4ef5, 0x6487c4, 0x63ee, 0x7118b0, - 0x7b5f, 0x7da998, 0x9547, 0x8a3a7b, - 0xb1a7, 0x96cb58, 0xd07e, 0xa35c30, - 0xf1ce, 0xafed02, 0x11594, 0xbc7dcc, - 0x13bd3, 0xc90e90, 0x16489, 0xd59f4c, - 0x18fb6, 0xe22fff, 0x1bd5c, 0xeec0aa, - 0x1ed78, 0xfb514b, 0x2200d, 0x107e1e3, - 0x25519, 0x1147271, 0x28c9c, 0x12102f4, - 0x2c697, 0x12d936c, 0x3030a, 0x13a23d8, - 0x341f4, 0x146b438, 0x38356, 0x153448c, - 0x3c72f, 0x15fd4d2, 0x40d80, 0x16c650b, - 0x45648, 0x178f536, 0x4a188, 0x1858552, - 0x4ef3f, 0x192155f, 0x53f6e, 0x19ea55d, - 0x59214, 0x1ab354b, 0x5e731, 0x1b7c528, - 0x63ec6, 0x1c454f5, 0x698d3, 0x1d0e4b0, - 0x6f556, 0x1dd7459, 0x75452, 0x1ea03ef, - 0x7b5c4, 0x1f69373, 0x819ae, 0x20322e3, - 0x8800f, 0x20fb240, 0x8e8e8, 0x21c4188, - 0x95438, 0x228d0bb, 0x9c1ff, 0x2355fd9, - 0xa323d, 0x241eee2, 0xaa4f3, 0x24e7dd4, - 0xb1a20, 0x25b0caf, 0xb91c4, 0x2679b73, - 0xc0be0, 0x2742a1f, 0xc8872, 0x280b8b3, - 0xd077c, 0x28d472e, 0xd88fd, 0x299d590, - 0xe0cf5, 0x2a663d8, 0xe9364, 0x2b2f207, - 0xf1c4a, 0x2bf801a, 0xfa7a8, 0x2cc0e13, - 0x10357c, 0x2d89bf0, 0x10c5c7, 0x2e529b0, - 0x11588a, 0x2f1b755, 0x11edc3, 0x2fe44dc, - 0x128574, 0x30ad245, 0x131f9b, 0x3175f91, - 0x13bc39, 0x323ecbe, 0x145b4e, 0x33079cc, - 0x14fcda, 0x33d06bb, 0x15a0dd, 0x3499389, - 0x164757, 0x3562038, 0x16f047, 0x362acc5, - 0x179bae, 0x36f3931, 0x18498c, 0x37bc57b, - 0x18f9e1, 0x38851a2, 0x19acac, 0x394dda7, - 0x1a61ee, 0x3a16988, 0x1b19a7, 0x3adf546, - 0x1bd3d6, 0x3ba80df, 0x1c907c, 0x3c70c54, - 0x1d4f99, 0x3d397a3, 0x1e112b, 0x3e022cc, - 0x1ed535, 0x3ecadcf, 0x1f9bb5, 0x3f938ac, - 0x2064ab, 0x405c361, 0x213018, 0x4124dee, - 0x21fdfb, 0x41ed854, 0x22ce54, 0x42b6290, - 0x23a124, 0x437eca4, 0x24766a, 0x444768d, - 0x254e27, 0x451004d, 0x262859, 0x45d89e2, - 0x270502, 0x46a134c, 0x27e421, 0x4769c8b, - 0x28c5b6, 0x483259d, 0x29a9c1, 0x48fae83, - 0x2a9042, 0x49c373c, 0x2b7939, 0x4a8bfc7, - 0x2c64a6, 0x4b54825, 0x2d5289, 0x4c1d054, - 0x2e42e2, 0x4ce5854, 0x2f35b1, 0x4dae024, - 0x302af5, 0x4e767c5, 0x3122b0, 0x4f3ef35, - 0x321ce0, 0x5007674, 0x331986, 0x50cfd82, - 0x3418a2, 0x519845e, 0x351a33, 0x5260b08, - 0x361e3a, 0x532917f, 0x3724b6, 0x53f17c3, - 0x382da8, 0x54b9dd3, 0x393910, 0x55823ae, - 0x3a46ed, 0x564a955, 0x3b573f, 0x5712ec7, - 0x3c6a07, 0x57db403, 0x3d7f44, 0x58a3908, - 0x3e96f6, 0x596bdd7, 0x3fb11d, 0x5a3426f, - 0x40cdba, 0x5afc6d0, 0x41eccc, 0x5bc4af8, - 0x430e53, 0x5c8cee7, 0x44324f, 0x5d5529e, - 0x4558c0, 0x5e1d61b, 0x4681a6, 0x5ee595d, - 0x47ad01, 0x5fadc66, 0x48dad1, 0x6075f33, - 0x4a0b16, 0x613e1c5, 0x4b3dcf, 0x620641a, - 0x4c72fe, 0x62ce634, 0x4daaa1, 0x6396810, - 0x4ee4b8, 0x645e9af, 0x502145, 0x6526b10, - 0x516045, 0x65eec33, 0x52a1bb, 0x66b6d16, - 0x53e5a5, 0x677edbb, 0x552c03, 0x6846e1f, - 0x5674d6, 0x690ee44, 0x57c01d, 0x69d6e27, - 0x590dd8, 0x6a9edc9, 0x5a5e07, 0x6b66d29, - 0x5bb0ab, 0x6c2ec48, 0x5d05c3, 0x6cf6b23, - 0x5e5d4e, 0x6dbe9bb, 0x5fb74e, 0x6e86810, - 0x6113c2, 0x6f4e620, 0x6272aa, 0x70163eb, - 0x63d405, 0x70de172, 0x6537d4, 0x71a5eb3, - 0x669e18, 0x726dbae, 0x6806ce, 0x7335862, - 0x6971f9, 0x73fd4cf, 0x6adf97, 0x74c50f4, - 0x6c4fa8, 0x758ccd2, 0x6dc22e, 0x7654867, - 0x6f3726, 0x771c3b3, 0x70ae92, 0x77e3eb5, - 0x722871, 0x78ab96e, 0x73a4c3, 0x79733dc, - 0x752389, 0x7a3adff, 0x76a4c2, 0x7b027d7, - 0x78286e, 0x7bca163, 0x79ae8c, 0x7c91aa3, - 0x7b371e, 0x7d59396, 0x7cc223, 0x7e20c3b, - 0x7e4f9b, 0x7ee8493, 0x7fdf85, 0x7fafc9c, - 0x8171e2, 0x8077457, 0x8306b2, 0x813ebc2, - 0x849df4, 0x82062de, 0x8637a9, 0x82cd9a9, - 0x87d3d0, 0x8395024, 0x89726a, 0x845c64d, - 0x8b1376, 0x8523c25, 0x8cb6f5, 0x85eb1ab, - 0x8e5ce5, 0x86b26de, 0x900548, 0x8779bbe, - 0x91b01d, 0x884104b, 0x935d64, 0x8908483, - 0x950d1d, 0x89cf867, 0x96bf48, 0x8a96bf6, - 0x9873e4, 0x8b5df30, 0x9a2af3, 0x8c25213, - 0x9be473, 0x8cec4a0, 0x9da065, 0x8db36d6, - 0x9f5ec8, 0x8e7a8b5, 0xa11f9d, 0x8f41a3c, - 0xa2e2e3, 0x9008b6a, 0xa4a89b, 0x90cfc40, - 0xa670c4, 0x9196cbc, 0xa83b5e, 0x925dcdf, - 0xaa086a, 0x9324ca7, 0xabd7e6, 0x93ebc14, - 0xada9d4, 0x94b2b27, 0xaf7e33, 0x95799dd, - 0xb15502, 0x9640837, 0xb32e42, 0x9707635, - 0xb509f3, 0x97ce3d5, 0xb6e815, 0x9895118, - 0xb8c8a7, 0x995bdfd, 0xbaabaa, 0x9a22a83, - 0xbc911d, 0x9ae96aa, 0xbe7901, 0x9bb0271, - 0xc06355, 0x9c76dd8, 0xc25019, 0x9d3d8df, - 0xc43f4d, 0x9e04385, 0xc630f2, 0x9ecadc9, - 0xc82506, 0x9f917ac, 0xca1b8a, 0xa05812c, - 0xcc147f, 0xa11ea49, 0xce0fe3, 0xa1e5303, - 0xd00db6, 0xa2abb59, 0xd20dfa, 0xa37234a, - 0xd410ad, 0xa438ad7, 0xd615cf, 0xa4ff1fe, - 0xd81d61, 0xa5c58c0, 0xda2762, 0xa68bf1b, - 0xdc33d2, 0xa752510, 0xde42b2, 0xa818a9d, - 0xe05401, 0xa8defc3, 0xe267be, 0xa9a5480, - 0xe47deb, 0xaa6b8d5, 0xe69686, 0xab31cc1, - 0xe8b190, 0xabf8043, 0xeacf09, 0xacbe35b, - 0xeceef1, 0xad84609, 0xef1147, 0xae4a84b, - 0xf1360b, 0xaf10a22, 0xf35d3e, 0xafd6b8d, - 0xf586df, 0xb09cc8c, 0xf7b2ee, 0xb162d1d, - 0xf9e16b, 0xb228d42, 0xfc1257, 0xb2eecf8, - 0xfe45b0, 0xb3b4c40, 0x1007b77, 0xb47ab19, - 0x102b3ac, 0xb540982, 0x104ee4f, 0xb60677c, - 0x1072b5f, 0xb6cc506, 0x1096add, 0xb79221f, - 0x10bacc8, 0xb857ec7, 0x10df120, 0xb91dafc, - 0x11037e6, 0xb9e36c0, 0x1128119, 0xbaa9211, - 0x114ccb9, 0xbb6ecef, 0x1171ac6, 0xbc34759, - 0x1196b3f, 0xbcfa150, 0x11bbe26, 0xbdbfad1, - 0x11e1379, 0xbe853de, 0x1206b39, 0xbf4ac75, - 0x122c566, 0xc010496, 0x12521ff, 0xc0d5c41, - 0x1278104, 0xc19b374, 0x129e276, 0xc260a31, - 0x12c4653, 0xc326075, 0x12eac9d, 0xc3eb641, - 0x1311553, 0xc4b0b94, 0x1338075, 0xc57606e, - 0x135ee02, 0xc63b4ce, 0x1385dfb, 0xc7008b3, - 0x13ad060, 0xc7c5c1e, 0x13d4530, 0xc88af0e, - 0x13fbc6c, 0xc950182, 0x1423613, 0xca1537a, - 0x144b225, 0xcada4f5, 0x14730a3, 0xcb9f5f3, - 0x149b18b, 0xcc64673, 0x14c34df, 0xcd29676, - 0x14eba9d, 0xcdee5f9, 0x15142c6, 0xceb34fe, - 0x153cd5a, 0xcf78383, 0x1565a58, 0xd03d189, - 0x158e9c1, 0xd101f0e, 0x15b7b94, 0xd1c6c11, - 0x15e0fd1, 0xd28b894, 0x160a678, 0xd350495, - 0x1633f8a, 0xd415013, 0x165db05, 0xd4d9b0e, - 0x16878eb, 0xd59e586, 0x16b193a, 0xd662f7b, - 0x16dbbf3, 0xd7278eb, 0x1706115, 0xd7ec1d6, - 0x17308a1, 0xd8b0a3d, 0x175b296, 0xd97521d, - 0x1785ef4, 0xda39978, 0x17b0dbb, 0xdafe04b, - 0x17dbeec, 0xdbc2698, 0x1807285, 0xdc86c5d, - 0x1832888, 0xdd4b19a, 0x185e0f3, 0xde0f64f, - 0x1889bc6, 0xded3a7b, 0x18b5903, 0xdf97e1d, - 0x18e18a7, 0xe05c135, 0x190dab4, 0xe1203c3, - 0x1939f29, 0xe1e45c6, 0x1966606, 0xe2a873e, - 0x1992f4c, 0xe36c82a, 0x19bfaf9, 0xe430889, - 0x19ec90d, 0xe4f485c, 0x1a1998a, 0xe5b87a2, - 0x1a46c6e, 0xe67c65a, 0x1a741b9, 0xe740483, - 0x1aa196c, 0xe80421e, 0x1acf386, 0xe8c7f2a, - 0x1afd007, 0xe98bba7, 0x1b2aef0, 0xea4f793, - 0x1b5903f, 0xeb132ef, 0x1b873f5, 0xebd6db9, - 0x1bb5a11, 0xec9a7f3, 0x1be4294, 0xed5e19a, - 0x1c12d7e, 0xee21aaf, 0x1c41ace, 0xeee5331, - 0x1c70a84, 0xefa8b20, 0x1c9fca0, 0xf06c27a, - 0x1ccf122, 0xf12f941, 0x1cfe80a, 0xf1f2f73, - 0x1d2e158, 0xf2b650f, 0x1d5dd0c, 0xf379a16, - 0x1d8db25, 0xf43ce86, 0x1dbdba3, 0xf500260, - 0x1dede87, 0xf5c35a3, 0x1e1e3d0, 0xf68684e, - 0x1e4eb7e, 0xf749a61, 0x1e7f591, 0xf80cbdc, - 0x1eb0209, 0xf8cfcbe, 0x1ee10e5, 0xf992d06, - 0x1f12227, 0xfa55cb4, 0x1f435cc, 0xfb18bc8, - 0x1f74bd6, 0xfbdba40, 0x1fa6445, 0xfc9e81e, - 0x1fd7f17, 0xfd6155f, 0x2009c4e, 0xfe24205, - 0x203bbe8, 0xfee6e0d, 0x206dde6, 0xffa9979, - 0x20a0248, 0x1006c446, 0x20d290d, 0x1012ee76, - 0x2105236, 0x101f1807, 0x2137dc2, 0x102b40f8, - 0x216abb1, 0x1037694b, 0x219dc03, 0x104390fd, - 0x21d0eb8, 0x104fb80e, 0x22043d0, 0x105bde7f, - 0x2237b4b, 0x1068044e, 0x226b528, 0x1074297b, - 0x229f167, 0x10804e06, 0x22d3009, 0x108c71ee, - 0x230710d, 0x10989532, 0x233b473, 0x10a4b7d3, - 0x236fa3b, 0x10b0d9d0, 0x23a4265, 0x10bcfb28, - 0x23d8cf1, 0x10c91bda, 0x240d9de, 0x10d53be7, - 0x244292c, 0x10e15b4e, 0x2477adc, 0x10ed7a0e, - 0x24aceed, 0x10f99827, 0x24e255e, 0x1105b599, - 0x2517e31, 0x1111d263, 0x254d965, 0x111dee84, - 0x25836f9, 0x112a09fc, 0x25b96ee, 0x113624cb, - 0x25ef943, 0x11423ef0, 0x2625df8, 0x114e586a, - 0x265c50e, 0x115a713a, 0x2692e83, 0x1166895f, - 0x26c9a58, 0x1172a0d7, 0x270088e, 0x117eb7a4, - 0x2737922, 0x118acdc4, 0x276ec16, 0x1196e337, - 0x27a616a, 0x11a2f7fc, 0x27dd91c, 0x11af0c13, - 0x281532e, 0x11bb1f7c, 0x284cf9f, 0x11c73235, - 0x2884e6e, 0x11d3443f, 0x28bcf9c, 0x11df5599, - 0x28f5329, 0x11eb6643, 0x292d914, 0x11f7763c, - 0x296615d, 0x12038584, 0x299ec05, 0x120f941a, - 0x29d790a, 0x121ba1fd, 0x2a1086d, 0x1227af2e, - 0x2a49a2e, 0x1233bbac, 0x2a82e4d, 0x123fc776, - 0x2abc4c9, 0x124bd28c, 0x2af5da2, 0x1257dced, - 0x2b2f8d8, 0x1263e699, 0x2b6966c, 0x126fef90, - 0x2ba365c, 0x127bf7d1, 0x2bdd8a9, 0x1287ff5b, - 0x2c17d52, 0x1294062f, 0x2c52459, 0x12a00c4b, - 0x2c8cdbb, 0x12ac11af, 0x2cc7979, 0x12b8165b, - 0x2d02794, 0x12c41a4f, 0x2d3d80a, 0x12d01d89, - 0x2d78add, 0x12dc2009, 0x2db400a, 0x12e821cf, - 0x2def794, 0x12f422db, 0x2e2b178, 0x1300232c, - 0x2e66db8, 0x130c22c1, 0x2ea2c53, 0x1318219a, - 0x2eded49, 0x13241fb6, 0x2f1b099, 0x13301d16, - 0x2f57644, 0x133c19b8, 0x2f93e4a, 0x1348159d, - 0x2fd08a9, 0x135410c3, 0x300d563, 0x13600b2a, - 0x304a477, 0x136c04d2, 0x30875e5, 0x1377fdbb, - 0x30c49ad, 0x1383f5e3, 0x3101fce, 0x138fed4b, - 0x313f848, 0x139be3f2, 0x317d31c, 0x13a7d9d7, - 0x31bb049, 0x13b3cefa, 0x31f8fcf, 0x13bfc35b, - 0x32371ae, 0x13cbb6f8, 0x32755e5, 0x13d7a9d3, - 0x32b3c75, 0x13e39be9, 0x32f255e, 0x13ef8d3c, - 0x333109e, 0x13fb7dc9, 0x336fe37, 0x14076d91, - 0x33aee27, 0x14135c94, 0x33ee070, 0x141f4ad1, - 0x342d510, 0x142b3846, 0x346cc07, 0x143724f5, - 0x34ac556, 0x144310dd, 0x34ec0fc, 0x144efbfc, - 0x352bef9, 0x145ae653, 0x356bf4d, 0x1466cfe1, - 0x35ac1f7, 0x1472b8a5, 0x35ec6f8, 0x147ea0a0, - 0x362ce50, 0x148a87d1, 0x366d7fd, 0x14966e36, - 0x36ae401, 0x14a253d1, 0x36ef25b, 0x14ae38a0, - 0x373030a, 0x14ba1ca3, 0x377160f, 0x14c5ffd9, - 0x37b2b6a, 0x14d1e242, 0x37f4319, 0x14ddc3de, - 0x3835d1e, 0x14e9a4ac, 0x3877978, 0x14f584ac, - 0x38b9827, 0x150163dc, 0x38fb92a, 0x150d423d, - 0x393dc82, 0x15191fcf, 0x398022f, 0x1524fc90, - 0x39c2a2f, 0x1530d881, 0x3a05484, 0x153cb3a0, - 0x3a4812c, 0x15488dee, 0x3a8b028, 0x1554676a, - 0x3ace178, 0x15604013, 0x3b1151b, 0x156c17e9, - 0x3b54b11, 0x1577eeec, 0x3b9835a, 0x1583c51b, - 0x3bdbdf6, 0x158f9a76, 0x3c1fae5, 0x159b6efb, - 0x3c63a26, 0x15a742ac, 0x3ca7bba, 0x15b31587, - 0x3cebfa0, 0x15bee78c, 0x3d305d8, 0x15cab8ba, - 0x3d74e62, 0x15d68911, 0x3db993e, 0x15e25890, - 0x3dfe66c, 0x15ee2738, 0x3e435ea, 0x15f9f507, - 0x3e887bb, 0x1605c1fd, 0x3ecdbdc, 0x16118e1a, - 0x3f1324e, 0x161d595d, 0x3f58b10, 0x162923c5, - 0x3f9e624, 0x1634ed53, 0x3fe4388, 0x1640b606, - 0x402a33c, 0x164c7ddd, 0x4070540, 0x165844d8, - 0x40b6994, 0x16640af7, 0x40fd037, 0x166fd039, - 0x414392b, 0x167b949d, 0x418a46d, 0x16875823, - 0x41d11ff, 0x16931acb, 0x42181e0, 0x169edc94, - 0x425f410, 0x16aa9d7e, 0x42a688f, 0x16b65d88, - 0x42edf5c, 0x16c21cb2, 0x4335877, 0x16cddafb, - 0x437d3e1, 0x16d99864, 0x43c5199, 0x16e554ea, - 0x440d19e, 0x16f1108f, 0x44553f2, 0x16fccb51, - 0x449d892, 0x17088531, 0x44e5f80, 0x17143e2d, - 0x452e8bc, 0x171ff646, 0x4577444, 0x172bad7a, - 0x45c0219, 0x173763c9, 0x460923b, 0x17431933, - 0x46524a9, 0x174ecdb8, 0x469b963, 0x175a8157, - 0x46e5069, 0x1766340f, 0x472e9bc, 0x1771e5e0, - 0x477855a, 0x177d96ca, 0x47c2344, 0x178946cc, - 0x480c379, 0x1794f5e6, 0x48565f9, 0x17a0a417, - 0x48a0ac4, 0x17ac515f, 0x48eb1db, 0x17b7fdbd, - 0x4935b3c, 0x17c3a931, 0x49806e7, 0x17cf53bb, - 0x49cb4dd, 0x17dafd59, 0x4a1651c, 0x17e6a60c, - 0x4a617a6, 0x17f24dd3, 0x4aacc7a, 0x17fdf4ae, - 0x4af8397, 0x18099a9c, 0x4b43cfd, 0x18153f9d, - 0x4b8f8ad, 0x1820e3b0, 0x4bdb6a6, 0x182c86d5, - 0x4c276e8, 0x1838290c, 0x4c73972, 0x1843ca53, - 0x4cbfe45, 0x184f6aab, 0x4d0c560, 0x185b0a13, - 0x4d58ec3, 0x1866a88a, 0x4da5a6f, 0x18724611, - 0x4df2862, 0x187de2a7, 0x4e3f89c, 0x18897e4a, - 0x4e8cb1e, 0x189518fc, 0x4ed9fe7, 0x18a0b2bb, - 0x4f276f7, 0x18ac4b87, 0x4f7504e, 0x18b7e35f, - 0x4fc2bec, 0x18c37a44, 0x50109d0, 0x18cf1034, - 0x505e9fb, 0x18daa52f, 0x50acc6b, 0x18e63935, - 0x50fb121, 0x18f1cc45, 0x514981d, 0x18fd5e5f, - 0x519815f, 0x1908ef82, 0x51e6ce6, 0x19147fae, - 0x5235ab2, 0x19200ee3, 0x5284ac3, 0x192b9d1f, - 0x52d3d18, 0x19372a64, 0x53231b3, 0x1942b6af, - 0x5372891, 0x194e4201, 0x53c21b4, 0x1959cc5a, - 0x5411d1b, 0x196555b8, 0x5461ac6, 0x1970de1b, - 0x54b1ab4, 0x197c6584, 0x5501ce5, 0x1987ebf0, - 0x555215a, 0x19937161, 0x55a2812, 0x199ef5d6, - 0x55f310d, 0x19aa794d, 0x5643c4a, 0x19b5fbc8, - 0x56949ca, 0x19c17d44, 0x56e598c, 0x19ccfdc2, - 0x5736b90, 0x19d87d42, 0x5787fd6, 0x19e3fbc3, - 0x57d965d, 0x19ef7944, 0x582af26, 0x19faf5c5, - 0x587ca31, 0x1a067145, 0x58ce77c, 0x1a11ebc5, - 0x5920708, 0x1a1d6544, 0x59728d5, 0x1a28ddc0, - 0x59c4ce3, 0x1a34553b, 0x5a17330, 0x1a3fcbb3, - 0x5a69bbe, 0x1a4b4128, 0x5abc68c, 0x1a56b599, - 0x5b0f399, 0x1a622907, 0x5b622e6, 0x1a6d9b70, - 0x5bb5472, 0x1a790cd4, 0x5c0883d, 0x1a847d33, - 0x5c5be47, 0x1a8fec8c, 0x5caf690, 0x1a9b5adf, - 0x5d03118, 0x1aa6c82b, 0x5d56ddd, 0x1ab23471, - 0x5daace1, 0x1abd9faf, 0x5dfee22, 0x1ac909e5, - 0x5e531a1, 0x1ad47312, 0x5ea775e, 0x1adfdb37, - 0x5efbf58, 0x1aeb4253, 0x5f5098f, 0x1af6a865, - 0x5fa5603, 0x1b020d6c, 0x5ffa4b3, 0x1b0d716a, - 0x604f5a0, 0x1b18d45c, 0x60a48c9, 0x1b243643, - 0x60f9e2e, 0x1b2f971e, 0x614f5cf, 0x1b3af6ec, - 0x61a4fac, 0x1b4655ae, 0x61fabc4, 0x1b51b363, - 0x6250a18, 0x1b5d100a, 0x62a6aa6, 0x1b686ba3, - 0x62fcd6f, 0x1b73c62d, 0x6353273, 0x1b7f1fa9, - 0x63a99b1, 0x1b8a7815, 0x6400329, 0x1b95cf71, - 0x6456edb, 0x1ba125bd, 0x64adcc7, 0x1bac7af9, - 0x6504ced, 0x1bb7cf23, 0x655bf4c, 0x1bc3223c, - 0x65b33e4, 0x1bce7442, 0x660aab5, 0x1bd9c537, - 0x66623be, 0x1be51518, 0x66b9f01, 0x1bf063e6, - 0x6711c7b, 0x1bfbb1a0, 0x6769c2e, 0x1c06fe46, - 0x67c1e18, 0x1c1249d8, 0x681a23a, 0x1c1d9454, - 0x6872894, 0x1c28ddbb, 0x68cb124, 0x1c34260c, - 0x6923bec, 0x1c3f6d47, 0x697c8eb, 0x1c4ab36b, - 0x69d5820, 0x1c55f878, 0x6a2e98b, 0x1c613c6d, - 0x6a87d2d, 0x1c6c7f4a, 0x6ae1304, 0x1c77c10e, - 0x6b3ab12, 0x1c8301b9, 0x6b94554, 0x1c8e414b, - 0x6bee1cd, 0x1c997fc4, 0x6c4807a, 0x1ca4bd21, - 0x6ca215c, 0x1caff965, 0x6cfc472, 0x1cbb348d, - 0x6d569be, 0x1cc66e99, 0x6db113d, 0x1cd1a78a, - 0x6e0baf0, 0x1cdcdf5e, 0x6e666d7, 0x1ce81615, - 0x6ec14f2, 0x1cf34baf, 0x6f1c540, 0x1cfe802b, - 0x6f777c1, 0x1d09b389, 0x6fd2c75, 0x1d14e5c9, - 0x702e35c, 0x1d2016e9, 0x7089c75, 0x1d2b46ea, - 0x70e57c0, 0x1d3675cb, 0x714153e, 0x1d41a38c, - 0x719d4ed, 0x1d4cd02c, 0x71f96ce, 0x1d57fbaa, - 0x7255ae0, 0x1d632608, 0x72b2123, 0x1d6e4f43, - 0x730e997, 0x1d79775c, 0x736b43c, 0x1d849e51, - 0x73c8111, 0x1d8fc424, 0x7425016, 0x1d9ae8d2, - 0x748214c, 0x1da60c5d, 0x74df4b1, 0x1db12ec3, - 0x753ca46, 0x1dbc5004, 0x759a20a, 0x1dc7701f, - 0x75f7bfe, 0x1dd28f15, 0x7655820, 0x1dddace4, - 0x76b3671, 0x1de8c98c, 0x77116f0, 0x1df3e50d, - 0x776f99d, 0x1dfeff67, 0x77cde79, 0x1e0a1898, - 0x782c582, 0x1e1530a1, 0x788aeb9, 0x1e204781, - 0x78e9a1d, 0x1e2b5d38, 0x79487ae, 0x1e3671c5, - 0x79a776c, 0x1e418528, 0x7a06957, 0x1e4c9760, - 0x7a65d6e, 0x1e57a86d, 0x7ac53b1, 0x1e62b84f, - 0x7b24c20, 0x1e6dc705, 0x7b846ba, 0x1e78d48e, - 0x7be4381, 0x1e83e0eb, 0x7c44272, 0x1e8eec1b, - 0x7ca438f, 0x1e99f61d, 0x7d046d6, 0x1ea4fef0, - 0x7d64c47, 0x1eb00696, 0x7dc53e3, 0x1ebb0d0d, - 0x7e25daa, 0x1ec61254, 0x7e8699a, 0x1ed1166b, - 0x7ee77b3, 0x1edc1953, 0x7f487f6, 0x1ee71b0a, - 0x7fa9a62, 0x1ef21b90, 0x800aef7, 0x1efd1ae4, - 0x806c5b5, 0x1f081907, 0x80cde9b, 0x1f1315f7, - 0x812f9a9, 0x1f1e11b5, 0x81916df, 0x1f290c3f, - 0x81f363d, 0x1f340596, 0x82557c3, 0x1f3efdb9, - 0x82b7b70, 0x1f49f4a8, 0x831a143, 0x1f54ea62, - 0x837c93e, 0x1f5fdee6, 0x83df35f, 0x1f6ad235, - 0x8441fa6, 0x1f75c44e, 0x84a4e14, 0x1f80b531, - 0x8507ea7, 0x1f8ba4dc, 0x856b160, 0x1f969350, - 0x85ce63e, 0x1fa1808c, 0x8631d42, 0x1fac6c91, - 0x869566a, 0x1fb7575c, 0x86f91b7, 0x1fc240ef, - 0x875cf28, 0x1fcd2948, 0x87c0ebd, 0x1fd81067, - 0x8825077, 0x1fe2f64c, 0x8889454, 0x1feddaf6, - 0x88eda54, 0x1ff8be65, 0x8952278, 0x2003a099, - 0x89b6cbf, 0x200e8190, 0x8a1b928, 0x2019614c, - 0x8a807b4, 0x20243fca, 0x8ae5862, 0x202f1d0b, - 0x8b4ab32, 0x2039f90f, 0x8bb0023, 0x2044d3d4, - 0x8c15736, 0x204fad5b, 0x8c7b06b, 0x205a85a3, - 0x8ce0bc0, 0x20655cac, 0x8d46936, 0x20703275, - 0x8dac8cd, 0x207b06fe, 0x8e12a84, 0x2085da46, - 0x8e78e5b, 0x2090ac4d, 0x8edf452, 0x209b7d13, - 0x8f45c68, 0x20a64c97, 0x8fac69e, 0x20b11ad9, - 0x90132f2, 0x20bbe7d8, 0x907a166, 0x20c6b395, - 0x90e11f7, 0x20d17e0d, 0x91484a8, 0x20dc4742, - 0x91af976, 0x20e70f32, 0x9217062, 0x20f1d5de, - 0x927e96b, 0x20fc9b44, 0x92e6492, 0x21075f65, - 0x934e1d6, 0x21122240, 0x93b6137, 0x211ce3d5, - 0x941e2b4, 0x2127a423, 0x948664d, 0x21326329, - 0x94eec03, 0x213d20e8, 0x95573d4, 0x2147dd5f, - 0x95bfdc1, 0x2152988d, 0x96289c9, 0x215d5273, - 0x96917ec, 0x21680b0f, 0x96fa82a, 0x2172c262, - 0x9763a83, 0x217d786a, 0x97ccef5, 0x21882d28, - 0x9836582, 0x2192e09b, 0x989fe29, 0x219d92c2, - 0x99098e9, 0x21a8439e, 0x99735c2, 0x21b2f32e, - 0x99dd4b4, 0x21bda171, 0x9a475bf, 0x21c84e67, - 0x9ab18e3, 0x21d2fa0f, 0x9b1be1e, 0x21dda46a, - 0x9b86572, 0x21e84d76, 0x9bf0edd, 0x21f2f534, - 0x9c5ba60, 0x21fd9ba3, 0x9cc67fa, 0x220840c2, - 0x9d317ab, 0x2212e492, 0x9d9c973, 0x221d8711, - 0x9e07d51, 0x2228283f, 0x9e73346, 0x2232c81c, - 0x9edeb50, 0x223d66a8, 0x9f4a570, 0x224803e2, - 0x9fb61a5, 0x22529fca, 0xa021fef, 0x225d3a5e, - 0xa08e04f, 0x2267d3a0, 0xa0fa2c3, 0x22726b8e, - 0xa16674b, 0x227d0228, 0xa1d2de7, 0x2287976e, - 0xa23f698, 0x22922b5e, 0xa2ac15b, 0x229cbdfa, - 0xa318e32, 0x22a74f40, 0xa385d1d, 0x22b1df30, - 0xa3f2e19, 0x22bc6dca, 0xa460129, 0x22c6fb0c, - 0xa4cd64b, 0x22d186f8, 0xa53ad7e, 0x22dc118c, - 0xa5a86c4, 0x22e69ac8, 0xa61621b, 0x22f122ab, - 0xa683f83, 0x22fba936, 0xa6f1efc, 0x23062e67, - 0xa760086, 0x2310b23e, 0xa7ce420, 0x231b34bc, - 0xa83c9ca, 0x2325b5df, 0xa8ab184, 0x233035a7, - 0xa919b4e, 0x233ab414, 0xa988727, 0x23453125, - 0xa9f750f, 0x234facda, 0xaa66506, 0x235a2733, - 0xaad570c, 0x2364a02e, 0xab44b1f, 0x236f17cc, - 0xabb4141, 0x23798e0d, 0xac23971, 0x238402ef, - 0xac933ae, 0x238e7673, 0xad02ff8, 0x2398e898, - 0xad72e4f, 0x23a3595e, 0xade2eb3, 0x23adc8c4, - 0xae53123, 0x23b836ca, 0xaec35a0, 0x23c2a36f, - 0xaf33c28, 0x23cd0eb3, 0xafa44bc, 0x23d77896, - 0xb014f5b, 0x23e1e117, 0xb085c05, 0x23ec4837, - 0xb0f6aba, 0x23f6adf3, 0xb167b79, 0x2401124d, - 0xb1d8e43, 0x240b7543, 0xb24a316, 0x2415d6d5, - 0xb2bb9f4, 0x24203704, 0xb32d2da, 0x242a95ce, - 0xb39edca, 0x2434f332, 0xb410ac3, 0x243f4f32, - 0xb4829c4, 0x2449a9cc, 0xb4f4acd, 0x245402ff, - 0xb566ddf, 0x245e5acc, 0xb5d92f8, 0x2468b132, - 0xb64ba19, 0x24730631, 0xb6be341, 0x247d59c8, - 0xb730e70, 0x2487abf7, 0xb7a3ba5, 0x2491fcbe, - 0xb816ae1, 0x249c4c1b, 0xb889c23, 0x24a69a0f, - 0xb8fcf6b, 0x24b0e699, 0xb9704b9, 0x24bb31ba, - 0xb9e3c0b, 0x24c57b6f, 0xba57563, 0x24cfc3ba, - 0xbacb0bf, 0x24da0a9a, 0xbb3ee20, 0x24e4500e, - 0xbbb2d85, 0x24ee9415, 0xbc26eee, 0x24f8d6b0, - 0xbc9b25a, 0x250317df, 0xbd0f7ca, 0x250d57a0, - 0xbd83f3d, 0x251795f3, 0xbdf88b3, 0x2521d2d8, - 0xbe6d42b, 0x252c0e4f, 0xbee21a5, 0x25364857, - 0xbf57121, 0x254080ef, 0xbfcc29f, 0x254ab818, - 0xc04161e, 0x2554edd1, 0xc0b6b9e, 0x255f2219, - 0xc12c31f, 0x256954f1, 0xc1a1ca0, 0x25738657, - 0xc217822, 0x257db64c, 0xc28d5a3, 0x2587e4cf, - 0xc303524, 0x259211df, 0xc3796a5, 0x259c3d7c, - 0xc3efa25, 0x25a667a7, 0xc465fa3, 0x25b0905d, - 0xc4dc720, 0x25bab7a0, 0xc55309b, 0x25c4dd6e, - 0xc5c9c14, 0x25cf01c8, 0xc64098b, 0x25d924ac, - 0xc6b78ff, 0x25e3461b, 0xc72ea70, 0x25ed6614, - 0xc7a5dde, 0x25f78497, 0xc81d349, 0x2601a1a2, - 0xc894aaf, 0x260bbd37, 0xc90c412, 0x2615d754, - 0xc983f70, 0x261feffa, 0xc9fbcca, 0x262a0727, - 0xca73c1e, 0x26341cdb, 0xcaebd6e, 0x263e3117, - 0xcb640b8, 0x264843d9, 0xcbdc5fc, 0x26525521, - 0xcc54d3a, 0x265c64ef, 0xcccd671, 0x26667342, - 0xcd461a2, 0x2670801a, 0xcdbeecc, 0x267a8b77, - 0xce37def, 0x26849558, 0xceb0f0a, 0x268e9dbd, - 0xcf2a21d, 0x2698a4a6, 0xcfa3729, 0x26a2aa11, - 0xd01ce2b, 0x26acadff, 0xd096725, 0x26b6b070, - 0xd110216, 0x26c0b162, 0xd189efe, 0x26cab0d6, - 0xd203ddc, 0x26d4aecb, 0xd27deb0, 0x26deab41, - 0xd2f817b, 0x26e8a637, 0xd37263a, 0x26f29fad, - 0xd3eccef, 0x26fc97a3, 0xd467599, 0x27068e18, - 0xd4e2037, 0x2710830c, 0xd55ccca, 0x271a767e, - 0xd5d7b50, 0x2724686e, 0xd652bcb, 0x272e58dc, - 0xd6cde39, 0x273847c8, 0xd74929a, 0x27423530, - 0xd7c48ee, 0x274c2115, 0xd840134, 0x27560b76, - 0xd8bbb6d, 0x275ff452, 0xd937798, 0x2769dbaa, - 0xd9b35b4, 0x2773c17d, 0xda2f5c2, 0x277da5cb, - 0xdaab7c0, 0x27878893, 0xdb27bb0, 0x279169d5, - 0xdba4190, 0x279b4990, 0xdc20960, 0x27a527c4, - 0xdc9d320, 0x27af0472, 0xdd19ed0, 0x27b8df97, - 0xdd96c6f, 0x27c2b934, 0xde13bfd, 0x27cc9149, - 0xde90d79, 0x27d667d5, 0xdf0e0e4, 0x27e03cd8, - 0xdf8b63d, 0x27ea1052, 0xe008d84, 0x27f3e241, - 0xe0866b8, 0x27fdb2a7, 0xe1041d9, 0x28078181, - 0xe181ee8, 0x28114ed0, 0xe1ffde2, 0x281b1a94, - 0xe27dec9, 0x2824e4cc, 0xe2fc19c, 0x282ead78, - 0xe37a65b, 0x28387498, 0xe3f8d05, 0x28423a2a, - 0xe47759a, 0x284bfe2f, 0xe4f6019, 0x2855c0a6, - 0xe574c84, 0x285f8190, 0xe5f3ad8, 0x286940ea, - 0xe672b16, 0x2872feb6, 0xe6f1d3d, 0x287cbaf3, - 0xe77114e, 0x288675a0, 0xe7f0748, 0x28902ebd, - 0xe86ff2a, 0x2899e64a, 0xe8ef8f4, 0x28a39c46, - 0xe96f4a7, 0x28ad50b1, 0xe9ef241, 0x28b7038b, - 0xea6f1c2, 0x28c0b4d2, 0xeaef32b, 0x28ca6488, - 0xeb6f67a, 0x28d412ab, 0xebefbb0, 0x28ddbf3b, - 0xec702cb, 0x28e76a37, 0xecf0bcd, 0x28f113a0, - 0xed716b4, 0x28fabb75, 0xedf2380, 0x290461b5, - 0xee73231, 0x290e0661, 0xeef42c7, 0x2917a977, - 0xef75541, 0x29214af8, 0xeff699f, 0x292aeae3, - 0xf077fe1, 0x29348937, 0xf0f9805, 0x293e25f5, - 0xf17b20d, 0x2947c11c, 0xf1fcdf8, 0x29515aab, - 0xf27ebc5, 0x295af2a3, 0xf300b74, 0x29648902, - 0xf382d05, 0x296e1dc9, 0xf405077, 0x2977b0f7, - 0xf4875ca, 0x2981428c, 0xf509cfe, 0x298ad287, - 0xf58c613, 0x299460e8, 0xf60f108, 0x299dedaf, - 0xf691ddd, 0x29a778db, 0xf714c91, 0x29b1026c, - 0xf797d24, 0x29ba8a61, 0xf81af97, 0x29c410ba, - 0xf89e3e8, 0x29cd9578, 0xf921a17, 0x29d71899, - 0xf9a5225, 0x29e09a1c, 0xfa28c10, 0x29ea1a03, - 0xfaac7d8, 0x29f3984c, 0xfb3057d, 0x29fd14f6, - 0xfbb4500, 0x2a069003, 0xfc3865e, 0x2a100970, - 0xfcbc999, 0x2a19813f, 0xfd40eaf, 0x2a22f76e, - 0xfdc55a1, 0x2a2c6bfd, 0xfe49e6d, 0x2a35deeb, - 0xfece915, 0x2a3f503a, 0xff53597, 0x2a48bfe7, - 0xffd83f4, 0x2a522df3, 0x1005d42a, 0x2a5b9a5d, - 0x100e2639, 0x2a650525, 0x10167a22, 0x2a6e6e4b, - 0x101ecfe4, 0x2a77d5ce, 0x1027277e, 0x2a813bae, - 0x102f80f1, 0x2a8a9fea, 0x1037dc3b, 0x2a940283, - 0x1040395d, 0x2a9d6377, 0x10489856, 0x2aa6c2c6, - 0x1050f926, 0x2ab02071, 0x10595bcd, 0x2ab97c77, - 0x1061c04a, 0x2ac2d6d6, 0x106a269d, 0x2acc2f90, - 0x10728ec6, 0x2ad586a3, 0x107af8c4, 0x2adedc10, - 0x10836497, 0x2ae82fd5, 0x108bd23f, 0x2af181f3, - 0x109441bb, 0x2afad269, 0x109cb30b, 0x2b042137, - 0x10a5262f, 0x2b0d6e5c, 0x10ad9b26, 0x2b16b9d9, - 0x10b611f1, 0x2b2003ac, 0x10be8a8d, 0x2b294bd5, - 0x10c704fd, 0x2b329255, 0x10cf813e, 0x2b3bd72a, - 0x10d7ff51, 0x2b451a55, 0x10e07f36, 0x2b4e5bd4, - 0x10e900ec, 0x2b579ba8, 0x10f18472, 0x2b60d9d0, - 0x10fa09c9, 0x2b6a164d, 0x110290f0, 0x2b73511c, - 0x110b19e7, 0x2b7c8a3f, 0x1113a4ad, 0x2b85c1b5, - 0x111c3142, 0x2b8ef77d, 0x1124bfa6, 0x2b982b97, - 0x112d4fd9, 0x2ba15e03, 0x1135e1d9, 0x2baa8ec0, - 0x113e75a8, 0x2bb3bdce, 0x11470b44, 0x2bbceb2d, - 0x114fa2ad, 0x2bc616dd, 0x11583be2, 0x2bcf40dc, - 0x1160d6e5, 0x2bd8692b, 0x116973b3, 0x2be18fc9, - 0x1172124d, 0x2beab4b6, 0x117ab2b3, 0x2bf3d7f2, - 0x118354e4, 0x2bfcf97c, 0x118bf8e0, 0x2c061953, - 0x11949ea6, 0x2c0f3779, 0x119d4636, 0x2c1853eb, - 0x11a5ef90, 0x2c216eaa, 0x11ae9ab4, 0x2c2a87b6, - 0x11b747a0, 0x2c339f0e, 0x11bff656, 0x2c3cb4b1, - 0x11c8a6d4, 0x2c45c8a0, 0x11d1591a, 0x2c4edada, - 0x11da0d28, 0x2c57eb5e, 0x11e2c2fd, 0x2c60fa2d, - 0x11eb7a9a, 0x2c6a0746, 0x11f433fd, 0x2c7312a9, - 0x11fcef27, 0x2c7c1c55, 0x1205ac17, 0x2c85244a, - 0x120e6acc, 0x2c8e2a87, 0x12172b48, 0x2c972f0d, - 0x121fed88, 0x2ca031da, 0x1228b18d, 0x2ca932ef, - 0x12317756, 0x2cb2324c, 0x123a3ee4, 0x2cbb2fef, - 0x12430835, 0x2cc42bd9, 0x124bd34a, 0x2ccd2609, - 0x1254a021, 0x2cd61e7f, 0x125d6ebc, 0x2cdf153a, - 0x12663f19, 0x2ce80a3a, 0x126f1138, 0x2cf0fd80, - 0x1277e518, 0x2cf9ef09, 0x1280babb, 0x2d02ded7, - 0x1289921e, 0x2d0bcce8, 0x12926b41, 0x2d14b93d, - 0x129b4626, 0x2d1da3d5, 0x12a422ca, 0x2d268cb0, - 0x12ad012e, 0x2d2f73cd, 0x12b5e151, 0x2d38592c, - 0x12bec333, 0x2d413ccd, 0x12c7a6d4, 0x2d4a1eaf, - 0x12d08c33, 0x2d52fed2, 0x12d97350, 0x2d5bdd36, - 0x12e25c2b, 0x2d64b9da, 0x12eb46c3, 0x2d6d94bf, - 0x12f43318, 0x2d766de2, 0x12fd2129, 0x2d7f4545, - 0x130610f7, 0x2d881ae8, 0x130f0280, 0x2d90eec8, - 0x1317f5c6, 0x2d99c0e7, 0x1320eac6, 0x2da29144, - 0x1329e181, 0x2dab5fdf, 0x1332d9f7, 0x2db42cb6, - 0x133bd427, 0x2dbcf7cb, 0x1344d011, 0x2dc5c11c, - 0x134dcdb4, 0x2dce88aa, 0x1356cd11, 0x2dd74e73, - 0x135fce26, 0x2de01278, 0x1368d0f3, 0x2de8d4b8, - 0x1371d579, 0x2df19534, 0x137adbb6, 0x2dfa53e9, - 0x1383e3ab, 0x2e0310d9, 0x138ced57, 0x2e0bcc03, - 0x1395f8ba, 0x2e148566, 0x139f05d3, 0x2e1d3d03, - 0x13a814a2, 0x2e25f2d8, 0x13b12526, 0x2e2ea6e6, - 0x13ba3760, 0x2e37592c, 0x13c34b4f, 0x2e4009aa, - 0x13cc60f2, 0x2e48b860, 0x13d5784a, 0x2e51654c, - 0x13de9156, 0x2e5a1070, 0x13e7ac15, 0x2e62b9ca, - 0x13f0c887, 0x2e6b615a, 0x13f9e6ad, 0x2e740720, - 0x14030684, 0x2e7cab1c, 0x140c280e, 0x2e854d4d, - 0x14154b4a, 0x2e8dedb3, 0x141e7037, 0x2e968c4d, - 0x142796d5, 0x2e9f291b, 0x1430bf24, 0x2ea7c41e, - 0x1439e923, 0x2eb05d53, 0x144314d3, 0x2eb8f4bc, - 0x144c4232, 0x2ec18a58, 0x14557140, 0x2eca1e27, - 0x145ea1fd, 0x2ed2b027, 0x1467d469, 0x2edb405a, - 0x14710883, 0x2ee3cebe, 0x147a3e4b, 0x2eec5b53, - 0x148375c1, 0x2ef4e619, 0x148caee4, 0x2efd6f10, - 0x1495e9b3, 0x2f05f637, 0x149f2630, 0x2f0e7b8e, - 0x14a86458, 0x2f16ff14, 0x14b1a42c, 0x2f1f80ca, - 0x14bae5ab, 0x2f2800af, 0x14c428d6, 0x2f307ec2, - 0x14cd6dab, 0x2f38fb03, 0x14d6b42b, 0x2f417573, - 0x14dffc54, 0x2f49ee0f, 0x14e94627, 0x2f5264da, - 0x14f291a4, 0x2f5ad9d1, 0x14fbdec9, 0x2f634cf5, - 0x15052d97, 0x2f6bbe45, 0x150e7e0d, 0x2f742dc1, - 0x1517d02b, 0x2f7c9b69, 0x152123f0, 0x2f85073c, - 0x152a795d, 0x2f8d713a, 0x1533d070, 0x2f95d963, - 0x153d292a, 0x2f9e3fb6, 0x15468389, 0x2fa6a433, - 0x154fdf8f, 0x2faf06da, 0x15593d3a, 0x2fb767aa, - 0x15629c89, 0x2fbfc6a3, 0x156bfd7d, 0x2fc823c5, - 0x15756016, 0x2fd07f0f, 0x157ec452, 0x2fd8d882, - 0x15882a32, 0x2fe1301c, 0x159191b5, 0x2fe985de, - 0x159afadb, 0x2ff1d9c7, 0x15a465a3, 0x2ffa2bd6, - 0x15add20d, 0x30027c0c, 0x15b74019, 0x300aca69, - 0x15c0afc6, 0x301316eb, 0x15ca2115, 0x301b6193, - 0x15d39403, 0x3023aa5f, 0x15dd0892, 0x302bf151, - 0x15e67ec1, 0x30343667, 0x15eff690, 0x303c79a2, - 0x15f96ffd, 0x3044bb00, 0x1602eb0a, 0x304cfa83, - 0x160c67b4, 0x30553828, 0x1615e5fd, 0x305d73f0, - 0x161f65e4, 0x3065addb, 0x1628e767, 0x306de5e9, - 0x16326a88, 0x30761c18, 0x163bef46, 0x307e5069, - 0x1645759f, 0x308682dc, 0x164efd94, 0x308eb36f, - 0x16588725, 0x3096e223, 0x16621251, 0x309f0ef8, - 0x166b9f18, 0x30a739ed, 0x16752d79, 0x30af6302, - 0x167ebd74, 0x30b78a36, 0x16884f09, 0x30bfaf89, - 0x1691e237, 0x30c7d2fb, 0x169b76fe, 0x30cff48c, - 0x16a50d5d, 0x30d8143b, 0x16aea555, 0x30e03208, - 0x16b83ee4, 0x30e84df3, 0x16c1da0b, 0x30f067fb, - 0x16cb76c9, 0x30f8801f, 0x16d5151d, 0x31009661, - 0x16deb508, 0x3108aabf, 0x16e85689, 0x3110bd39, - 0x16f1f99f, 0x3118cdcf, 0x16fb9e4b, 0x3120dc80, - 0x1705448b, 0x3128e94c, 0x170eec60, 0x3130f433, - 0x171895c9, 0x3138fd35, 0x172240c5, 0x31410450, - 0x172bed55, 0x31490986, 0x17359b78, 0x31510cd5, - 0x173f4b2e, 0x31590e3e, 0x1748fc75, 0x31610dbf, - 0x1752af4f, 0x31690b59, 0x175c63ba, 0x3171070c, - 0x176619b6, 0x317900d6, 0x176fd143, 0x3180f8b8, - 0x17798a60, 0x3188eeb2, 0x1783450d, 0x3190e2c3, - 0x178d014a, 0x3198d4ea, 0x1796bf16, 0x31a0c528, - 0x17a07e70, 0x31a8b37c, 0x17aa3f5a, 0x31b09fe7, - 0x17b401d1, 0x31b88a66, 0x17bdc5d6, 0x31c072fb, - 0x17c78b68, 0x31c859a5, 0x17d15288, 0x31d03e64, - 0x17db1b34, 0x31d82137, 0x17e4e56c, 0x31e0021e, - 0x17eeb130, 0x31e7e118, 0x17f87e7f, 0x31efbe27, - 0x18024d59, 0x31f79948, 0x180c1dbf, 0x31ff727c, - 0x1815efae, 0x320749c3, 0x181fc328, 0x320f1f1c, - 0x1829982b, 0x3216f287, 0x18336eb7, 0x321ec403, - 0x183d46cc, 0x32269391, 0x18472069, 0x322e6130, - 0x1850fb8e, 0x32362ce0, 0x185ad83c, 0x323df6a0, - 0x1864b670, 0x3245be70, 0x186e962b, 0x324d8450, - 0x1878776d, 0x32554840, 0x18825a35, 0x325d0a3e, - 0x188c3e83, 0x3264ca4c, 0x18962456, 0x326c8868, - 0x18a00bae, 0x32744493, 0x18a9f48a, 0x327bfecc, - 0x18b3deeb, 0x3283b712, 0x18bdcad0, 0x328b6d66, - 0x18c7b838, 0x329321c7, 0x18d1a724, 0x329ad435, - 0x18db9792, 0x32a284b0, 0x18e58982, 0x32aa3336, - 0x18ef7cf4, 0x32b1dfc9, 0x18f971e8, 0x32b98a67, - 0x1903685d, 0x32c13311, 0x190d6053, 0x32c8d9c6, - 0x191759c9, 0x32d07e85, 0x192154bf, 0x32d82150, - 0x192b5135, 0x32dfc224, 0x19354f2a, 0x32e76102, - 0x193f4e9e, 0x32eefdea, 0x19494f90, 0x32f698db, - 0x19535201, 0x32fe31d5, 0x195d55ef, 0x3305c8d7, - 0x19675b5a, 0x330d5de3, 0x19716243, 0x3314f0f6, - 0x197b6aa8, 0x331c8211, 0x19857489, 0x33241134, - 0x198f7fe6, 0x332b9e5e, 0x19998cbe, 0x3333298f, - 0x19a39b11, 0x333ab2c6, 0x19adaadf, 0x33423a04, - 0x19b7bc27, 0x3349bf48, 0x19c1cee9, 0x33514292, - 0x19cbe325, 0x3358c3e2, 0x19d5f8d9, 0x33604336, - 0x19e01006, 0x3367c090, 0x19ea28ac, 0x336f3bee, - 0x19f442c9, 0x3376b551, 0x19fe5e5e, 0x337e2cb7, - 0x1a087b69, 0x3385a222, 0x1a1299ec, 0x338d1590, - 0x1a1cb9e5, 0x33948701, 0x1a26db54, 0x339bf675, - 0x1a30fe38, 0x33a363ec, 0x1a3b2292, 0x33aacf65, - 0x1a454860, 0x33b238e0, 0x1a4f6fa3, 0x33b9a05d, - 0x1a599859, 0x33c105db, 0x1a63c284, 0x33c8695b, - 0x1a6dee21, 0x33cfcadc, 0x1a781b31, 0x33d72a5d, - 0x1a8249b4, 0x33de87de, 0x1a8c79a9, 0x33e5e360, - 0x1a96ab0f, 0x33ed3ce1, 0x1aa0dde7, 0x33f49462, - 0x1aab122f, 0x33fbe9e2, 0x1ab547e8, 0x34033d61, - 0x1abf7f11, 0x340a8edf, 0x1ac9b7a9, 0x3411de5b, - 0x1ad3f1b1, 0x34192bd5, 0x1ade2d28, 0x3420774d, - 0x1ae86a0d, 0x3427c0c3, 0x1af2a860, 0x342f0836, - 0x1afce821, 0x34364da6, 0x1b072950, 0x343d9112, - 0x1b116beb, 0x3444d27b, 0x1b1baff2, 0x344c11e0, - 0x1b25f566, 0x34534f41, 0x1b303c46, 0x345a8a9d, - 0x1b3a8491, 0x3461c3f5, 0x1b44ce46, 0x3468fb47, - 0x1b4f1967, 0x34703095, 0x1b5965f1, 0x347763dd, - 0x1b63b3e5, 0x347e951f, 0x1b6e0342, 0x3485c45b, - 0x1b785409, 0x348cf190, 0x1b82a638, 0x34941cbf, - 0x1b8cf9cf, 0x349b45e7, 0x1b974ece, 0x34a26d08, - 0x1ba1a534, 0x34a99221, 0x1babfd01, 0x34b0b533, - 0x1bb65634, 0x34b7d63c, 0x1bc0b0ce, 0x34bef53d, - 0x1bcb0cce, 0x34c61236, 0x1bd56a32, 0x34cd2d26, - 0x1bdfc8fc, 0x34d4460c, 0x1bea292b, 0x34db5cea, - 0x1bf48abd, 0x34e271bd, 0x1bfeedb3, 0x34e98487, - 0x1c09520d, 0x34f09546, 0x1c13b7c9, 0x34f7a3fb, - 0x1c1e1ee9, 0x34feb0a5, 0x1c28876a, 0x3505bb44, - 0x1c32f14d, 0x350cc3d8, 0x1c3d5c91, 0x3513ca60, - 0x1c47c936, 0x351acedd, 0x1c52373c, 0x3521d14d, - 0x1c5ca6a2, 0x3528d1b1, 0x1c671768, 0x352fd008, - 0x1c71898d, 0x3536cc52, 0x1c7bfd11, 0x353dc68f, - 0x1c8671f3, 0x3544bebf, 0x1c90e834, 0x354bb4e1, - 0x1c9b5fd2, 0x3552a8f4, 0x1ca5d8cd, 0x35599afa, - 0x1cb05326, 0x35608af1, 0x1cbacedb, 0x356778d9, - 0x1cc54bec, 0x356e64b2, 0x1ccfca59, 0x35754e7c, - 0x1cda4a21, 0x357c3636, 0x1ce4cb44, 0x35831be0, - 0x1cef4dc2, 0x3589ff7a, 0x1cf9d199, 0x3590e104, - 0x1d0456ca, 0x3597c07d, 0x1d0edd55, 0x359e9de5, - 0x1d196538, 0x35a5793c, 0x1d23ee74, 0x35ac5282, - 0x1d2e7908, 0x35b329b5, 0x1d3904f4, 0x35b9fed7, - 0x1d439236, 0x35c0d1e7, 0x1d4e20d0, 0x35c7a2e3, - 0x1d58b0c0, 0x35ce71ce, 0x1d634206, 0x35d53ea5, - 0x1d6dd4a2, 0x35dc0968, 0x1d786892, 0x35e2d219, - 0x1d82fdd8, 0x35e998b5, 0x1d8d9472, 0x35f05d3d, - 0x1d982c60, 0x35f71fb1, 0x1da2c5a2, 0x35fde011, - 0x1dad6036, 0x36049e5b, 0x1db7fc1e, 0x360b5a90, - 0x1dc29958, 0x361214b0, 0x1dcd37e4, 0x3618ccba, - 0x1dd7d7c1, 0x361f82af, 0x1de278ef, 0x3626368d, - 0x1ded1b6e, 0x362ce855, 0x1df7bf3e, 0x36339806, - 0x1e02645d, 0x363a45a0, 0x1e0d0acc, 0x3640f123, - 0x1e17b28a, 0x36479a8e, 0x1e225b96, 0x364e41e2, - 0x1e2d05f1, 0x3654e71d, 0x1e37b199, 0x365b8a41, - 0x1e425e8f, 0x36622b4c, 0x1e4d0cd2, 0x3668ca3e, - 0x1e57bc62, 0x366f6717, 0x1e626d3e, 0x367601d7, - 0x1e6d1f65, 0x367c9a7e, 0x1e77d2d8, 0x3683310b, - 0x1e828796, 0x3689c57d, 0x1e8d3d9e, 0x369057d6, - 0x1e97f4f1, 0x3696e814, 0x1ea2ad8d, 0x369d7637, - 0x1ead6773, 0x36a4023f, 0x1eb822a1, 0x36aa8c2c, - 0x1ec2df18, 0x36b113fd, 0x1ecd9cd7, 0x36b799b3, - 0x1ed85bdd, 0x36be1d4c, 0x1ee31c2b, 0x36c49ec9, - 0x1eedddc0, 0x36cb1e2a, 0x1ef8a09b, 0x36d19b6e, - 0x1f0364bc, 0x36d81695, 0x1f0e2a22, 0x36de8f9e, - 0x1f18f0ce, 0x36e5068a, 0x1f23b8be, 0x36eb7b58, - 0x1f2e81f3, 0x36f1ee09, 0x1f394c6b, 0x36f85e9a, - 0x1f441828, 0x36fecd0e, 0x1f4ee527, 0x37053962, - 0x1f59b369, 0x370ba398, 0x1f6482ed, 0x37120bae, - 0x1f6f53b3, 0x371871a5, 0x1f7a25ba, 0x371ed57c, - 0x1f84f902, 0x37253733, 0x1f8fcd8b, 0x372b96ca, - 0x1f9aa354, 0x3731f440, 0x1fa57a5d, 0x37384f95, - 0x1fb052a5, 0x373ea8ca, 0x1fbb2c2c, 0x3744ffdd, - 0x1fc606f1, 0x374b54ce, 0x1fd0e2f5, 0x3751a79e, - 0x1fdbc036, 0x3757f84c, 0x1fe69eb4, 0x375e46d8, - 0x1ff17e70, 0x37649341, 0x1ffc5f67, 0x376add88, - 0x2007419b, 0x377125ac, 0x2012250a, 0x37776bac, - 0x201d09b4, 0x377daf89, 0x2027ef99, 0x3783f143, - 0x2032d6b8, 0x378a30d8, 0x203dbf11, 0x37906e49, - 0x2048a8a4, 0x3796a996, 0x2053936f, 0x379ce2be, - 0x205e7f74, 0x37a319c2, 0x20696cb0, 0x37a94ea0, - 0x20745b24, 0x37af8159, 0x207f4acf, 0x37b5b1ec, - 0x208a3bb2, 0x37bbe05a, 0x20952dcb, 0x37c20ca1, - 0x20a0211a, 0x37c836c2, 0x20ab159e, 0x37ce5ebd, - 0x20b60b58, 0x37d48490, 0x20c10247, 0x37daa83d, - 0x20cbfa6a, 0x37e0c9c3, 0x20d6f3c1, 0x37e6e921, - 0x20e1ee4b, 0x37ed0657, 0x20ecea09, 0x37f32165, - 0x20f7e6f9, 0x37f93a4b, 0x2102e51c, 0x37ff5109, - 0x210de470, 0x3805659e, 0x2118e4f6, 0x380b780a, - 0x2123e6ad, 0x3811884d, 0x212ee995, 0x38179666, - 0x2139edac, 0x381da256, 0x2144f2f3, 0x3823ac1d, - 0x214ff96a, 0x3829b3b9, 0x215b0110, 0x382fb92a, - 0x216609e3, 0x3835bc71, 0x217113e5, 0x383bbd8e, - 0x217c1f15, 0x3841bc7f, 0x21872b72, 0x3847b946, - 0x219238fb, 0x384db3e0, 0x219d47b1, 0x3853ac4f, - 0x21a85793, 0x3859a292, 0x21b368a0, 0x385f96a9, - 0x21be7ad8, 0x38658894, 0x21c98e3b, 0x386b7852, - 0x21d4a2c8, 0x387165e3, 0x21dfb87f, 0x38775147, - 0x21eacf5f, 0x387d3a7e, 0x21f5e768, 0x38832187, - 0x22010099, 0x38890663, 0x220c1af3, 0x388ee910, - 0x22173674, 0x3894c98f, 0x2222531c, 0x389aa7e0, - 0x222d70eb, 0x38a08402, 0x22388fe1, 0x38a65df6, - 0x2243affc, 0x38ac35ba, 0x224ed13d, 0x38b20b4f, - 0x2259f3a3, 0x38b7deb4, 0x2265172e, 0x38bdafea, - 0x22703bdc, 0x38c37eef, 0x227b61af, 0x38c94bc4, - 0x228688a4, 0x38cf1669, 0x2291b0bd, 0x38d4dedd, - 0x229cd9f8, 0x38daa520, 0x22a80456, 0x38e06932, - 0x22b32fd4, 0x38e62b13, 0x22be5c74, 0x38ebeac2, - 0x22c98a35, 0x38f1a840, 0x22d4b916, 0x38f7638b, - 0x22dfe917, 0x38fd1ca4, 0x22eb1a37, 0x3902d38b, - 0x22f64c77, 0x3908883f, 0x23017fd5, 0x390e3ac0, - 0x230cb451, 0x3913eb0e, 0x2317e9eb, 0x39199929, - 0x232320a2, 0x391f4510, 0x232e5876, 0x3924eec3, - 0x23399167, 0x392a9642, 0x2344cb73, 0x39303b8e, - 0x2350069b, 0x3935dea4, 0x235b42df, 0x393b7f86, - 0x2366803c, 0x39411e33, 0x2371beb5, 0x3946baac, - 0x237cfe47, 0x394c54ee, 0x23883ef2, 0x3951ecfc, - 0x239380b6, 0x395782d3, 0x239ec393, 0x395d1675, - 0x23aa0788, 0x3962a7e0, 0x23b54c95, 0x39683715, - 0x23c092b9, 0x396dc414, 0x23cbd9f4, 0x39734edc, - 0x23d72245, 0x3978d76c, 0x23e26bac, 0x397e5dc6, - 0x23edb628, 0x3983e1e8, 0x23f901ba, 0x398963d2, - 0x24044e60, 0x398ee385, 0x240f9c1a, 0x399460ff, - 0x241aeae8, 0x3999dc42, 0x24263ac9, 0x399f554b, - 0x24318bbe, 0x39a4cc1c, 0x243cddc4, 0x39aa40b4, - 0x244830dd, 0x39afb313, 0x24538507, 0x39b52339, - 0x245eda43, 0x39ba9125, 0x246a308f, 0x39bffcd7, - 0x247587eb, 0x39c5664f, 0x2480e057, 0x39cacd8d, - 0x248c39d3, 0x39d03291, 0x2497945d, 0x39d5955a, - 0x24a2eff6, 0x39daf5e8, 0x24ae4c9d, 0x39e0543c, - 0x24b9aa52, 0x39e5b054, 0x24c50914, 0x39eb0a31, - 0x24d068e2, 0x39f061d2, 0x24dbc9bd, 0x39f5b737, - 0x24e72ba4, 0x39fb0a60, 0x24f28e96, 0x3a005b4d, - 0x24fdf294, 0x3a05a9fd, 0x2509579b, 0x3a0af671, - 0x2514bdad, 0x3a1040a8, 0x252024c9, 0x3a1588a2, - 0x252b8cee, 0x3a1ace5f, 0x2536f61b, 0x3a2011de, - 0x25426051, 0x3a25531f, 0x254dcb8f, 0x3a2a9223, - 0x255937d5, 0x3a2fcee8, 0x2564a521, 0x3a350970, - 0x25701374, 0x3a3a41b9, 0x257b82cd, 0x3a3f77c3, - 0x2586f32c, 0x3a44ab8e, 0x25926490, 0x3a49dd1a, - 0x259dd6f9, 0x3a4f0c67, 0x25a94a67, 0x3a543974, - 0x25b4bed8, 0x3a596442, 0x25c0344d, 0x3a5e8cd0, - 0x25cbaac5, 0x3a63b31d, 0x25d72240, 0x3a68d72b, - 0x25e29abc, 0x3a6df8f8, 0x25ee143b, 0x3a731884, - 0x25f98ebb, 0x3a7835cf, 0x26050a3b, 0x3a7d50da, - 0x261086bc, 0x3a8269a3, 0x261c043d, 0x3a87802a, - 0x262782be, 0x3a8c9470, 0x2633023e, 0x3a91a674, - 0x263e82bc, 0x3a96b636, 0x264a0438, 0x3a9bc3b6, - 0x265586b3, 0x3aa0cef3, 0x26610a2a, 0x3aa5d7ee, - 0x266c8e9f, 0x3aaadea6, 0x26781410, 0x3aafe31b, - 0x26839a7c, 0x3ab4e54c, 0x268f21e5, 0x3ab9e53a, - 0x269aaa48, 0x3abee2e5, 0x26a633a6, 0x3ac3de4c, - 0x26b1bdff, 0x3ac8d76f, 0x26bd4951, 0x3acdce4d, - 0x26c8d59c, 0x3ad2c2e8, 0x26d462e1, 0x3ad7b53d, - 0x26dff11d, 0x3adca54e, 0x26eb8052, 0x3ae1931a, - 0x26f7107e, 0x3ae67ea1, 0x2702a1a1, 0x3aeb67e3, - 0x270e33bb, 0x3af04edf, 0x2719c6cb, 0x3af53395, - 0x27255ad1, 0x3afa1605, 0x2730efcc, 0x3afef630, - 0x273c85bc, 0x3b03d414, 0x27481ca1, 0x3b08afb2, - 0x2753b479, 0x3b0d8909, 0x275f4d45, 0x3b126019, - 0x276ae704, 0x3b1734e2, 0x277681b6, 0x3b1c0764, - 0x27821d59, 0x3b20d79e, 0x278db9ef, 0x3b25a591, - 0x27995776, 0x3b2a713d, 0x27a4f5ed, 0x3b2f3aa0, - 0x27b09555, 0x3b3401bb, 0x27bc35ad, 0x3b38c68e, - 0x27c7d6f4, 0x3b3d8918, 0x27d3792b, 0x3b42495a, - 0x27df1c50, 0x3b470753, 0x27eac063, 0x3b4bc303, - 0x27f66564, 0x3b507c69, 0x28020b52, 0x3b553386, - 0x280db22d, 0x3b59e85a, 0x281959f4, 0x3b5e9ae4, - 0x282502a7, 0x3b634b23, 0x2830ac45, 0x3b67f919, - 0x283c56cf, 0x3b6ca4c4, 0x28480243, 0x3b714e25, - 0x2853aea1, 0x3b75f53c, 0x285f5be9, 0x3b7a9a07, - 0x286b0a1a, 0x3b7f3c87, 0x2876b934, 0x3b83dcbc, - 0x28826936, 0x3b887aa6, 0x288e1a20, 0x3b8d1644, - 0x2899cbf1, 0x3b91af97, 0x28a57ea9, 0x3b96469d, - 0x28b13248, 0x3b9adb57, 0x28bce6cd, 0x3b9f6dc5, - 0x28c89c37, 0x3ba3fde7, 0x28d45286, 0x3ba88bbc, - 0x28e009ba, 0x3bad1744, 0x28ebc1d3, 0x3bb1a080, - 0x28f77acf, 0x3bb6276e, 0x290334af, 0x3bbaac0e, - 0x290eef71, 0x3bbf2e62, 0x291aab16, 0x3bc3ae67, - 0x2926679c, 0x3bc82c1f, 0x29322505, 0x3bcca789, - 0x293de34e, 0x3bd120a4, 0x2949a278, 0x3bd59771, - 0x29556282, 0x3bda0bf0, 0x2961236c, 0x3bde7e20, - 0x296ce535, 0x3be2ee01, 0x2978a7dd, 0x3be75b93, - 0x29846b63, 0x3bebc6d5, 0x29902fc7, 0x3bf02fc9, - 0x299bf509, 0x3bf4966c, 0x29a7bb28, 0x3bf8fac0, - 0x29b38223, 0x3bfd5cc4, 0x29bf49fa, 0x3c01bc78, - 0x29cb12ad, 0x3c0619dc, 0x29d6dc3b, 0x3c0a74f0, - 0x29e2a6a3, 0x3c0ecdb2, 0x29ee71e6, 0x3c132424, - 0x29fa3e03, 0x3c177845, 0x2a060af9, 0x3c1bca16, - 0x2a11d8c8, 0x3c201994, 0x2a1da770, 0x3c2466c2, - 0x2a2976ef, 0x3c28b19e, 0x2a354746, 0x3c2cfa28, - 0x2a411874, 0x3c314060, 0x2a4cea79, 0x3c358446, - 0x2a58bd54, 0x3c39c5da, 0x2a649105, 0x3c3e051b, - 0x2a70658a, 0x3c42420a, 0x2a7c3ae5, 0x3c467ca6, - 0x2a881114, 0x3c4ab4ef, 0x2a93e817, 0x3c4eeae5, - 0x2a9fbfed, 0x3c531e88, 0x2aab9896, 0x3c574fd8, - 0x2ab77212, 0x3c5b7ed4, 0x2ac34c60, 0x3c5fab7c, - 0x2acf277f, 0x3c63d5d1, 0x2adb0370, 0x3c67fdd1, - 0x2ae6e031, 0x3c6c237e, 0x2af2bdc3, 0x3c7046d6, - 0x2afe9c24, 0x3c7467d9, 0x2b0a7b54, 0x3c788688, - 0x2b165b54, 0x3c7ca2e2, 0x2b223c22, 0x3c80bce7, - 0x2b2e1dbe, 0x3c84d496, 0x2b3a0027, 0x3c88e9f1, - 0x2b45e35d, 0x3c8cfcf6, 0x2b51c760, 0x3c910da5, - 0x2b5dac2f, 0x3c951bff, 0x2b6991ca, 0x3c992803, - 0x2b75782f, 0x3c9d31b0, 0x2b815f60, 0x3ca13908, - 0x2b8d475b, 0x3ca53e09, 0x2b99301f, 0x3ca940b3, - 0x2ba519ad, 0x3cad4107, 0x2bb10404, 0x3cb13f04, - 0x2bbcef23, 0x3cb53aaa, 0x2bc8db0b, 0x3cb933f9, - 0x2bd4c7ba, 0x3cbd2af0, 0x2be0b52f, 0x3cc11f90, - 0x2beca36c, 0x3cc511d9, 0x2bf8926f, 0x3cc901c9, - 0x2c048237, 0x3cccef62, 0x2c1072c4, 0x3cd0daa2, - 0x2c1c6417, 0x3cd4c38b, 0x2c28562d, 0x3cd8aa1b, - 0x2c344908, 0x3cdc8e52, 0x2c403ca5, 0x3ce07031, - 0x2c4c3106, 0x3ce44fb7, 0x2c582629, 0x3ce82ce4, - 0x2c641c0e, 0x3cec07b8, 0x2c7012b5, 0x3cefe032, - 0x2c7c0a1d, 0x3cf3b653, 0x2c880245, 0x3cf78a1b, - 0x2c93fb2e, 0x3cfb5b89, 0x2c9ff4d6, 0x3cff2a9d, - 0x2cabef3d, 0x3d02f757, 0x2cb7ea63, 0x3d06c1b6, - 0x2cc3e648, 0x3d0a89bc, 0x2ccfe2ea, 0x3d0e4f67, - 0x2cdbe04a, 0x3d1212b7, 0x2ce7de66, 0x3d15d3ad, - 0x2cf3dd3f, 0x3d199248, 0x2cffdcd4, 0x3d1d4e88, - 0x2d0bdd25, 0x3d21086c, 0x2d17de31, 0x3d24bff6, - 0x2d23dff7, 0x3d287523, 0x2d2fe277, 0x3d2c27f6, - 0x2d3be5b1, 0x3d2fd86c, 0x2d47e9a5, 0x3d338687, - 0x2d53ee51, 0x3d373245, 0x2d5ff3b5, 0x3d3adba7, - 0x2d6bf9d1, 0x3d3e82ae, 0x2d7800a5, 0x3d422757, - 0x2d84082f, 0x3d45c9a4, 0x2d901070, 0x3d496994, - 0x2d9c1967, 0x3d4d0728, 0x2da82313, 0x3d50a25e, - 0x2db42d74, 0x3d543b37, 0x2dc0388a, 0x3d57d1b3, - 0x2dcc4454, 0x3d5b65d2, 0x2dd850d2, 0x3d5ef793, - 0x2de45e03, 0x3d6286f6, 0x2df06be6, 0x3d6613fb, - 0x2dfc7a7c, 0x3d699ea3, 0x2e0889c4, 0x3d6d26ec, - 0x2e1499bd, 0x3d70acd7, 0x2e20aa67, 0x3d743064, - 0x2e2cbbc1, 0x3d77b192, 0x2e38cdcb, 0x3d7b3061, - 0x2e44e084, 0x3d7eacd2, 0x2e50f3ed, 0x3d8226e4, - 0x2e5d0804, 0x3d859e96, 0x2e691cc9, 0x3d8913ea, - 0x2e75323c, 0x3d8c86de, 0x2e81485c, 0x3d8ff772, - 0x2e8d5f29, 0x3d9365a8, 0x2e9976a1, 0x3d96d17d, - 0x2ea58ec6, 0x3d9a3af2, 0x2eb1a796, 0x3d9da208, - 0x2ebdc110, 0x3da106bd, 0x2ec9db35, 0x3da46912, - 0x2ed5f604, 0x3da7c907, 0x2ee2117c, 0x3dab269b, - 0x2eee2d9d, 0x3dae81cf, 0x2efa4a67, 0x3db1daa2, - 0x2f0667d9, 0x3db53113, 0x2f1285f2, 0x3db88524, - 0x2f1ea4b2, 0x3dbbd6d4, 0x2f2ac419, 0x3dbf2622, - 0x2f36e426, 0x3dc2730f, 0x2f4304d8, 0x3dc5bd9b, - 0x2f4f2630, 0x3dc905c5, 0x2f5b482d, 0x3dcc4b8d, - 0x2f676ace, 0x3dcf8ef3, 0x2f738e12, 0x3dd2cff7, - 0x2f7fb1fa, 0x3dd60e99, 0x2f8bd685, 0x3dd94ad8, - 0x2f97fbb2, 0x3ddc84b5, 0x2fa42181, 0x3ddfbc30, - 0x2fb047f2, 0x3de2f148, 0x2fbc6f03, 0x3de623fd, - 0x2fc896b5, 0x3de9544f, 0x2fd4bf08, 0x3dec823e, - 0x2fe0e7f9, 0x3defadca, 0x2fed118a, 0x3df2d6f3, - 0x2ff93bba, 0x3df5fdb8, 0x30056687, 0x3df9221a, - 0x301191f3, 0x3dfc4418, 0x301dbdfb, 0x3dff63b2, - 0x3029eaa1, 0x3e0280e9, 0x303617e2, 0x3e059bbb, - 0x304245c0, 0x3e08b42a, 0x304e7438, 0x3e0bca34, - 0x305aa34c, 0x3e0eddd9, 0x3066d2fa, 0x3e11ef1b, - 0x30730342, 0x3e14fdf7, 0x307f3424, 0x3e180a6f, - 0x308b659f, 0x3e1b1482, 0x309797b2, 0x3e1e1c30, - 0x30a3ca5d, 0x3e212179, 0x30affda0, 0x3e24245d, - 0x30bc317a, 0x3e2724db, 0x30c865ea, 0x3e2a22f4, - 0x30d49af1, 0x3e2d1ea8, 0x30e0d08d, 0x3e3017f6, - 0x30ed06bf, 0x3e330ede, 0x30f93d86, 0x3e360360, - 0x310574e0, 0x3e38f57c, 0x3111accf, 0x3e3be532, - 0x311de551, 0x3e3ed282, 0x312a1e66, 0x3e41bd6c, - 0x3136580d, 0x3e44a5ef, 0x31429247, 0x3e478c0b, - 0x314ecd11, 0x3e4a6fc1, 0x315b086d, 0x3e4d5110, - 0x31674459, 0x3e502ff9, 0x317380d6, 0x3e530c7a, - 0x317fbde2, 0x3e55e694, 0x318bfb7d, 0x3e58be47, - 0x319839a6, 0x3e5b9392, 0x31a4785e, 0x3e5e6676, - 0x31b0b7a4, 0x3e6136f3, 0x31bcf777, 0x3e640507, - 0x31c937d6, 0x3e66d0b4, 0x31d578c2, 0x3e6999fa, - 0x31e1ba3a, 0x3e6c60d7, 0x31edfc3d, 0x3e6f254c, - 0x31fa3ecb, 0x3e71e759, 0x320681e3, 0x3e74a6fd, - 0x3212c585, 0x3e77643a, 0x321f09b1, 0x3e7a1f0d, - 0x322b4e66, 0x3e7cd778, 0x323793a3, 0x3e7f8d7b, - 0x3243d968, 0x3e824114, 0x32501fb5, 0x3e84f245, - 0x325c6688, 0x3e87a10c, 0x3268ade3, 0x3e8a4d6a, - 0x3274f5c3, 0x3e8cf75f, 0x32813e2a, 0x3e8f9eeb, - 0x328d8715, 0x3e92440d, 0x3299d085, 0x3e94e6c6, - 0x32a61a7a, 0x3e978715, 0x32b264f2, 0x3e9a24fb, - 0x32beafed, 0x3e9cc076, 0x32cafb6b, 0x3e9f5988, - 0x32d7476c, 0x3ea1f02f, 0x32e393ef, 0x3ea4846c, - 0x32efe0f2, 0x3ea7163f, 0x32fc2e77, 0x3ea9a5a8, - 0x33087c7d, 0x3eac32a6, 0x3314cb02, 0x3eaebd3a, - 0x33211a07, 0x3eb14563, 0x332d698a, 0x3eb3cb21, - 0x3339b98d, 0x3eb64e75, 0x33460a0d, 0x3eb8cf5d, - 0x33525b0b, 0x3ebb4ddb, 0x335eac86, 0x3ebdc9ed, - 0x336afe7e, 0x3ec04394, 0x337750f2, 0x3ec2bad0, - 0x3383a3e2, 0x3ec52fa0, 0x338ff74d, 0x3ec7a205, - 0x339c4b32, 0x3eca11fe, 0x33a89f92, 0x3ecc7f8b, - 0x33b4f46c, 0x3eceeaad, 0x33c149bf, 0x3ed15363, - 0x33cd9f8b, 0x3ed3b9ad, 0x33d9f5cf, 0x3ed61d8a, - 0x33e64c8c, 0x3ed87efc, 0x33f2a3bf, 0x3edade01, - 0x33fefb6a, 0x3edd3a9a, 0x340b538b, 0x3edf94c7, - 0x3417ac22, 0x3ee1ec87, 0x3424052f, 0x3ee441da, - 0x34305eb0, 0x3ee694c1, 0x343cb8a7, 0x3ee8e53a, - 0x34491311, 0x3eeb3347, 0x34556def, 0x3eed7ee7, - 0x3461c940, 0x3eefc81a, 0x346e2504, 0x3ef20ee0, - 0x347a8139, 0x3ef45338, 0x3486dde1, 0x3ef69523, - 0x34933afa, 0x3ef8d4a1, 0x349f9884, 0x3efb11b1, - 0x34abf67e, 0x3efd4c54, 0x34b854e7, 0x3eff8489, - 0x34c4b3c0, 0x3f01ba50, 0x34d11308, 0x3f03eda9, - 0x34dd72be, 0x3f061e95, 0x34e9d2e3, 0x3f084d12, - 0x34f63374, 0x3f0a7921, 0x35029473, 0x3f0ca2c2, - 0x350ef5de, 0x3f0ec9f5, 0x351b57b5, 0x3f10eeb9, - 0x3527b9f7, 0x3f13110f, 0x35341ca5, 0x3f1530f7, - 0x35407fbd, 0x3f174e70, 0x354ce33f, 0x3f19697a, - 0x3559472b, 0x3f1b8215, 0x3565ab80, 0x3f1d9842, - 0x3572103d, 0x3f1fabff, 0x357e7563, 0x3f21bd4e, - 0x358adaf0, 0x3f23cc2e, 0x359740e5, 0x3f25d89e, - 0x35a3a740, 0x3f27e29f, 0x35b00e02, 0x3f29ea31, - 0x35bc7529, 0x3f2bef53, 0x35c8dcb6, 0x3f2df206, - 0x35d544a7, 0x3f2ff24a, 0x35e1acfd, 0x3f31f01d, - 0x35ee15b7, 0x3f33eb81, 0x35fa7ed4, 0x3f35e476, - 0x3606e854, 0x3f37dafa, 0x36135237, 0x3f39cf0e, - 0x361fbc7b, 0x3f3bc0b3, 0x362c2721, 0x3f3dafe7, - 0x36389228, 0x3f3f9cab, 0x3644fd8f, 0x3f4186ff, - 0x36516956, 0x3f436ee3, 0x365dd57d, 0x3f455456, - 0x366a4203, 0x3f473759, 0x3676aee8, 0x3f4917eb, - 0x36831c2b, 0x3f4af60d, 0x368f89cb, 0x3f4cd1be, - 0x369bf7c9, 0x3f4eaafe, 0x36a86623, 0x3f5081cd, - 0x36b4d4d9, 0x3f52562c, 0x36c143ec, 0x3f54281a, - 0x36cdb359, 0x3f55f796, 0x36da2321, 0x3f57c4a2, - 0x36e69344, 0x3f598f3c, 0x36f303c0, 0x3f5b5765, - 0x36ff7496, 0x3f5d1d1d, 0x370be5c4, 0x3f5ee063, - 0x3718574b, 0x3f60a138, 0x3724c92a, 0x3f625f9b, - 0x37313b60, 0x3f641b8d, 0x373daded, 0x3f65d50d, - 0x374a20d0, 0x3f678c1c, 0x3756940a, 0x3f6940b8, - 0x37630799, 0x3f6af2e3, 0x376f7b7d, 0x3f6ca29c, - 0x377befb5, 0x3f6e4fe3, 0x37886442, 0x3f6ffab8, - 0x3794d922, 0x3f71a31b, 0x37a14e55, 0x3f73490b, - 0x37adc3db, 0x3f74ec8a, 0x37ba39b3, 0x3f768d96, - 0x37c6afdc, 0x3f782c30, 0x37d32657, 0x3f79c857, - 0x37df9d22, 0x3f7b620c, 0x37ec143e, 0x3f7cf94e, - 0x37f88ba9, 0x3f7e8e1e, 0x38050364, 0x3f80207b, - 0x38117b6d, 0x3f81b065, 0x381df3c5, 0x3f833ddd, - 0x382a6c6a, 0x3f84c8e2, 0x3836e55d, 0x3f865174, - 0x38435e9d, 0x3f87d792, 0x384fd829, 0x3f895b3e, - 0x385c5201, 0x3f8adc77, 0x3868cc24, 0x3f8c5b3d, - 0x38754692, 0x3f8dd78f, 0x3881c14b, 0x3f8f516e, - 0x388e3c4d, 0x3f90c8da, 0x389ab799, 0x3f923dd2, - 0x38a7332e, 0x3f93b058, 0x38b3af0c, 0x3f952069, - 0x38c02b31, 0x3f968e07, 0x38cca79e, 0x3f97f932, - 0x38d92452, 0x3f9961e8, 0x38e5a14d, 0x3f9ac82c, - 0x38f21e8e, 0x3f9c2bfb, 0x38fe9c15, 0x3f9d8d56, - 0x390b19e0, 0x3f9eec3e, 0x391797f0, 0x3fa048b2, - 0x39241645, 0x3fa1a2b2, 0x393094dd, 0x3fa2fa3d, - 0x393d13b8, 0x3fa44f55, 0x394992d7, 0x3fa5a1f9, - 0x39561237, 0x3fa6f228, 0x396291d9, 0x3fa83fe3, - 0x396f11bc, 0x3fa98b2a, 0x397b91e1, 0x3faad3fd, - 0x39881245, 0x3fac1a5b, 0x399492ea, 0x3fad5e45, - 0x39a113cd, 0x3fae9fbb, 0x39ad94f0, 0x3fafdebb, - 0x39ba1651, 0x3fb11b48, 0x39c697f0, 0x3fb2555f, - 0x39d319cc, 0x3fb38d02, 0x39df9be6, 0x3fb4c231, - 0x39ec1e3b, 0x3fb5f4ea, 0x39f8a0cd, 0x3fb7252f, - 0x3a05239a, 0x3fb852ff, 0x3a11a6a3, 0x3fb97e5a, - 0x3a1e29e5, 0x3fbaa740, 0x3a2aad62, 0x3fbbcdb1, - 0x3a373119, 0x3fbcf1ad, 0x3a43b508, 0x3fbe1334, - 0x3a503930, 0x3fbf3246, 0x3a5cbd91, 0x3fc04ee3, - 0x3a694229, 0x3fc1690a, 0x3a75c6f8, 0x3fc280bc, - 0x3a824bfd, 0x3fc395f9, 0x3a8ed139, 0x3fc4a8c1, - 0x3a9b56ab, 0x3fc5b913, 0x3aa7dc52, 0x3fc6c6f0, - 0x3ab4622d, 0x3fc7d258, 0x3ac0e83d, 0x3fc8db4a, - 0x3acd6e81, 0x3fc9e1c6, 0x3ad9f4f8, 0x3fcae5cd, - 0x3ae67ba2, 0x3fcbe75e, 0x3af3027e, 0x3fcce67a, - 0x3aff898c, 0x3fcde320, 0x3b0c10cb, 0x3fcedd50, - 0x3b18983b, 0x3fcfd50b, 0x3b251fdc, 0x3fd0ca4f, - 0x3b31a7ac, 0x3fd1bd1e, 0x3b3e2fac, 0x3fd2ad77, - 0x3b4ab7db, 0x3fd39b5a, 0x3b574039, 0x3fd486c7, - 0x3b63c8c4, 0x3fd56fbe, 0x3b70517d, 0x3fd6563f, - 0x3b7cda63, 0x3fd73a4a, 0x3b896375, 0x3fd81bdf, - 0x3b95ecb4, 0x3fd8fafe, 0x3ba2761e, 0x3fd9d7a7, - 0x3baeffb3, 0x3fdab1d9, 0x3bbb8973, 0x3fdb8996, - 0x3bc8135c, 0x3fdc5edc, 0x3bd49d70, 0x3fdd31ac, - 0x3be127ac, 0x3fde0205, 0x3bedb212, 0x3fdecfe8, - 0x3bfa3c9f, 0x3fdf9b55, 0x3c06c754, 0x3fe0644b, - 0x3c135231, 0x3fe12acb, 0x3c1fdd34, 0x3fe1eed5, - 0x3c2c685d, 0x3fe2b067, 0x3c38f3ac, 0x3fe36f84, - 0x3c457f21, 0x3fe42c2a, 0x3c520aba, 0x3fe4e659, - 0x3c5e9678, 0x3fe59e12, 0x3c6b2259, 0x3fe65354, - 0x3c77ae5e, 0x3fe7061f, 0x3c843a85, 0x3fe7b674, - 0x3c90c6cf, 0x3fe86452, 0x3c9d533b, 0x3fe90fb9, - 0x3ca9dfc8, 0x3fe9b8a9, 0x3cb66c77, 0x3fea5f23, - 0x3cc2f945, 0x3feb0326, 0x3ccf8634, 0x3feba4b2, - 0x3cdc1342, 0x3fec43c7, 0x3ce8a06f, 0x3fece065, - 0x3cf52dbb, 0x3fed7a8c, 0x3d01bb24, 0x3fee123d, - 0x3d0e48ab, 0x3feea776, 0x3d1ad650, 0x3fef3a39, - 0x3d276410, 0x3fefca84, 0x3d33f1ed, 0x3ff05858, - 0x3d407fe6, 0x3ff0e3b6, 0x3d4d0df9, 0x3ff16c9c, - 0x3d599c28, 0x3ff1f30b, 0x3d662a70, 0x3ff27703, - 0x3d72b8d2, 0x3ff2f884, 0x3d7f474d, 0x3ff3778e, - 0x3d8bd5e1, 0x3ff3f420, 0x3d98648d, 0x3ff46e3c, - 0x3da4f351, 0x3ff4e5e0, 0x3db1822c, 0x3ff55b0d, - 0x3dbe111e, 0x3ff5cdc3, 0x3dcaa027, 0x3ff63e01, - 0x3dd72f45, 0x3ff6abc8, 0x3de3be78, 0x3ff71718, - 0x3df04dc0, 0x3ff77ff1, 0x3dfcdd1d, 0x3ff7e652, - 0x3e096c8d, 0x3ff84a3c, 0x3e15fc11, 0x3ff8abae, - 0x3e228ba7, 0x3ff90aaa, 0x3e2f1b50, 0x3ff9672d, - 0x3e3bab0b, 0x3ff9c13a, 0x3e483ad8, 0x3ffa18cf, - 0x3e54cab5, 0x3ffa6dec, 0x3e615aa3, 0x3ffac092, - 0x3e6deaa1, 0x3ffb10c1, 0x3e7a7aae, 0x3ffb5e78, - 0x3e870aca, 0x3ffba9b8, 0x3e939af5, 0x3ffbf280, - 0x3ea02b2e, 0x3ffc38d1, 0x3eacbb74, 0x3ffc7caa, - 0x3eb94bc8, 0x3ffcbe0c, 0x3ec5dc28, 0x3ffcfcf6, - 0x3ed26c94, 0x3ffd3969, 0x3edefd0c, 0x3ffd7364, - 0x3eeb8d8f, 0x3ffdaae7, 0x3ef81e1d, 0x3ffddff3, - 0x3f04aeb5, 0x3ffe1288, 0x3f113f56, 0x3ffe42a4, - 0x3f1dd001, 0x3ffe704a, 0x3f2a60b4, 0x3ffe9b77, - 0x3f36f170, 0x3ffec42d, 0x3f438234, 0x3ffeea6c, - 0x3f5012fe, 0x3fff0e32, 0x3f5ca3d0, 0x3fff2f82, - 0x3f6934a8, 0x3fff4e59, 0x3f75c585, 0x3fff6ab9, - 0x3f825668, 0x3fff84a1, 0x3f8ee750, 0x3fff9c12, - 0x3f9b783c, 0x3fffb10b, 0x3fa8092c, 0x3fffc38c, - 0x3fb49a1f, 0x3fffd396, 0x3fc12b16, 0x3fffe128, - 0x3fcdbc0f, 0x3fffec43, 0x3fda4d09, 0x3ffff4e6, - 0x3fe6de05, 0x3ffffb11, 0x3ff36f02, 0x3ffffec4, -}; - - -/** -* \par -* Generation of realCoefBQ31 array: -* \par -* n = 4096 -*
for (i = 0; i < n; i++)    
-* {    
-*    pBTable[2 * i] = 0.5 * (1.0 + sin (2 * PI / (double) (2 * n) * (double) i));    
-*    pBTable[2 * i + 1] = 0.5 * (1.0 * cos (2 * PI / (double) (2 * n) * (double) i));    
-* } 
-* \par -* Convert to fixed point Q31 format -* round(pBTable[i] * pow(2, 31)) -* -*/ - -static const q31_t realCoefBQ31[8192] = { - 0x40000000, 0x40000000, 0x400c90fe, 0x3ffffec4, - 0x401921fb, 0x3ffffb11, 0x4025b2f7, 0x3ffff4e6, - 0x403243f1, 0x3fffec43, 0x403ed4ea, 0x3fffe128, - 0x404b65e1, 0x3fffd396, 0x4057f6d4, 0x3fffc38c, - 0x406487c4, 0x3fffb10b, 0x407118b0, 0x3fff9c12, - 0x407da998, 0x3fff84a1, 0x408a3a7b, 0x3fff6ab9, - 0x4096cb58, 0x3fff4e59, 0x40a35c30, 0x3fff2f82, - 0x40afed02, 0x3fff0e32, 0x40bc7dcc, 0x3ffeea6c, - 0x40c90e90, 0x3ffec42d, 0x40d59f4c, 0x3ffe9b77, - 0x40e22fff, 0x3ffe704a, 0x40eec0aa, 0x3ffe42a4, - 0x40fb514b, 0x3ffe1288, 0x4107e1e3, 0x3ffddff3, - 0x41147271, 0x3ffdaae7, 0x412102f4, 0x3ffd7364, - 0x412d936c, 0x3ffd3969, 0x413a23d8, 0x3ffcfcf6, - 0x4146b438, 0x3ffcbe0c, 0x4153448c, 0x3ffc7caa, - 0x415fd4d2, 0x3ffc38d1, 0x416c650b, 0x3ffbf280, - 0x4178f536, 0x3ffba9b8, 0x41858552, 0x3ffb5e78, - 0x4192155f, 0x3ffb10c1, 0x419ea55d, 0x3ffac092, - 0x41ab354b, 0x3ffa6dec, 0x41b7c528, 0x3ffa18cf, - 0x41c454f5, 0x3ff9c13a, 0x41d0e4b0, 0x3ff9672d, - 0x41dd7459, 0x3ff90aaa, 0x41ea03ef, 0x3ff8abae, - 0x41f69373, 0x3ff84a3c, 0x420322e3, 0x3ff7e652, - 0x420fb240, 0x3ff77ff1, 0x421c4188, 0x3ff71718, - 0x4228d0bb, 0x3ff6abc8, 0x42355fd9, 0x3ff63e01, - 0x4241eee2, 0x3ff5cdc3, 0x424e7dd4, 0x3ff55b0d, - 0x425b0caf, 0x3ff4e5e0, 0x42679b73, 0x3ff46e3c, - 0x42742a1f, 0x3ff3f420, 0x4280b8b3, 0x3ff3778e, - 0x428d472e, 0x3ff2f884, 0x4299d590, 0x3ff27703, - 0x42a663d8, 0x3ff1f30b, 0x42b2f207, 0x3ff16c9c, - 0x42bf801a, 0x3ff0e3b6, 0x42cc0e13, 0x3ff05858, - 0x42d89bf0, 0x3fefca84, 0x42e529b0, 0x3fef3a39, - 0x42f1b755, 0x3feea776, 0x42fe44dc, 0x3fee123d, - 0x430ad245, 0x3fed7a8c, 0x43175f91, 0x3fece065, - 0x4323ecbe, 0x3fec43c7, 0x433079cc, 0x3feba4b2, - 0x433d06bb, 0x3feb0326, 0x43499389, 0x3fea5f23, - 0x43562038, 0x3fe9b8a9, 0x4362acc5, 0x3fe90fb9, - 0x436f3931, 0x3fe86452, 0x437bc57b, 0x3fe7b674, - 0x438851a2, 0x3fe7061f, 0x4394dda7, 0x3fe65354, - 0x43a16988, 0x3fe59e12, 0x43adf546, 0x3fe4e659, - 0x43ba80df, 0x3fe42c2a, 0x43c70c54, 0x3fe36f84, - 0x43d397a3, 0x3fe2b067, 0x43e022cc, 0x3fe1eed5, - 0x43ecadcf, 0x3fe12acb, 0x43f938ac, 0x3fe0644b, - 0x4405c361, 0x3fdf9b55, 0x44124dee, 0x3fdecfe8, - 0x441ed854, 0x3fde0205, 0x442b6290, 0x3fdd31ac, - 0x4437eca4, 0x3fdc5edc, 0x4444768d, 0x3fdb8996, - 0x4451004d, 0x3fdab1d9, 0x445d89e2, 0x3fd9d7a7, - 0x446a134c, 0x3fd8fafe, 0x44769c8b, 0x3fd81bdf, - 0x4483259d, 0x3fd73a4a, 0x448fae83, 0x3fd6563f, - 0x449c373c, 0x3fd56fbe, 0x44a8bfc7, 0x3fd486c7, - 0x44b54825, 0x3fd39b5a, 0x44c1d054, 0x3fd2ad77, - 0x44ce5854, 0x3fd1bd1e, 0x44dae024, 0x3fd0ca4f, - 0x44e767c5, 0x3fcfd50b, 0x44f3ef35, 0x3fcedd50, - 0x45007674, 0x3fcde320, 0x450cfd82, 0x3fcce67a, - 0x4519845e, 0x3fcbe75e, 0x45260b08, 0x3fcae5cd, - 0x4532917f, 0x3fc9e1c6, 0x453f17c3, 0x3fc8db4a, - 0x454b9dd3, 0x3fc7d258, 0x455823ae, 0x3fc6c6f0, - 0x4564a955, 0x3fc5b913, 0x45712ec7, 0x3fc4a8c1, - 0x457db403, 0x3fc395f9, 0x458a3908, 0x3fc280bc, - 0x4596bdd7, 0x3fc1690a, 0x45a3426f, 0x3fc04ee3, - 0x45afc6d0, 0x3fbf3246, 0x45bc4af8, 0x3fbe1334, - 0x45c8cee7, 0x3fbcf1ad, 0x45d5529e, 0x3fbbcdb1, - 0x45e1d61b, 0x3fbaa740, 0x45ee595d, 0x3fb97e5a, - 0x45fadc66, 0x3fb852ff, 0x46075f33, 0x3fb7252f, - 0x4613e1c5, 0x3fb5f4ea, 0x4620641a, 0x3fb4c231, - 0x462ce634, 0x3fb38d02, 0x46396810, 0x3fb2555f, - 0x4645e9af, 0x3fb11b48, 0x46526b10, 0x3fafdebb, - 0x465eec33, 0x3fae9fbb, 0x466b6d16, 0x3fad5e45, - 0x4677edbb, 0x3fac1a5b, 0x46846e1f, 0x3faad3fd, - 0x4690ee44, 0x3fa98b2a, 0x469d6e27, 0x3fa83fe3, - 0x46a9edc9, 0x3fa6f228, 0x46b66d29, 0x3fa5a1f9, - 0x46c2ec48, 0x3fa44f55, 0x46cf6b23, 0x3fa2fa3d, - 0x46dbe9bb, 0x3fa1a2b2, 0x46e86810, 0x3fa048b2, - 0x46f4e620, 0x3f9eec3e, 0x470163eb, 0x3f9d8d56, - 0x470de172, 0x3f9c2bfb, 0x471a5eb3, 0x3f9ac82c, - 0x4726dbae, 0x3f9961e8, 0x47335862, 0x3f97f932, - 0x473fd4cf, 0x3f968e07, 0x474c50f4, 0x3f952069, - 0x4758ccd2, 0x3f93b058, 0x47654867, 0x3f923dd2, - 0x4771c3b3, 0x3f90c8da, 0x477e3eb5, 0x3f8f516e, - 0x478ab96e, 0x3f8dd78f, 0x479733dc, 0x3f8c5b3d, - 0x47a3adff, 0x3f8adc77, 0x47b027d7, 0x3f895b3e, - 0x47bca163, 0x3f87d792, 0x47c91aa3, 0x3f865174, - 0x47d59396, 0x3f84c8e2, 0x47e20c3b, 0x3f833ddd, - 0x47ee8493, 0x3f81b065, 0x47fafc9c, 0x3f80207b, - 0x48077457, 0x3f7e8e1e, 0x4813ebc2, 0x3f7cf94e, - 0x482062de, 0x3f7b620c, 0x482cd9a9, 0x3f79c857, - 0x48395024, 0x3f782c30, 0x4845c64d, 0x3f768d96, - 0x48523c25, 0x3f74ec8a, 0x485eb1ab, 0x3f73490b, - 0x486b26de, 0x3f71a31b, 0x48779bbe, 0x3f6ffab8, - 0x4884104b, 0x3f6e4fe3, 0x48908483, 0x3f6ca29c, - 0x489cf867, 0x3f6af2e3, 0x48a96bf6, 0x3f6940b8, - 0x48b5df30, 0x3f678c1c, 0x48c25213, 0x3f65d50d, - 0x48cec4a0, 0x3f641b8d, 0x48db36d6, 0x3f625f9b, - 0x48e7a8b5, 0x3f60a138, 0x48f41a3c, 0x3f5ee063, - 0x49008b6a, 0x3f5d1d1d, 0x490cfc40, 0x3f5b5765, - 0x49196cbc, 0x3f598f3c, 0x4925dcdf, 0x3f57c4a2, - 0x49324ca7, 0x3f55f796, 0x493ebc14, 0x3f54281a, - 0x494b2b27, 0x3f52562c, 0x495799dd, 0x3f5081cd, - 0x49640837, 0x3f4eaafe, 0x49707635, 0x3f4cd1be, - 0x497ce3d5, 0x3f4af60d, 0x49895118, 0x3f4917eb, - 0x4995bdfd, 0x3f473759, 0x49a22a83, 0x3f455456, - 0x49ae96aa, 0x3f436ee3, 0x49bb0271, 0x3f4186ff, - 0x49c76dd8, 0x3f3f9cab, 0x49d3d8df, 0x3f3dafe7, - 0x49e04385, 0x3f3bc0b3, 0x49ecadc9, 0x3f39cf0e, - 0x49f917ac, 0x3f37dafa, 0x4a05812c, 0x3f35e476, - 0x4a11ea49, 0x3f33eb81, 0x4a1e5303, 0x3f31f01d, - 0x4a2abb59, 0x3f2ff24a, 0x4a37234a, 0x3f2df206, - 0x4a438ad7, 0x3f2bef53, 0x4a4ff1fe, 0x3f29ea31, - 0x4a5c58c0, 0x3f27e29f, 0x4a68bf1b, 0x3f25d89e, - 0x4a752510, 0x3f23cc2e, 0x4a818a9d, 0x3f21bd4e, - 0x4a8defc3, 0x3f1fabff, 0x4a9a5480, 0x3f1d9842, - 0x4aa6b8d5, 0x3f1b8215, 0x4ab31cc1, 0x3f19697a, - 0x4abf8043, 0x3f174e70, 0x4acbe35b, 0x3f1530f7, - 0x4ad84609, 0x3f13110f, 0x4ae4a84b, 0x3f10eeb9, - 0x4af10a22, 0x3f0ec9f5, 0x4afd6b8d, 0x3f0ca2c2, - 0x4b09cc8c, 0x3f0a7921, 0x4b162d1d, 0x3f084d12, - 0x4b228d42, 0x3f061e95, 0x4b2eecf8, 0x3f03eda9, - 0x4b3b4c40, 0x3f01ba50, 0x4b47ab19, 0x3eff8489, - 0x4b540982, 0x3efd4c54, 0x4b60677c, 0x3efb11b1, - 0x4b6cc506, 0x3ef8d4a1, 0x4b79221f, 0x3ef69523, - 0x4b857ec7, 0x3ef45338, 0x4b91dafc, 0x3ef20ee0, - 0x4b9e36c0, 0x3eefc81a, 0x4baa9211, 0x3eed7ee7, - 0x4bb6ecef, 0x3eeb3347, 0x4bc34759, 0x3ee8e53a, - 0x4bcfa150, 0x3ee694c1, 0x4bdbfad1, 0x3ee441da, - 0x4be853de, 0x3ee1ec87, 0x4bf4ac75, 0x3edf94c7, - 0x4c010496, 0x3edd3a9a, 0x4c0d5c41, 0x3edade01, - 0x4c19b374, 0x3ed87efc, 0x4c260a31, 0x3ed61d8a, - 0x4c326075, 0x3ed3b9ad, 0x4c3eb641, 0x3ed15363, - 0x4c4b0b94, 0x3eceeaad, 0x4c57606e, 0x3ecc7f8b, - 0x4c63b4ce, 0x3eca11fe, 0x4c7008b3, 0x3ec7a205, - 0x4c7c5c1e, 0x3ec52fa0, 0x4c88af0e, 0x3ec2bad0, - 0x4c950182, 0x3ec04394, 0x4ca1537a, 0x3ebdc9ed, - 0x4cada4f5, 0x3ebb4ddb, 0x4cb9f5f3, 0x3eb8cf5d, - 0x4cc64673, 0x3eb64e75, 0x4cd29676, 0x3eb3cb21, - 0x4cdee5f9, 0x3eb14563, 0x4ceb34fe, 0x3eaebd3a, - 0x4cf78383, 0x3eac32a6, 0x4d03d189, 0x3ea9a5a8, - 0x4d101f0e, 0x3ea7163f, 0x4d1c6c11, 0x3ea4846c, - 0x4d28b894, 0x3ea1f02f, 0x4d350495, 0x3e9f5988, - 0x4d415013, 0x3e9cc076, 0x4d4d9b0e, 0x3e9a24fb, - 0x4d59e586, 0x3e978715, 0x4d662f7b, 0x3e94e6c6, - 0x4d7278eb, 0x3e92440d, 0x4d7ec1d6, 0x3e8f9eeb, - 0x4d8b0a3d, 0x3e8cf75f, 0x4d97521d, 0x3e8a4d6a, - 0x4da39978, 0x3e87a10c, 0x4dafe04b, 0x3e84f245, - 0x4dbc2698, 0x3e824114, 0x4dc86c5d, 0x3e7f8d7b, - 0x4dd4b19a, 0x3e7cd778, 0x4de0f64f, 0x3e7a1f0d, - 0x4ded3a7b, 0x3e77643a, 0x4df97e1d, 0x3e74a6fd, - 0x4e05c135, 0x3e71e759, 0x4e1203c3, 0x3e6f254c, - 0x4e1e45c6, 0x3e6c60d7, 0x4e2a873e, 0x3e6999fa, - 0x4e36c82a, 0x3e66d0b4, 0x4e430889, 0x3e640507, - 0x4e4f485c, 0x3e6136f3, 0x4e5b87a2, 0x3e5e6676, - 0x4e67c65a, 0x3e5b9392, 0x4e740483, 0x3e58be47, - 0x4e80421e, 0x3e55e694, 0x4e8c7f2a, 0x3e530c7a, - 0x4e98bba7, 0x3e502ff9, 0x4ea4f793, 0x3e4d5110, - 0x4eb132ef, 0x3e4a6fc1, 0x4ebd6db9, 0x3e478c0b, - 0x4ec9a7f3, 0x3e44a5ef, 0x4ed5e19a, 0x3e41bd6c, - 0x4ee21aaf, 0x3e3ed282, 0x4eee5331, 0x3e3be532, - 0x4efa8b20, 0x3e38f57c, 0x4f06c27a, 0x3e360360, - 0x4f12f941, 0x3e330ede, 0x4f1f2f73, 0x3e3017f6, - 0x4f2b650f, 0x3e2d1ea8, 0x4f379a16, 0x3e2a22f4, - 0x4f43ce86, 0x3e2724db, 0x4f500260, 0x3e24245d, - 0x4f5c35a3, 0x3e212179, 0x4f68684e, 0x3e1e1c30, - 0x4f749a61, 0x3e1b1482, 0x4f80cbdc, 0x3e180a6f, - 0x4f8cfcbe, 0x3e14fdf7, 0x4f992d06, 0x3e11ef1b, - 0x4fa55cb4, 0x3e0eddd9, 0x4fb18bc8, 0x3e0bca34, - 0x4fbdba40, 0x3e08b42a, 0x4fc9e81e, 0x3e059bbb, - 0x4fd6155f, 0x3e0280e9, 0x4fe24205, 0x3dff63b2, - 0x4fee6e0d, 0x3dfc4418, 0x4ffa9979, 0x3df9221a, - 0x5006c446, 0x3df5fdb8, 0x5012ee76, 0x3df2d6f3, - 0x501f1807, 0x3defadca, 0x502b40f8, 0x3dec823e, - 0x5037694b, 0x3de9544f, 0x504390fd, 0x3de623fd, - 0x504fb80e, 0x3de2f148, 0x505bde7f, 0x3ddfbc30, - 0x5068044e, 0x3ddc84b5, 0x5074297b, 0x3dd94ad8, - 0x50804e06, 0x3dd60e99, 0x508c71ee, 0x3dd2cff7, - 0x50989532, 0x3dcf8ef3, 0x50a4b7d3, 0x3dcc4b8d, - 0x50b0d9d0, 0x3dc905c5, 0x50bcfb28, 0x3dc5bd9b, - 0x50c91bda, 0x3dc2730f, 0x50d53be7, 0x3dbf2622, - 0x50e15b4e, 0x3dbbd6d4, 0x50ed7a0e, 0x3db88524, - 0x50f99827, 0x3db53113, 0x5105b599, 0x3db1daa2, - 0x5111d263, 0x3dae81cf, 0x511dee84, 0x3dab269b, - 0x512a09fc, 0x3da7c907, 0x513624cb, 0x3da46912, - 0x51423ef0, 0x3da106bd, 0x514e586a, 0x3d9da208, - 0x515a713a, 0x3d9a3af2, 0x5166895f, 0x3d96d17d, - 0x5172a0d7, 0x3d9365a8, 0x517eb7a4, 0x3d8ff772, - 0x518acdc4, 0x3d8c86de, 0x5196e337, 0x3d8913ea, - 0x51a2f7fc, 0x3d859e96, 0x51af0c13, 0x3d8226e4, - 0x51bb1f7c, 0x3d7eacd2, 0x51c73235, 0x3d7b3061, - 0x51d3443f, 0x3d77b192, 0x51df5599, 0x3d743064, - 0x51eb6643, 0x3d70acd7, 0x51f7763c, 0x3d6d26ec, - 0x52038584, 0x3d699ea3, 0x520f941a, 0x3d6613fb, - 0x521ba1fd, 0x3d6286f6, 0x5227af2e, 0x3d5ef793, - 0x5233bbac, 0x3d5b65d2, 0x523fc776, 0x3d57d1b3, - 0x524bd28c, 0x3d543b37, 0x5257dced, 0x3d50a25e, - 0x5263e699, 0x3d4d0728, 0x526fef90, 0x3d496994, - 0x527bf7d1, 0x3d45c9a4, 0x5287ff5b, 0x3d422757, - 0x5294062f, 0x3d3e82ae, 0x52a00c4b, 0x3d3adba7, - 0x52ac11af, 0x3d373245, 0x52b8165b, 0x3d338687, - 0x52c41a4f, 0x3d2fd86c, 0x52d01d89, 0x3d2c27f6, - 0x52dc2009, 0x3d287523, 0x52e821cf, 0x3d24bff6, - 0x52f422db, 0x3d21086c, 0x5300232c, 0x3d1d4e88, - 0x530c22c1, 0x3d199248, 0x5318219a, 0x3d15d3ad, - 0x53241fb6, 0x3d1212b7, 0x53301d16, 0x3d0e4f67, - 0x533c19b8, 0x3d0a89bc, 0x5348159d, 0x3d06c1b6, - 0x535410c3, 0x3d02f757, 0x53600b2a, 0x3cff2a9d, - 0x536c04d2, 0x3cfb5b89, 0x5377fdbb, 0x3cf78a1b, - 0x5383f5e3, 0x3cf3b653, 0x538fed4b, 0x3cefe032, - 0x539be3f2, 0x3cec07b8, 0x53a7d9d7, 0x3ce82ce4, - 0x53b3cefa, 0x3ce44fb7, 0x53bfc35b, 0x3ce07031, - 0x53cbb6f8, 0x3cdc8e52, 0x53d7a9d3, 0x3cd8aa1b, - 0x53e39be9, 0x3cd4c38b, 0x53ef8d3c, 0x3cd0daa2, - 0x53fb7dc9, 0x3cccef62, 0x54076d91, 0x3cc901c9, - 0x54135c94, 0x3cc511d9, 0x541f4ad1, 0x3cc11f90, - 0x542b3846, 0x3cbd2af0, 0x543724f5, 0x3cb933f9, - 0x544310dd, 0x3cb53aaa, 0x544efbfc, 0x3cb13f04, - 0x545ae653, 0x3cad4107, 0x5466cfe1, 0x3ca940b3, - 0x5472b8a5, 0x3ca53e09, 0x547ea0a0, 0x3ca13908, - 0x548a87d1, 0x3c9d31b0, 0x54966e36, 0x3c992803, - 0x54a253d1, 0x3c951bff, 0x54ae38a0, 0x3c910da5, - 0x54ba1ca3, 0x3c8cfcf6, 0x54c5ffd9, 0x3c88e9f1, - 0x54d1e242, 0x3c84d496, 0x54ddc3de, 0x3c80bce7, - 0x54e9a4ac, 0x3c7ca2e2, 0x54f584ac, 0x3c788688, - 0x550163dc, 0x3c7467d9, 0x550d423d, 0x3c7046d6, - 0x55191fcf, 0x3c6c237e, 0x5524fc90, 0x3c67fdd1, - 0x5530d881, 0x3c63d5d1, 0x553cb3a0, 0x3c5fab7c, - 0x55488dee, 0x3c5b7ed4, 0x5554676a, 0x3c574fd8, - 0x55604013, 0x3c531e88, 0x556c17e9, 0x3c4eeae5, - 0x5577eeec, 0x3c4ab4ef, 0x5583c51b, 0x3c467ca6, - 0x558f9a76, 0x3c42420a, 0x559b6efb, 0x3c3e051b, - 0x55a742ac, 0x3c39c5da, 0x55b31587, 0x3c358446, - 0x55bee78c, 0x3c314060, 0x55cab8ba, 0x3c2cfa28, - 0x55d68911, 0x3c28b19e, 0x55e25890, 0x3c2466c2, - 0x55ee2738, 0x3c201994, 0x55f9f507, 0x3c1bca16, - 0x5605c1fd, 0x3c177845, 0x56118e1a, 0x3c132424, - 0x561d595d, 0x3c0ecdb2, 0x562923c5, 0x3c0a74f0, - 0x5634ed53, 0x3c0619dc, 0x5640b606, 0x3c01bc78, - 0x564c7ddd, 0x3bfd5cc4, 0x565844d8, 0x3bf8fac0, - 0x56640af7, 0x3bf4966c, 0x566fd039, 0x3bf02fc9, - 0x567b949d, 0x3bebc6d5, 0x56875823, 0x3be75b93, - 0x56931acb, 0x3be2ee01, 0x569edc94, 0x3bde7e20, - 0x56aa9d7e, 0x3bda0bf0, 0x56b65d88, 0x3bd59771, - 0x56c21cb2, 0x3bd120a4, 0x56cddafb, 0x3bcca789, - 0x56d99864, 0x3bc82c1f, 0x56e554ea, 0x3bc3ae67, - 0x56f1108f, 0x3bbf2e62, 0x56fccb51, 0x3bbaac0e, - 0x57088531, 0x3bb6276e, 0x57143e2d, 0x3bb1a080, - 0x571ff646, 0x3bad1744, 0x572bad7a, 0x3ba88bbc, - 0x573763c9, 0x3ba3fde7, 0x57431933, 0x3b9f6dc5, - 0x574ecdb8, 0x3b9adb57, 0x575a8157, 0x3b96469d, - 0x5766340f, 0x3b91af97, 0x5771e5e0, 0x3b8d1644, - 0x577d96ca, 0x3b887aa6, 0x578946cc, 0x3b83dcbc, - 0x5794f5e6, 0x3b7f3c87, 0x57a0a417, 0x3b7a9a07, - 0x57ac515f, 0x3b75f53c, 0x57b7fdbd, 0x3b714e25, - 0x57c3a931, 0x3b6ca4c4, 0x57cf53bb, 0x3b67f919, - 0x57dafd59, 0x3b634b23, 0x57e6a60c, 0x3b5e9ae4, - 0x57f24dd3, 0x3b59e85a, 0x57fdf4ae, 0x3b553386, - 0x58099a9c, 0x3b507c69, 0x58153f9d, 0x3b4bc303, - 0x5820e3b0, 0x3b470753, 0x582c86d5, 0x3b42495a, - 0x5838290c, 0x3b3d8918, 0x5843ca53, 0x3b38c68e, - 0x584f6aab, 0x3b3401bb, 0x585b0a13, 0x3b2f3aa0, - 0x5866a88a, 0x3b2a713d, 0x58724611, 0x3b25a591, - 0x587de2a7, 0x3b20d79e, 0x58897e4a, 0x3b1c0764, - 0x589518fc, 0x3b1734e2, 0x58a0b2bb, 0x3b126019, - 0x58ac4b87, 0x3b0d8909, 0x58b7e35f, 0x3b08afb2, - 0x58c37a44, 0x3b03d414, 0x58cf1034, 0x3afef630, - 0x58daa52f, 0x3afa1605, 0x58e63935, 0x3af53395, - 0x58f1cc45, 0x3af04edf, 0x58fd5e5f, 0x3aeb67e3, - 0x5908ef82, 0x3ae67ea1, 0x59147fae, 0x3ae1931a, - 0x59200ee3, 0x3adca54e, 0x592b9d1f, 0x3ad7b53d, - 0x59372a64, 0x3ad2c2e8, 0x5942b6af, 0x3acdce4d, - 0x594e4201, 0x3ac8d76f, 0x5959cc5a, 0x3ac3de4c, - 0x596555b8, 0x3abee2e5, 0x5970de1b, 0x3ab9e53a, - 0x597c6584, 0x3ab4e54c, 0x5987ebf0, 0x3aafe31b, - 0x59937161, 0x3aaadea6, 0x599ef5d6, 0x3aa5d7ee, - 0x59aa794d, 0x3aa0cef3, 0x59b5fbc8, 0x3a9bc3b6, - 0x59c17d44, 0x3a96b636, 0x59ccfdc2, 0x3a91a674, - 0x59d87d42, 0x3a8c9470, 0x59e3fbc3, 0x3a87802a, - 0x59ef7944, 0x3a8269a3, 0x59faf5c5, 0x3a7d50da, - 0x5a067145, 0x3a7835cf, 0x5a11ebc5, 0x3a731884, - 0x5a1d6544, 0x3a6df8f8, 0x5a28ddc0, 0x3a68d72b, - 0x5a34553b, 0x3a63b31d, 0x5a3fcbb3, 0x3a5e8cd0, - 0x5a4b4128, 0x3a596442, 0x5a56b599, 0x3a543974, - 0x5a622907, 0x3a4f0c67, 0x5a6d9b70, 0x3a49dd1a, - 0x5a790cd4, 0x3a44ab8e, 0x5a847d33, 0x3a3f77c3, - 0x5a8fec8c, 0x3a3a41b9, 0x5a9b5adf, 0x3a350970, - 0x5aa6c82b, 0x3a2fcee8, 0x5ab23471, 0x3a2a9223, - 0x5abd9faf, 0x3a25531f, 0x5ac909e5, 0x3a2011de, - 0x5ad47312, 0x3a1ace5f, 0x5adfdb37, 0x3a1588a2, - 0x5aeb4253, 0x3a1040a8, 0x5af6a865, 0x3a0af671, - 0x5b020d6c, 0x3a05a9fd, 0x5b0d716a, 0x3a005b4d, - 0x5b18d45c, 0x39fb0a60, 0x5b243643, 0x39f5b737, - 0x5b2f971e, 0x39f061d2, 0x5b3af6ec, 0x39eb0a31, - 0x5b4655ae, 0x39e5b054, 0x5b51b363, 0x39e0543c, - 0x5b5d100a, 0x39daf5e8, 0x5b686ba3, 0x39d5955a, - 0x5b73c62d, 0x39d03291, 0x5b7f1fa9, 0x39cacd8d, - 0x5b8a7815, 0x39c5664f, 0x5b95cf71, 0x39bffcd7, - 0x5ba125bd, 0x39ba9125, 0x5bac7af9, 0x39b52339, - 0x5bb7cf23, 0x39afb313, 0x5bc3223c, 0x39aa40b4, - 0x5bce7442, 0x39a4cc1c, 0x5bd9c537, 0x399f554b, - 0x5be51518, 0x3999dc42, 0x5bf063e6, 0x399460ff, - 0x5bfbb1a0, 0x398ee385, 0x5c06fe46, 0x398963d2, - 0x5c1249d8, 0x3983e1e8, 0x5c1d9454, 0x397e5dc6, - 0x5c28ddbb, 0x3978d76c, 0x5c34260c, 0x39734edc, - 0x5c3f6d47, 0x396dc414, 0x5c4ab36b, 0x39683715, - 0x5c55f878, 0x3962a7e0, 0x5c613c6d, 0x395d1675, - 0x5c6c7f4a, 0x395782d3, 0x5c77c10e, 0x3951ecfc, - 0x5c8301b9, 0x394c54ee, 0x5c8e414b, 0x3946baac, - 0x5c997fc4, 0x39411e33, 0x5ca4bd21, 0x393b7f86, - 0x5caff965, 0x3935dea4, 0x5cbb348d, 0x39303b8e, - 0x5cc66e99, 0x392a9642, 0x5cd1a78a, 0x3924eec3, - 0x5cdcdf5e, 0x391f4510, 0x5ce81615, 0x39199929, - 0x5cf34baf, 0x3913eb0e, 0x5cfe802b, 0x390e3ac0, - 0x5d09b389, 0x3908883f, 0x5d14e5c9, 0x3902d38b, - 0x5d2016e9, 0x38fd1ca4, 0x5d2b46ea, 0x38f7638b, - 0x5d3675cb, 0x38f1a840, 0x5d41a38c, 0x38ebeac2, - 0x5d4cd02c, 0x38e62b13, 0x5d57fbaa, 0x38e06932, - 0x5d632608, 0x38daa520, 0x5d6e4f43, 0x38d4dedd, - 0x5d79775c, 0x38cf1669, 0x5d849e51, 0x38c94bc4, - 0x5d8fc424, 0x38c37eef, 0x5d9ae8d2, 0x38bdafea, - 0x5da60c5d, 0x38b7deb4, 0x5db12ec3, 0x38b20b4f, - 0x5dbc5004, 0x38ac35ba, 0x5dc7701f, 0x38a65df6, - 0x5dd28f15, 0x38a08402, 0x5dddace4, 0x389aa7e0, - 0x5de8c98c, 0x3894c98f, 0x5df3e50d, 0x388ee910, - 0x5dfeff67, 0x38890663, 0x5e0a1898, 0x38832187, - 0x5e1530a1, 0x387d3a7e, 0x5e204781, 0x38775147, - 0x5e2b5d38, 0x387165e3, 0x5e3671c5, 0x386b7852, - 0x5e418528, 0x38658894, 0x5e4c9760, 0x385f96a9, - 0x5e57a86d, 0x3859a292, 0x5e62b84f, 0x3853ac4f, - 0x5e6dc705, 0x384db3e0, 0x5e78d48e, 0x3847b946, - 0x5e83e0eb, 0x3841bc7f, 0x5e8eec1b, 0x383bbd8e, - 0x5e99f61d, 0x3835bc71, 0x5ea4fef0, 0x382fb92a, - 0x5eb00696, 0x3829b3b9, 0x5ebb0d0d, 0x3823ac1d, - 0x5ec61254, 0x381da256, 0x5ed1166b, 0x38179666, - 0x5edc1953, 0x3811884d, 0x5ee71b0a, 0x380b780a, - 0x5ef21b90, 0x3805659e, 0x5efd1ae4, 0x37ff5109, - 0x5f081907, 0x37f93a4b, 0x5f1315f7, 0x37f32165, - 0x5f1e11b5, 0x37ed0657, 0x5f290c3f, 0x37e6e921, - 0x5f340596, 0x37e0c9c3, 0x5f3efdb9, 0x37daa83d, - 0x5f49f4a8, 0x37d48490, 0x5f54ea62, 0x37ce5ebd, - 0x5f5fdee6, 0x37c836c2, 0x5f6ad235, 0x37c20ca1, - 0x5f75c44e, 0x37bbe05a, 0x5f80b531, 0x37b5b1ec, - 0x5f8ba4dc, 0x37af8159, 0x5f969350, 0x37a94ea0, - 0x5fa1808c, 0x37a319c2, 0x5fac6c91, 0x379ce2be, - 0x5fb7575c, 0x3796a996, 0x5fc240ef, 0x37906e49, - 0x5fcd2948, 0x378a30d8, 0x5fd81067, 0x3783f143, - 0x5fe2f64c, 0x377daf89, 0x5feddaf6, 0x37776bac, - 0x5ff8be65, 0x377125ac, 0x6003a099, 0x376add88, - 0x600e8190, 0x37649341, 0x6019614c, 0x375e46d8, - 0x60243fca, 0x3757f84c, 0x602f1d0b, 0x3751a79e, - 0x6039f90f, 0x374b54ce, 0x6044d3d4, 0x3744ffdd, - 0x604fad5b, 0x373ea8ca, 0x605a85a3, 0x37384f95, - 0x60655cac, 0x3731f440, 0x60703275, 0x372b96ca, - 0x607b06fe, 0x37253733, 0x6085da46, 0x371ed57c, - 0x6090ac4d, 0x371871a5, 0x609b7d13, 0x37120bae, - 0x60a64c97, 0x370ba398, 0x60b11ad9, 0x37053962, - 0x60bbe7d8, 0x36fecd0e, 0x60c6b395, 0x36f85e9a, - 0x60d17e0d, 0x36f1ee09, 0x60dc4742, 0x36eb7b58, - 0x60e70f32, 0x36e5068a, 0x60f1d5de, 0x36de8f9e, - 0x60fc9b44, 0x36d81695, 0x61075f65, 0x36d19b6e, - 0x61122240, 0x36cb1e2a, 0x611ce3d5, 0x36c49ec9, - 0x6127a423, 0x36be1d4c, 0x61326329, 0x36b799b3, - 0x613d20e8, 0x36b113fd, 0x6147dd5f, 0x36aa8c2c, - 0x6152988d, 0x36a4023f, 0x615d5273, 0x369d7637, - 0x61680b0f, 0x3696e814, 0x6172c262, 0x369057d6, - 0x617d786a, 0x3689c57d, 0x61882d28, 0x3683310b, - 0x6192e09b, 0x367c9a7e, 0x619d92c2, 0x367601d7, - 0x61a8439e, 0x366f6717, 0x61b2f32e, 0x3668ca3e, - 0x61bda171, 0x36622b4c, 0x61c84e67, 0x365b8a41, - 0x61d2fa0f, 0x3654e71d, 0x61dda46a, 0x364e41e2, - 0x61e84d76, 0x36479a8e, 0x61f2f534, 0x3640f123, - 0x61fd9ba3, 0x363a45a0, 0x620840c2, 0x36339806, - 0x6212e492, 0x362ce855, 0x621d8711, 0x3626368d, - 0x6228283f, 0x361f82af, 0x6232c81c, 0x3618ccba, - 0x623d66a8, 0x361214b0, 0x624803e2, 0x360b5a90, - 0x62529fca, 0x36049e5b, 0x625d3a5e, 0x35fde011, - 0x6267d3a0, 0x35f71fb1, 0x62726b8e, 0x35f05d3d, - 0x627d0228, 0x35e998b5, 0x6287976e, 0x35e2d219, - 0x62922b5e, 0x35dc0968, 0x629cbdfa, 0x35d53ea5, - 0x62a74f40, 0x35ce71ce, 0x62b1df30, 0x35c7a2e3, - 0x62bc6dca, 0x35c0d1e7, 0x62c6fb0c, 0x35b9fed7, - 0x62d186f8, 0x35b329b5, 0x62dc118c, 0x35ac5282, - 0x62e69ac8, 0x35a5793c, 0x62f122ab, 0x359e9de5, - 0x62fba936, 0x3597c07d, 0x63062e67, 0x3590e104, - 0x6310b23e, 0x3589ff7a, 0x631b34bc, 0x35831be0, - 0x6325b5df, 0x357c3636, 0x633035a7, 0x35754e7c, - 0x633ab414, 0x356e64b2, 0x63453125, 0x356778d9, - 0x634facda, 0x35608af1, 0x635a2733, 0x35599afa, - 0x6364a02e, 0x3552a8f4, 0x636f17cc, 0x354bb4e1, - 0x63798e0d, 0x3544bebf, 0x638402ef, 0x353dc68f, - 0x638e7673, 0x3536cc52, 0x6398e898, 0x352fd008, - 0x63a3595e, 0x3528d1b1, 0x63adc8c4, 0x3521d14d, - 0x63b836ca, 0x351acedd, 0x63c2a36f, 0x3513ca60, - 0x63cd0eb3, 0x350cc3d8, 0x63d77896, 0x3505bb44, - 0x63e1e117, 0x34feb0a5, 0x63ec4837, 0x34f7a3fb, - 0x63f6adf3, 0x34f09546, 0x6401124d, 0x34e98487, - 0x640b7543, 0x34e271bd, 0x6415d6d5, 0x34db5cea, - 0x64203704, 0x34d4460c, 0x642a95ce, 0x34cd2d26, - 0x6434f332, 0x34c61236, 0x643f4f32, 0x34bef53d, - 0x6449a9cc, 0x34b7d63c, 0x645402ff, 0x34b0b533, - 0x645e5acc, 0x34a99221, 0x6468b132, 0x34a26d08, - 0x64730631, 0x349b45e7, 0x647d59c8, 0x34941cbf, - 0x6487abf7, 0x348cf190, 0x6491fcbe, 0x3485c45b, - 0x649c4c1b, 0x347e951f, 0x64a69a0f, 0x347763dd, - 0x64b0e699, 0x34703095, 0x64bb31ba, 0x3468fb47, - 0x64c57b6f, 0x3461c3f5, 0x64cfc3ba, 0x345a8a9d, - 0x64da0a9a, 0x34534f41, 0x64e4500e, 0x344c11e0, - 0x64ee9415, 0x3444d27b, 0x64f8d6b0, 0x343d9112, - 0x650317df, 0x34364da6, 0x650d57a0, 0x342f0836, - 0x651795f3, 0x3427c0c3, 0x6521d2d8, 0x3420774d, - 0x652c0e4f, 0x34192bd5, 0x65364857, 0x3411de5b, - 0x654080ef, 0x340a8edf, 0x654ab818, 0x34033d61, - 0x6554edd1, 0x33fbe9e2, 0x655f2219, 0x33f49462, - 0x656954f1, 0x33ed3ce1, 0x65738657, 0x33e5e360, - 0x657db64c, 0x33de87de, 0x6587e4cf, 0x33d72a5d, - 0x659211df, 0x33cfcadc, 0x659c3d7c, 0x33c8695b, - 0x65a667a7, 0x33c105db, 0x65b0905d, 0x33b9a05d, - 0x65bab7a0, 0x33b238e0, 0x65c4dd6e, 0x33aacf65, - 0x65cf01c8, 0x33a363ec, 0x65d924ac, 0x339bf675, - 0x65e3461b, 0x33948701, 0x65ed6614, 0x338d1590, - 0x65f78497, 0x3385a222, 0x6601a1a2, 0x337e2cb7, - 0x660bbd37, 0x3376b551, 0x6615d754, 0x336f3bee, - 0x661feffa, 0x3367c090, 0x662a0727, 0x33604336, - 0x66341cdb, 0x3358c3e2, 0x663e3117, 0x33514292, - 0x664843d9, 0x3349bf48, 0x66525521, 0x33423a04, - 0x665c64ef, 0x333ab2c6, 0x66667342, 0x3333298f, - 0x6670801a, 0x332b9e5e, 0x667a8b77, 0x33241134, - 0x66849558, 0x331c8211, 0x668e9dbd, 0x3314f0f6, - 0x6698a4a6, 0x330d5de3, 0x66a2aa11, 0x3305c8d7, - 0x66acadff, 0x32fe31d5, 0x66b6b070, 0x32f698db, - 0x66c0b162, 0x32eefdea, 0x66cab0d6, 0x32e76102, - 0x66d4aecb, 0x32dfc224, 0x66deab41, 0x32d82150, - 0x66e8a637, 0x32d07e85, 0x66f29fad, 0x32c8d9c6, - 0x66fc97a3, 0x32c13311, 0x67068e18, 0x32b98a67, - 0x6710830c, 0x32b1dfc9, 0x671a767e, 0x32aa3336, - 0x6724686e, 0x32a284b0, 0x672e58dc, 0x329ad435, - 0x673847c8, 0x329321c7, 0x67423530, 0x328b6d66, - 0x674c2115, 0x3283b712, 0x67560b76, 0x327bfecc, - 0x675ff452, 0x32744493, 0x6769dbaa, 0x326c8868, - 0x6773c17d, 0x3264ca4c, 0x677da5cb, 0x325d0a3e, - 0x67878893, 0x32554840, 0x679169d5, 0x324d8450, - 0x679b4990, 0x3245be70, 0x67a527c4, 0x323df6a0, - 0x67af0472, 0x32362ce0, 0x67b8df97, 0x322e6130, - 0x67c2b934, 0x32269391, 0x67cc9149, 0x321ec403, - 0x67d667d5, 0x3216f287, 0x67e03cd8, 0x320f1f1c, - 0x67ea1052, 0x320749c3, 0x67f3e241, 0x31ff727c, - 0x67fdb2a7, 0x31f79948, 0x68078181, 0x31efbe27, - 0x68114ed0, 0x31e7e118, 0x681b1a94, 0x31e0021e, - 0x6824e4cc, 0x31d82137, 0x682ead78, 0x31d03e64, - 0x68387498, 0x31c859a5, 0x68423a2a, 0x31c072fb, - 0x684bfe2f, 0x31b88a66, 0x6855c0a6, 0x31b09fe7, - 0x685f8190, 0x31a8b37c, 0x686940ea, 0x31a0c528, - 0x6872feb6, 0x3198d4ea, 0x687cbaf3, 0x3190e2c3, - 0x688675a0, 0x3188eeb2, 0x68902ebd, 0x3180f8b8, - 0x6899e64a, 0x317900d6, 0x68a39c46, 0x3171070c, - 0x68ad50b1, 0x31690b59, 0x68b7038b, 0x31610dbf, - 0x68c0b4d2, 0x31590e3e, 0x68ca6488, 0x31510cd5, - 0x68d412ab, 0x31490986, 0x68ddbf3b, 0x31410450, - 0x68e76a37, 0x3138fd35, 0x68f113a0, 0x3130f433, - 0x68fabb75, 0x3128e94c, 0x690461b5, 0x3120dc80, - 0x690e0661, 0x3118cdcf, 0x6917a977, 0x3110bd39, - 0x69214af8, 0x3108aabf, 0x692aeae3, 0x31009661, - 0x69348937, 0x30f8801f, 0x693e25f5, 0x30f067fb, - 0x6947c11c, 0x30e84df3, 0x69515aab, 0x30e03208, - 0x695af2a3, 0x30d8143b, 0x69648902, 0x30cff48c, - 0x696e1dc9, 0x30c7d2fb, 0x6977b0f7, 0x30bfaf89, - 0x6981428c, 0x30b78a36, 0x698ad287, 0x30af6302, - 0x699460e8, 0x30a739ed, 0x699dedaf, 0x309f0ef8, - 0x69a778db, 0x3096e223, 0x69b1026c, 0x308eb36f, - 0x69ba8a61, 0x308682dc, 0x69c410ba, 0x307e5069, - 0x69cd9578, 0x30761c18, 0x69d71899, 0x306de5e9, - 0x69e09a1c, 0x3065addb, 0x69ea1a03, 0x305d73f0, - 0x69f3984c, 0x30553828, 0x69fd14f6, 0x304cfa83, - 0x6a069003, 0x3044bb00, 0x6a100970, 0x303c79a2, - 0x6a19813f, 0x30343667, 0x6a22f76e, 0x302bf151, - 0x6a2c6bfd, 0x3023aa5f, 0x6a35deeb, 0x301b6193, - 0x6a3f503a, 0x301316eb, 0x6a48bfe7, 0x300aca69, - 0x6a522df3, 0x30027c0c, 0x6a5b9a5d, 0x2ffa2bd6, - 0x6a650525, 0x2ff1d9c7, 0x6a6e6e4b, 0x2fe985de, - 0x6a77d5ce, 0x2fe1301c, 0x6a813bae, 0x2fd8d882, - 0x6a8a9fea, 0x2fd07f0f, 0x6a940283, 0x2fc823c5, - 0x6a9d6377, 0x2fbfc6a3, 0x6aa6c2c6, 0x2fb767aa, - 0x6ab02071, 0x2faf06da, 0x6ab97c77, 0x2fa6a433, - 0x6ac2d6d6, 0x2f9e3fb6, 0x6acc2f90, 0x2f95d963, - 0x6ad586a3, 0x2f8d713a, 0x6adedc10, 0x2f85073c, - 0x6ae82fd5, 0x2f7c9b69, 0x6af181f3, 0x2f742dc1, - 0x6afad269, 0x2f6bbe45, 0x6b042137, 0x2f634cf5, - 0x6b0d6e5c, 0x2f5ad9d1, 0x6b16b9d9, 0x2f5264da, - 0x6b2003ac, 0x2f49ee0f, 0x6b294bd5, 0x2f417573, - 0x6b329255, 0x2f38fb03, 0x6b3bd72a, 0x2f307ec2, - 0x6b451a55, 0x2f2800af, 0x6b4e5bd4, 0x2f1f80ca, - 0x6b579ba8, 0x2f16ff14, 0x6b60d9d0, 0x2f0e7b8e, - 0x6b6a164d, 0x2f05f637, 0x6b73511c, 0x2efd6f10, - 0x6b7c8a3f, 0x2ef4e619, 0x6b85c1b5, 0x2eec5b53, - 0x6b8ef77d, 0x2ee3cebe, 0x6b982b97, 0x2edb405a, - 0x6ba15e03, 0x2ed2b027, 0x6baa8ec0, 0x2eca1e27, - 0x6bb3bdce, 0x2ec18a58, 0x6bbceb2d, 0x2eb8f4bc, - 0x6bc616dd, 0x2eb05d53, 0x6bcf40dc, 0x2ea7c41e, - 0x6bd8692b, 0x2e9f291b, 0x6be18fc9, 0x2e968c4d, - 0x6beab4b6, 0x2e8dedb3, 0x6bf3d7f2, 0x2e854d4d, - 0x6bfcf97c, 0x2e7cab1c, 0x6c061953, 0x2e740720, - 0x6c0f3779, 0x2e6b615a, 0x6c1853eb, 0x2e62b9ca, - 0x6c216eaa, 0x2e5a1070, 0x6c2a87b6, 0x2e51654c, - 0x6c339f0e, 0x2e48b860, 0x6c3cb4b1, 0x2e4009aa, - 0x6c45c8a0, 0x2e37592c, 0x6c4edada, 0x2e2ea6e6, - 0x6c57eb5e, 0x2e25f2d8, 0x6c60fa2d, 0x2e1d3d03, - 0x6c6a0746, 0x2e148566, 0x6c7312a9, 0x2e0bcc03, - 0x6c7c1c55, 0x2e0310d9, 0x6c85244a, 0x2dfa53e9, - 0x6c8e2a87, 0x2df19534, 0x6c972f0d, 0x2de8d4b8, - 0x6ca031da, 0x2de01278, 0x6ca932ef, 0x2dd74e73, - 0x6cb2324c, 0x2dce88aa, 0x6cbb2fef, 0x2dc5c11c, - 0x6cc42bd9, 0x2dbcf7cb, 0x6ccd2609, 0x2db42cb6, - 0x6cd61e7f, 0x2dab5fdf, 0x6cdf153a, 0x2da29144, - 0x6ce80a3a, 0x2d99c0e7, 0x6cf0fd80, 0x2d90eec8, - 0x6cf9ef09, 0x2d881ae8, 0x6d02ded7, 0x2d7f4545, - 0x6d0bcce8, 0x2d766de2, 0x6d14b93d, 0x2d6d94bf, - 0x6d1da3d5, 0x2d64b9da, 0x6d268cb0, 0x2d5bdd36, - 0x6d2f73cd, 0x2d52fed2, 0x6d38592c, 0x2d4a1eaf, - 0x6d413ccd, 0x2d413ccd, 0x6d4a1eaf, 0x2d38592c, - 0x6d52fed2, 0x2d2f73cd, 0x6d5bdd36, 0x2d268cb0, - 0x6d64b9da, 0x2d1da3d5, 0x6d6d94bf, 0x2d14b93d, - 0x6d766de2, 0x2d0bcce8, 0x6d7f4545, 0x2d02ded7, - 0x6d881ae8, 0x2cf9ef09, 0x6d90eec8, 0x2cf0fd80, - 0x6d99c0e7, 0x2ce80a3a, 0x6da29144, 0x2cdf153a, - 0x6dab5fdf, 0x2cd61e7f, 0x6db42cb6, 0x2ccd2609, - 0x6dbcf7cb, 0x2cc42bd9, 0x6dc5c11c, 0x2cbb2fef, - 0x6dce88aa, 0x2cb2324c, 0x6dd74e73, 0x2ca932ef, - 0x6de01278, 0x2ca031da, 0x6de8d4b8, 0x2c972f0d, - 0x6df19534, 0x2c8e2a87, 0x6dfa53e9, 0x2c85244a, - 0x6e0310d9, 0x2c7c1c55, 0x6e0bcc03, 0x2c7312a9, - 0x6e148566, 0x2c6a0746, 0x6e1d3d03, 0x2c60fa2d, - 0x6e25f2d8, 0x2c57eb5e, 0x6e2ea6e6, 0x2c4edada, - 0x6e37592c, 0x2c45c8a0, 0x6e4009aa, 0x2c3cb4b1, - 0x6e48b860, 0x2c339f0e, 0x6e51654c, 0x2c2a87b6, - 0x6e5a1070, 0x2c216eaa, 0x6e62b9ca, 0x2c1853eb, - 0x6e6b615a, 0x2c0f3779, 0x6e740720, 0x2c061953, - 0x6e7cab1c, 0x2bfcf97c, 0x6e854d4d, 0x2bf3d7f2, - 0x6e8dedb3, 0x2beab4b6, 0x6e968c4d, 0x2be18fc9, - 0x6e9f291b, 0x2bd8692b, 0x6ea7c41e, 0x2bcf40dc, - 0x6eb05d53, 0x2bc616dd, 0x6eb8f4bc, 0x2bbceb2d, - 0x6ec18a58, 0x2bb3bdce, 0x6eca1e27, 0x2baa8ec0, - 0x6ed2b027, 0x2ba15e03, 0x6edb405a, 0x2b982b97, - 0x6ee3cebe, 0x2b8ef77d, 0x6eec5b53, 0x2b85c1b5, - 0x6ef4e619, 0x2b7c8a3f, 0x6efd6f10, 0x2b73511c, - 0x6f05f637, 0x2b6a164d, 0x6f0e7b8e, 0x2b60d9d0, - 0x6f16ff14, 0x2b579ba8, 0x6f1f80ca, 0x2b4e5bd4, - 0x6f2800af, 0x2b451a55, 0x6f307ec2, 0x2b3bd72a, - 0x6f38fb03, 0x2b329255, 0x6f417573, 0x2b294bd5, - 0x6f49ee0f, 0x2b2003ac, 0x6f5264da, 0x2b16b9d9, - 0x6f5ad9d1, 0x2b0d6e5c, 0x6f634cf5, 0x2b042137, - 0x6f6bbe45, 0x2afad269, 0x6f742dc1, 0x2af181f3, - 0x6f7c9b69, 0x2ae82fd5, 0x6f85073c, 0x2adedc10, - 0x6f8d713a, 0x2ad586a3, 0x6f95d963, 0x2acc2f90, - 0x6f9e3fb6, 0x2ac2d6d6, 0x6fa6a433, 0x2ab97c77, - 0x6faf06da, 0x2ab02071, 0x6fb767aa, 0x2aa6c2c6, - 0x6fbfc6a3, 0x2a9d6377, 0x6fc823c5, 0x2a940283, - 0x6fd07f0f, 0x2a8a9fea, 0x6fd8d882, 0x2a813bae, - 0x6fe1301c, 0x2a77d5ce, 0x6fe985de, 0x2a6e6e4b, - 0x6ff1d9c7, 0x2a650525, 0x6ffa2bd6, 0x2a5b9a5d, - 0x70027c0c, 0x2a522df3, 0x700aca69, 0x2a48bfe7, - 0x701316eb, 0x2a3f503a, 0x701b6193, 0x2a35deeb, - 0x7023aa5f, 0x2a2c6bfd, 0x702bf151, 0x2a22f76e, - 0x70343667, 0x2a19813f, 0x703c79a2, 0x2a100970, - 0x7044bb00, 0x2a069003, 0x704cfa83, 0x29fd14f6, - 0x70553828, 0x29f3984c, 0x705d73f0, 0x29ea1a03, - 0x7065addb, 0x29e09a1c, 0x706de5e9, 0x29d71899, - 0x70761c18, 0x29cd9578, 0x707e5069, 0x29c410ba, - 0x708682dc, 0x29ba8a61, 0x708eb36f, 0x29b1026c, - 0x7096e223, 0x29a778db, 0x709f0ef8, 0x299dedaf, - 0x70a739ed, 0x299460e8, 0x70af6302, 0x298ad287, - 0x70b78a36, 0x2981428c, 0x70bfaf89, 0x2977b0f7, - 0x70c7d2fb, 0x296e1dc9, 0x70cff48c, 0x29648902, - 0x70d8143b, 0x295af2a3, 0x70e03208, 0x29515aab, - 0x70e84df3, 0x2947c11c, 0x70f067fb, 0x293e25f5, - 0x70f8801f, 0x29348937, 0x71009661, 0x292aeae3, - 0x7108aabf, 0x29214af8, 0x7110bd39, 0x2917a977, - 0x7118cdcf, 0x290e0661, 0x7120dc80, 0x290461b5, - 0x7128e94c, 0x28fabb75, 0x7130f433, 0x28f113a0, - 0x7138fd35, 0x28e76a37, 0x71410450, 0x28ddbf3b, - 0x71490986, 0x28d412ab, 0x71510cd5, 0x28ca6488, - 0x71590e3e, 0x28c0b4d2, 0x71610dbf, 0x28b7038b, - 0x71690b59, 0x28ad50b1, 0x7171070c, 0x28a39c46, - 0x717900d6, 0x2899e64a, 0x7180f8b8, 0x28902ebd, - 0x7188eeb2, 0x288675a0, 0x7190e2c3, 0x287cbaf3, - 0x7198d4ea, 0x2872feb6, 0x71a0c528, 0x286940ea, - 0x71a8b37c, 0x285f8190, 0x71b09fe7, 0x2855c0a6, - 0x71b88a66, 0x284bfe2f, 0x71c072fb, 0x28423a2a, - 0x71c859a5, 0x28387498, 0x71d03e64, 0x282ead78, - 0x71d82137, 0x2824e4cc, 0x71e0021e, 0x281b1a94, - 0x71e7e118, 0x28114ed0, 0x71efbe27, 0x28078181, - 0x71f79948, 0x27fdb2a7, 0x71ff727c, 0x27f3e241, - 0x720749c3, 0x27ea1052, 0x720f1f1c, 0x27e03cd8, - 0x7216f287, 0x27d667d5, 0x721ec403, 0x27cc9149, - 0x72269391, 0x27c2b934, 0x722e6130, 0x27b8df97, - 0x72362ce0, 0x27af0472, 0x723df6a0, 0x27a527c4, - 0x7245be70, 0x279b4990, 0x724d8450, 0x279169d5, - 0x72554840, 0x27878893, 0x725d0a3e, 0x277da5cb, - 0x7264ca4c, 0x2773c17d, 0x726c8868, 0x2769dbaa, - 0x72744493, 0x275ff452, 0x727bfecc, 0x27560b76, - 0x7283b712, 0x274c2115, 0x728b6d66, 0x27423530, - 0x729321c7, 0x273847c8, 0x729ad435, 0x272e58dc, - 0x72a284b0, 0x2724686e, 0x72aa3336, 0x271a767e, - 0x72b1dfc9, 0x2710830c, 0x72b98a67, 0x27068e18, - 0x72c13311, 0x26fc97a3, 0x72c8d9c6, 0x26f29fad, - 0x72d07e85, 0x26e8a637, 0x72d82150, 0x26deab41, - 0x72dfc224, 0x26d4aecb, 0x72e76102, 0x26cab0d6, - 0x72eefdea, 0x26c0b162, 0x72f698db, 0x26b6b070, - 0x72fe31d5, 0x26acadff, 0x7305c8d7, 0x26a2aa11, - 0x730d5de3, 0x2698a4a6, 0x7314f0f6, 0x268e9dbd, - 0x731c8211, 0x26849558, 0x73241134, 0x267a8b77, - 0x732b9e5e, 0x2670801a, 0x7333298f, 0x26667342, - 0x733ab2c6, 0x265c64ef, 0x73423a04, 0x26525521, - 0x7349bf48, 0x264843d9, 0x73514292, 0x263e3117, - 0x7358c3e2, 0x26341cdb, 0x73604336, 0x262a0727, - 0x7367c090, 0x261feffa, 0x736f3bee, 0x2615d754, - 0x7376b551, 0x260bbd37, 0x737e2cb7, 0x2601a1a2, - 0x7385a222, 0x25f78497, 0x738d1590, 0x25ed6614, - 0x73948701, 0x25e3461b, 0x739bf675, 0x25d924ac, - 0x73a363ec, 0x25cf01c8, 0x73aacf65, 0x25c4dd6e, - 0x73b238e0, 0x25bab7a0, 0x73b9a05d, 0x25b0905d, - 0x73c105db, 0x25a667a7, 0x73c8695b, 0x259c3d7c, - 0x73cfcadc, 0x259211df, 0x73d72a5d, 0x2587e4cf, - 0x73de87de, 0x257db64c, 0x73e5e360, 0x25738657, - 0x73ed3ce1, 0x256954f1, 0x73f49462, 0x255f2219, - 0x73fbe9e2, 0x2554edd1, 0x74033d61, 0x254ab818, - 0x740a8edf, 0x254080ef, 0x7411de5b, 0x25364857, - 0x74192bd5, 0x252c0e4f, 0x7420774d, 0x2521d2d8, - 0x7427c0c3, 0x251795f3, 0x742f0836, 0x250d57a0, - 0x74364da6, 0x250317df, 0x743d9112, 0x24f8d6b0, - 0x7444d27b, 0x24ee9415, 0x744c11e0, 0x24e4500e, - 0x74534f41, 0x24da0a9a, 0x745a8a9d, 0x24cfc3ba, - 0x7461c3f5, 0x24c57b6f, 0x7468fb47, 0x24bb31ba, - 0x74703095, 0x24b0e699, 0x747763dd, 0x24a69a0f, - 0x747e951f, 0x249c4c1b, 0x7485c45b, 0x2491fcbe, - 0x748cf190, 0x2487abf7, 0x74941cbf, 0x247d59c8, - 0x749b45e7, 0x24730631, 0x74a26d08, 0x2468b132, - 0x74a99221, 0x245e5acc, 0x74b0b533, 0x245402ff, - 0x74b7d63c, 0x2449a9cc, 0x74bef53d, 0x243f4f32, - 0x74c61236, 0x2434f332, 0x74cd2d26, 0x242a95ce, - 0x74d4460c, 0x24203704, 0x74db5cea, 0x2415d6d5, - 0x74e271bd, 0x240b7543, 0x74e98487, 0x2401124d, - 0x74f09546, 0x23f6adf3, 0x74f7a3fb, 0x23ec4837, - 0x74feb0a5, 0x23e1e117, 0x7505bb44, 0x23d77896, - 0x750cc3d8, 0x23cd0eb3, 0x7513ca60, 0x23c2a36f, - 0x751acedd, 0x23b836ca, 0x7521d14d, 0x23adc8c4, - 0x7528d1b1, 0x23a3595e, 0x752fd008, 0x2398e898, - 0x7536cc52, 0x238e7673, 0x753dc68f, 0x238402ef, - 0x7544bebf, 0x23798e0d, 0x754bb4e1, 0x236f17cc, - 0x7552a8f4, 0x2364a02e, 0x75599afa, 0x235a2733, - 0x75608af1, 0x234facda, 0x756778d9, 0x23453125, - 0x756e64b2, 0x233ab414, 0x75754e7c, 0x233035a7, - 0x757c3636, 0x2325b5df, 0x75831be0, 0x231b34bc, - 0x7589ff7a, 0x2310b23e, 0x7590e104, 0x23062e67, - 0x7597c07d, 0x22fba936, 0x759e9de5, 0x22f122ab, - 0x75a5793c, 0x22e69ac8, 0x75ac5282, 0x22dc118c, - 0x75b329b5, 0x22d186f8, 0x75b9fed7, 0x22c6fb0c, - 0x75c0d1e7, 0x22bc6dca, 0x75c7a2e3, 0x22b1df30, - 0x75ce71ce, 0x22a74f40, 0x75d53ea5, 0x229cbdfa, - 0x75dc0968, 0x22922b5e, 0x75e2d219, 0x2287976e, - 0x75e998b5, 0x227d0228, 0x75f05d3d, 0x22726b8e, - 0x75f71fb1, 0x2267d3a0, 0x75fde011, 0x225d3a5e, - 0x76049e5b, 0x22529fca, 0x760b5a90, 0x224803e2, - 0x761214b0, 0x223d66a8, 0x7618ccba, 0x2232c81c, - 0x761f82af, 0x2228283f, 0x7626368d, 0x221d8711, - 0x762ce855, 0x2212e492, 0x76339806, 0x220840c2, - 0x763a45a0, 0x21fd9ba3, 0x7640f123, 0x21f2f534, - 0x76479a8e, 0x21e84d76, 0x764e41e2, 0x21dda46a, - 0x7654e71d, 0x21d2fa0f, 0x765b8a41, 0x21c84e67, - 0x76622b4c, 0x21bda171, 0x7668ca3e, 0x21b2f32e, - 0x766f6717, 0x21a8439e, 0x767601d7, 0x219d92c2, - 0x767c9a7e, 0x2192e09b, 0x7683310b, 0x21882d28, - 0x7689c57d, 0x217d786a, 0x769057d6, 0x2172c262, - 0x7696e814, 0x21680b0f, 0x769d7637, 0x215d5273, - 0x76a4023f, 0x2152988d, 0x76aa8c2c, 0x2147dd5f, - 0x76b113fd, 0x213d20e8, 0x76b799b3, 0x21326329, - 0x76be1d4c, 0x2127a423, 0x76c49ec9, 0x211ce3d5, - 0x76cb1e2a, 0x21122240, 0x76d19b6e, 0x21075f65, - 0x76d81695, 0x20fc9b44, 0x76de8f9e, 0x20f1d5de, - 0x76e5068a, 0x20e70f32, 0x76eb7b58, 0x20dc4742, - 0x76f1ee09, 0x20d17e0d, 0x76f85e9a, 0x20c6b395, - 0x76fecd0e, 0x20bbe7d8, 0x77053962, 0x20b11ad9, - 0x770ba398, 0x20a64c97, 0x77120bae, 0x209b7d13, - 0x771871a5, 0x2090ac4d, 0x771ed57c, 0x2085da46, - 0x77253733, 0x207b06fe, 0x772b96ca, 0x20703275, - 0x7731f440, 0x20655cac, 0x77384f95, 0x205a85a3, - 0x773ea8ca, 0x204fad5b, 0x7744ffdd, 0x2044d3d4, - 0x774b54ce, 0x2039f90f, 0x7751a79e, 0x202f1d0b, - 0x7757f84c, 0x20243fca, 0x775e46d8, 0x2019614c, - 0x77649341, 0x200e8190, 0x776add88, 0x2003a099, - 0x777125ac, 0x1ff8be65, 0x77776bac, 0x1feddaf6, - 0x777daf89, 0x1fe2f64c, 0x7783f143, 0x1fd81067, - 0x778a30d8, 0x1fcd2948, 0x77906e49, 0x1fc240ef, - 0x7796a996, 0x1fb7575c, 0x779ce2be, 0x1fac6c91, - 0x77a319c2, 0x1fa1808c, 0x77a94ea0, 0x1f969350, - 0x77af8159, 0x1f8ba4dc, 0x77b5b1ec, 0x1f80b531, - 0x77bbe05a, 0x1f75c44e, 0x77c20ca1, 0x1f6ad235, - 0x77c836c2, 0x1f5fdee6, 0x77ce5ebd, 0x1f54ea62, - 0x77d48490, 0x1f49f4a8, 0x77daa83d, 0x1f3efdb9, - 0x77e0c9c3, 0x1f340596, 0x77e6e921, 0x1f290c3f, - 0x77ed0657, 0x1f1e11b5, 0x77f32165, 0x1f1315f7, - 0x77f93a4b, 0x1f081907, 0x77ff5109, 0x1efd1ae4, - 0x7805659e, 0x1ef21b90, 0x780b780a, 0x1ee71b0a, - 0x7811884d, 0x1edc1953, 0x78179666, 0x1ed1166b, - 0x781da256, 0x1ec61254, 0x7823ac1d, 0x1ebb0d0d, - 0x7829b3b9, 0x1eb00696, 0x782fb92a, 0x1ea4fef0, - 0x7835bc71, 0x1e99f61d, 0x783bbd8e, 0x1e8eec1b, - 0x7841bc7f, 0x1e83e0eb, 0x7847b946, 0x1e78d48e, - 0x784db3e0, 0x1e6dc705, 0x7853ac4f, 0x1e62b84f, - 0x7859a292, 0x1e57a86d, 0x785f96a9, 0x1e4c9760, - 0x78658894, 0x1e418528, 0x786b7852, 0x1e3671c5, - 0x787165e3, 0x1e2b5d38, 0x78775147, 0x1e204781, - 0x787d3a7e, 0x1e1530a1, 0x78832187, 0x1e0a1898, - 0x78890663, 0x1dfeff67, 0x788ee910, 0x1df3e50d, - 0x7894c98f, 0x1de8c98c, 0x789aa7e0, 0x1dddace4, - 0x78a08402, 0x1dd28f15, 0x78a65df6, 0x1dc7701f, - 0x78ac35ba, 0x1dbc5004, 0x78b20b4f, 0x1db12ec3, - 0x78b7deb4, 0x1da60c5d, 0x78bdafea, 0x1d9ae8d2, - 0x78c37eef, 0x1d8fc424, 0x78c94bc4, 0x1d849e51, - 0x78cf1669, 0x1d79775c, 0x78d4dedd, 0x1d6e4f43, - 0x78daa520, 0x1d632608, 0x78e06932, 0x1d57fbaa, - 0x78e62b13, 0x1d4cd02c, 0x78ebeac2, 0x1d41a38c, - 0x78f1a840, 0x1d3675cb, 0x78f7638b, 0x1d2b46ea, - 0x78fd1ca4, 0x1d2016e9, 0x7902d38b, 0x1d14e5c9, - 0x7908883f, 0x1d09b389, 0x790e3ac0, 0x1cfe802b, - 0x7913eb0e, 0x1cf34baf, 0x79199929, 0x1ce81615, - 0x791f4510, 0x1cdcdf5e, 0x7924eec3, 0x1cd1a78a, - 0x792a9642, 0x1cc66e99, 0x79303b8e, 0x1cbb348d, - 0x7935dea4, 0x1caff965, 0x793b7f86, 0x1ca4bd21, - 0x79411e33, 0x1c997fc4, 0x7946baac, 0x1c8e414b, - 0x794c54ee, 0x1c8301b9, 0x7951ecfc, 0x1c77c10e, - 0x795782d3, 0x1c6c7f4a, 0x795d1675, 0x1c613c6d, - 0x7962a7e0, 0x1c55f878, 0x79683715, 0x1c4ab36b, - 0x796dc414, 0x1c3f6d47, 0x79734edc, 0x1c34260c, - 0x7978d76c, 0x1c28ddbb, 0x797e5dc6, 0x1c1d9454, - 0x7983e1e8, 0x1c1249d8, 0x798963d2, 0x1c06fe46, - 0x798ee385, 0x1bfbb1a0, 0x799460ff, 0x1bf063e6, - 0x7999dc42, 0x1be51518, 0x799f554b, 0x1bd9c537, - 0x79a4cc1c, 0x1bce7442, 0x79aa40b4, 0x1bc3223c, - 0x79afb313, 0x1bb7cf23, 0x79b52339, 0x1bac7af9, - 0x79ba9125, 0x1ba125bd, 0x79bffcd7, 0x1b95cf71, - 0x79c5664f, 0x1b8a7815, 0x79cacd8d, 0x1b7f1fa9, - 0x79d03291, 0x1b73c62d, 0x79d5955a, 0x1b686ba3, - 0x79daf5e8, 0x1b5d100a, 0x79e0543c, 0x1b51b363, - 0x79e5b054, 0x1b4655ae, 0x79eb0a31, 0x1b3af6ec, - 0x79f061d2, 0x1b2f971e, 0x79f5b737, 0x1b243643, - 0x79fb0a60, 0x1b18d45c, 0x7a005b4d, 0x1b0d716a, - 0x7a05a9fd, 0x1b020d6c, 0x7a0af671, 0x1af6a865, - 0x7a1040a8, 0x1aeb4253, 0x7a1588a2, 0x1adfdb37, - 0x7a1ace5f, 0x1ad47312, 0x7a2011de, 0x1ac909e5, - 0x7a25531f, 0x1abd9faf, 0x7a2a9223, 0x1ab23471, - 0x7a2fcee8, 0x1aa6c82b, 0x7a350970, 0x1a9b5adf, - 0x7a3a41b9, 0x1a8fec8c, 0x7a3f77c3, 0x1a847d33, - 0x7a44ab8e, 0x1a790cd4, 0x7a49dd1a, 0x1a6d9b70, - 0x7a4f0c67, 0x1a622907, 0x7a543974, 0x1a56b599, - 0x7a596442, 0x1a4b4128, 0x7a5e8cd0, 0x1a3fcbb3, - 0x7a63b31d, 0x1a34553b, 0x7a68d72b, 0x1a28ddc0, - 0x7a6df8f8, 0x1a1d6544, 0x7a731884, 0x1a11ebc5, - 0x7a7835cf, 0x1a067145, 0x7a7d50da, 0x19faf5c5, - 0x7a8269a3, 0x19ef7944, 0x7a87802a, 0x19e3fbc3, - 0x7a8c9470, 0x19d87d42, 0x7a91a674, 0x19ccfdc2, - 0x7a96b636, 0x19c17d44, 0x7a9bc3b6, 0x19b5fbc8, - 0x7aa0cef3, 0x19aa794d, 0x7aa5d7ee, 0x199ef5d6, - 0x7aaadea6, 0x19937161, 0x7aafe31b, 0x1987ebf0, - 0x7ab4e54c, 0x197c6584, 0x7ab9e53a, 0x1970de1b, - 0x7abee2e5, 0x196555b8, 0x7ac3de4c, 0x1959cc5a, - 0x7ac8d76f, 0x194e4201, 0x7acdce4d, 0x1942b6af, - 0x7ad2c2e8, 0x19372a64, 0x7ad7b53d, 0x192b9d1f, - 0x7adca54e, 0x19200ee3, 0x7ae1931a, 0x19147fae, - 0x7ae67ea1, 0x1908ef82, 0x7aeb67e3, 0x18fd5e5f, - 0x7af04edf, 0x18f1cc45, 0x7af53395, 0x18e63935, - 0x7afa1605, 0x18daa52f, 0x7afef630, 0x18cf1034, - 0x7b03d414, 0x18c37a44, 0x7b08afb2, 0x18b7e35f, - 0x7b0d8909, 0x18ac4b87, 0x7b126019, 0x18a0b2bb, - 0x7b1734e2, 0x189518fc, 0x7b1c0764, 0x18897e4a, - 0x7b20d79e, 0x187de2a7, 0x7b25a591, 0x18724611, - 0x7b2a713d, 0x1866a88a, 0x7b2f3aa0, 0x185b0a13, - 0x7b3401bb, 0x184f6aab, 0x7b38c68e, 0x1843ca53, - 0x7b3d8918, 0x1838290c, 0x7b42495a, 0x182c86d5, - 0x7b470753, 0x1820e3b0, 0x7b4bc303, 0x18153f9d, - 0x7b507c69, 0x18099a9c, 0x7b553386, 0x17fdf4ae, - 0x7b59e85a, 0x17f24dd3, 0x7b5e9ae4, 0x17e6a60c, - 0x7b634b23, 0x17dafd59, 0x7b67f919, 0x17cf53bb, - 0x7b6ca4c4, 0x17c3a931, 0x7b714e25, 0x17b7fdbd, - 0x7b75f53c, 0x17ac515f, 0x7b7a9a07, 0x17a0a417, - 0x7b7f3c87, 0x1794f5e6, 0x7b83dcbc, 0x178946cc, - 0x7b887aa6, 0x177d96ca, 0x7b8d1644, 0x1771e5e0, - 0x7b91af97, 0x1766340f, 0x7b96469d, 0x175a8157, - 0x7b9adb57, 0x174ecdb8, 0x7b9f6dc5, 0x17431933, - 0x7ba3fde7, 0x173763c9, 0x7ba88bbc, 0x172bad7a, - 0x7bad1744, 0x171ff646, 0x7bb1a080, 0x17143e2d, - 0x7bb6276e, 0x17088531, 0x7bbaac0e, 0x16fccb51, - 0x7bbf2e62, 0x16f1108f, 0x7bc3ae67, 0x16e554ea, - 0x7bc82c1f, 0x16d99864, 0x7bcca789, 0x16cddafb, - 0x7bd120a4, 0x16c21cb2, 0x7bd59771, 0x16b65d88, - 0x7bda0bf0, 0x16aa9d7e, 0x7bde7e20, 0x169edc94, - 0x7be2ee01, 0x16931acb, 0x7be75b93, 0x16875823, - 0x7bebc6d5, 0x167b949d, 0x7bf02fc9, 0x166fd039, - 0x7bf4966c, 0x16640af7, 0x7bf8fac0, 0x165844d8, - 0x7bfd5cc4, 0x164c7ddd, 0x7c01bc78, 0x1640b606, - 0x7c0619dc, 0x1634ed53, 0x7c0a74f0, 0x162923c5, - 0x7c0ecdb2, 0x161d595d, 0x7c132424, 0x16118e1a, - 0x7c177845, 0x1605c1fd, 0x7c1bca16, 0x15f9f507, - 0x7c201994, 0x15ee2738, 0x7c2466c2, 0x15e25890, - 0x7c28b19e, 0x15d68911, 0x7c2cfa28, 0x15cab8ba, - 0x7c314060, 0x15bee78c, 0x7c358446, 0x15b31587, - 0x7c39c5da, 0x15a742ac, 0x7c3e051b, 0x159b6efb, - 0x7c42420a, 0x158f9a76, 0x7c467ca6, 0x1583c51b, - 0x7c4ab4ef, 0x1577eeec, 0x7c4eeae5, 0x156c17e9, - 0x7c531e88, 0x15604013, 0x7c574fd8, 0x1554676a, - 0x7c5b7ed4, 0x15488dee, 0x7c5fab7c, 0x153cb3a0, - 0x7c63d5d1, 0x1530d881, 0x7c67fdd1, 0x1524fc90, - 0x7c6c237e, 0x15191fcf, 0x7c7046d6, 0x150d423d, - 0x7c7467d9, 0x150163dc, 0x7c788688, 0x14f584ac, - 0x7c7ca2e2, 0x14e9a4ac, 0x7c80bce7, 0x14ddc3de, - 0x7c84d496, 0x14d1e242, 0x7c88e9f1, 0x14c5ffd9, - 0x7c8cfcf6, 0x14ba1ca3, 0x7c910da5, 0x14ae38a0, - 0x7c951bff, 0x14a253d1, 0x7c992803, 0x14966e36, - 0x7c9d31b0, 0x148a87d1, 0x7ca13908, 0x147ea0a0, - 0x7ca53e09, 0x1472b8a5, 0x7ca940b3, 0x1466cfe1, - 0x7cad4107, 0x145ae653, 0x7cb13f04, 0x144efbfc, - 0x7cb53aaa, 0x144310dd, 0x7cb933f9, 0x143724f5, - 0x7cbd2af0, 0x142b3846, 0x7cc11f90, 0x141f4ad1, - 0x7cc511d9, 0x14135c94, 0x7cc901c9, 0x14076d91, - 0x7cccef62, 0x13fb7dc9, 0x7cd0daa2, 0x13ef8d3c, - 0x7cd4c38b, 0x13e39be9, 0x7cd8aa1b, 0x13d7a9d3, - 0x7cdc8e52, 0x13cbb6f8, 0x7ce07031, 0x13bfc35b, - 0x7ce44fb7, 0x13b3cefa, 0x7ce82ce4, 0x13a7d9d7, - 0x7cec07b8, 0x139be3f2, 0x7cefe032, 0x138fed4b, - 0x7cf3b653, 0x1383f5e3, 0x7cf78a1b, 0x1377fdbb, - 0x7cfb5b89, 0x136c04d2, 0x7cff2a9d, 0x13600b2a, - 0x7d02f757, 0x135410c3, 0x7d06c1b6, 0x1348159d, - 0x7d0a89bc, 0x133c19b8, 0x7d0e4f67, 0x13301d16, - 0x7d1212b7, 0x13241fb6, 0x7d15d3ad, 0x1318219a, - 0x7d199248, 0x130c22c1, 0x7d1d4e88, 0x1300232c, - 0x7d21086c, 0x12f422db, 0x7d24bff6, 0x12e821cf, - 0x7d287523, 0x12dc2009, 0x7d2c27f6, 0x12d01d89, - 0x7d2fd86c, 0x12c41a4f, 0x7d338687, 0x12b8165b, - 0x7d373245, 0x12ac11af, 0x7d3adba7, 0x12a00c4b, - 0x7d3e82ae, 0x1294062f, 0x7d422757, 0x1287ff5b, - 0x7d45c9a4, 0x127bf7d1, 0x7d496994, 0x126fef90, - 0x7d4d0728, 0x1263e699, 0x7d50a25e, 0x1257dced, - 0x7d543b37, 0x124bd28c, 0x7d57d1b3, 0x123fc776, - 0x7d5b65d2, 0x1233bbac, 0x7d5ef793, 0x1227af2e, - 0x7d6286f6, 0x121ba1fd, 0x7d6613fb, 0x120f941a, - 0x7d699ea3, 0x12038584, 0x7d6d26ec, 0x11f7763c, - 0x7d70acd7, 0x11eb6643, 0x7d743064, 0x11df5599, - 0x7d77b192, 0x11d3443f, 0x7d7b3061, 0x11c73235, - 0x7d7eacd2, 0x11bb1f7c, 0x7d8226e4, 0x11af0c13, - 0x7d859e96, 0x11a2f7fc, 0x7d8913ea, 0x1196e337, - 0x7d8c86de, 0x118acdc4, 0x7d8ff772, 0x117eb7a4, - 0x7d9365a8, 0x1172a0d7, 0x7d96d17d, 0x1166895f, - 0x7d9a3af2, 0x115a713a, 0x7d9da208, 0x114e586a, - 0x7da106bd, 0x11423ef0, 0x7da46912, 0x113624cb, - 0x7da7c907, 0x112a09fc, 0x7dab269b, 0x111dee84, - 0x7dae81cf, 0x1111d263, 0x7db1daa2, 0x1105b599, - 0x7db53113, 0x10f99827, 0x7db88524, 0x10ed7a0e, - 0x7dbbd6d4, 0x10e15b4e, 0x7dbf2622, 0x10d53be7, - 0x7dc2730f, 0x10c91bda, 0x7dc5bd9b, 0x10bcfb28, - 0x7dc905c5, 0x10b0d9d0, 0x7dcc4b8d, 0x10a4b7d3, - 0x7dcf8ef3, 0x10989532, 0x7dd2cff7, 0x108c71ee, - 0x7dd60e99, 0x10804e06, 0x7dd94ad8, 0x1074297b, - 0x7ddc84b5, 0x1068044e, 0x7ddfbc30, 0x105bde7f, - 0x7de2f148, 0x104fb80e, 0x7de623fd, 0x104390fd, - 0x7de9544f, 0x1037694b, 0x7dec823e, 0x102b40f8, - 0x7defadca, 0x101f1807, 0x7df2d6f3, 0x1012ee76, - 0x7df5fdb8, 0x1006c446, 0x7df9221a, 0xffa9979, - 0x7dfc4418, 0xfee6e0d, 0x7dff63b2, 0xfe24205, - 0x7e0280e9, 0xfd6155f, 0x7e059bbb, 0xfc9e81e, - 0x7e08b42a, 0xfbdba40, 0x7e0bca34, 0xfb18bc8, - 0x7e0eddd9, 0xfa55cb4, 0x7e11ef1b, 0xf992d06, - 0x7e14fdf7, 0xf8cfcbe, 0x7e180a6f, 0xf80cbdc, - 0x7e1b1482, 0xf749a61, 0x7e1e1c30, 0xf68684e, - 0x7e212179, 0xf5c35a3, 0x7e24245d, 0xf500260, - 0x7e2724db, 0xf43ce86, 0x7e2a22f4, 0xf379a16, - 0x7e2d1ea8, 0xf2b650f, 0x7e3017f6, 0xf1f2f73, - 0x7e330ede, 0xf12f941, 0x7e360360, 0xf06c27a, - 0x7e38f57c, 0xefa8b20, 0x7e3be532, 0xeee5331, - 0x7e3ed282, 0xee21aaf, 0x7e41bd6c, 0xed5e19a, - 0x7e44a5ef, 0xec9a7f3, 0x7e478c0b, 0xebd6db9, - 0x7e4a6fc1, 0xeb132ef, 0x7e4d5110, 0xea4f793, - 0x7e502ff9, 0xe98bba7, 0x7e530c7a, 0xe8c7f2a, - 0x7e55e694, 0xe80421e, 0x7e58be47, 0xe740483, - 0x7e5b9392, 0xe67c65a, 0x7e5e6676, 0xe5b87a2, - 0x7e6136f3, 0xe4f485c, 0x7e640507, 0xe430889, - 0x7e66d0b4, 0xe36c82a, 0x7e6999fa, 0xe2a873e, - 0x7e6c60d7, 0xe1e45c6, 0x7e6f254c, 0xe1203c3, - 0x7e71e759, 0xe05c135, 0x7e74a6fd, 0xdf97e1d, - 0x7e77643a, 0xded3a7b, 0x7e7a1f0d, 0xde0f64f, - 0x7e7cd778, 0xdd4b19a, 0x7e7f8d7b, 0xdc86c5d, - 0x7e824114, 0xdbc2698, 0x7e84f245, 0xdafe04b, - 0x7e87a10c, 0xda39978, 0x7e8a4d6a, 0xd97521d, - 0x7e8cf75f, 0xd8b0a3d, 0x7e8f9eeb, 0xd7ec1d6, - 0x7e92440d, 0xd7278eb, 0x7e94e6c6, 0xd662f7b, - 0x7e978715, 0xd59e586, 0x7e9a24fb, 0xd4d9b0e, - 0x7e9cc076, 0xd415013, 0x7e9f5988, 0xd350495, - 0x7ea1f02f, 0xd28b894, 0x7ea4846c, 0xd1c6c11, - 0x7ea7163f, 0xd101f0e, 0x7ea9a5a8, 0xd03d189, - 0x7eac32a6, 0xcf78383, 0x7eaebd3a, 0xceb34fe, - 0x7eb14563, 0xcdee5f9, 0x7eb3cb21, 0xcd29676, - 0x7eb64e75, 0xcc64673, 0x7eb8cf5d, 0xcb9f5f3, - 0x7ebb4ddb, 0xcada4f5, 0x7ebdc9ed, 0xca1537a, - 0x7ec04394, 0xc950182, 0x7ec2bad0, 0xc88af0e, - 0x7ec52fa0, 0xc7c5c1e, 0x7ec7a205, 0xc7008b3, - 0x7eca11fe, 0xc63b4ce, 0x7ecc7f8b, 0xc57606e, - 0x7eceeaad, 0xc4b0b94, 0x7ed15363, 0xc3eb641, - 0x7ed3b9ad, 0xc326075, 0x7ed61d8a, 0xc260a31, - 0x7ed87efc, 0xc19b374, 0x7edade01, 0xc0d5c41, - 0x7edd3a9a, 0xc010496, 0x7edf94c7, 0xbf4ac75, - 0x7ee1ec87, 0xbe853de, 0x7ee441da, 0xbdbfad1, - 0x7ee694c1, 0xbcfa150, 0x7ee8e53a, 0xbc34759, - 0x7eeb3347, 0xbb6ecef, 0x7eed7ee7, 0xbaa9211, - 0x7eefc81a, 0xb9e36c0, 0x7ef20ee0, 0xb91dafc, - 0x7ef45338, 0xb857ec7, 0x7ef69523, 0xb79221f, - 0x7ef8d4a1, 0xb6cc506, 0x7efb11b1, 0xb60677c, - 0x7efd4c54, 0xb540982, 0x7eff8489, 0xb47ab19, - 0x7f01ba50, 0xb3b4c40, 0x7f03eda9, 0xb2eecf8, - 0x7f061e95, 0xb228d42, 0x7f084d12, 0xb162d1d, - 0x7f0a7921, 0xb09cc8c, 0x7f0ca2c2, 0xafd6b8d, - 0x7f0ec9f5, 0xaf10a22, 0x7f10eeb9, 0xae4a84b, - 0x7f13110f, 0xad84609, 0x7f1530f7, 0xacbe35b, - 0x7f174e70, 0xabf8043, 0x7f19697a, 0xab31cc1, - 0x7f1b8215, 0xaa6b8d5, 0x7f1d9842, 0xa9a5480, - 0x7f1fabff, 0xa8defc3, 0x7f21bd4e, 0xa818a9d, - 0x7f23cc2e, 0xa752510, 0x7f25d89e, 0xa68bf1b, - 0x7f27e29f, 0xa5c58c0, 0x7f29ea31, 0xa4ff1fe, - 0x7f2bef53, 0xa438ad7, 0x7f2df206, 0xa37234a, - 0x7f2ff24a, 0xa2abb59, 0x7f31f01d, 0xa1e5303, - 0x7f33eb81, 0xa11ea49, 0x7f35e476, 0xa05812c, - 0x7f37dafa, 0x9f917ac, 0x7f39cf0e, 0x9ecadc9, - 0x7f3bc0b3, 0x9e04385, 0x7f3dafe7, 0x9d3d8df, - 0x7f3f9cab, 0x9c76dd8, 0x7f4186ff, 0x9bb0271, - 0x7f436ee3, 0x9ae96aa, 0x7f455456, 0x9a22a83, - 0x7f473759, 0x995bdfd, 0x7f4917eb, 0x9895118, - 0x7f4af60d, 0x97ce3d5, 0x7f4cd1be, 0x9707635, - 0x7f4eaafe, 0x9640837, 0x7f5081cd, 0x95799dd, - 0x7f52562c, 0x94b2b27, 0x7f54281a, 0x93ebc14, - 0x7f55f796, 0x9324ca7, 0x7f57c4a2, 0x925dcdf, - 0x7f598f3c, 0x9196cbc, 0x7f5b5765, 0x90cfc40, - 0x7f5d1d1d, 0x9008b6a, 0x7f5ee063, 0x8f41a3c, - 0x7f60a138, 0x8e7a8b5, 0x7f625f9b, 0x8db36d6, - 0x7f641b8d, 0x8cec4a0, 0x7f65d50d, 0x8c25213, - 0x7f678c1c, 0x8b5df30, 0x7f6940b8, 0x8a96bf6, - 0x7f6af2e3, 0x89cf867, 0x7f6ca29c, 0x8908483, - 0x7f6e4fe3, 0x884104b, 0x7f6ffab8, 0x8779bbe, - 0x7f71a31b, 0x86b26de, 0x7f73490b, 0x85eb1ab, - 0x7f74ec8a, 0x8523c25, 0x7f768d96, 0x845c64d, - 0x7f782c30, 0x8395024, 0x7f79c857, 0x82cd9a9, - 0x7f7b620c, 0x82062de, 0x7f7cf94e, 0x813ebc2, - 0x7f7e8e1e, 0x8077457, 0x7f80207b, 0x7fafc9c, - 0x7f81b065, 0x7ee8493, 0x7f833ddd, 0x7e20c3b, - 0x7f84c8e2, 0x7d59396, 0x7f865174, 0x7c91aa3, - 0x7f87d792, 0x7bca163, 0x7f895b3e, 0x7b027d7, - 0x7f8adc77, 0x7a3adff, 0x7f8c5b3d, 0x79733dc, - 0x7f8dd78f, 0x78ab96e, 0x7f8f516e, 0x77e3eb5, - 0x7f90c8da, 0x771c3b3, 0x7f923dd2, 0x7654867, - 0x7f93b058, 0x758ccd2, 0x7f952069, 0x74c50f4, - 0x7f968e07, 0x73fd4cf, 0x7f97f932, 0x7335862, - 0x7f9961e8, 0x726dbae, 0x7f9ac82c, 0x71a5eb3, - 0x7f9c2bfb, 0x70de172, 0x7f9d8d56, 0x70163eb, - 0x7f9eec3e, 0x6f4e620, 0x7fa048b2, 0x6e86810, - 0x7fa1a2b2, 0x6dbe9bb, 0x7fa2fa3d, 0x6cf6b23, - 0x7fa44f55, 0x6c2ec48, 0x7fa5a1f9, 0x6b66d29, - 0x7fa6f228, 0x6a9edc9, 0x7fa83fe3, 0x69d6e27, - 0x7fa98b2a, 0x690ee44, 0x7faad3fd, 0x6846e1f, - 0x7fac1a5b, 0x677edbb, 0x7fad5e45, 0x66b6d16, - 0x7fae9fbb, 0x65eec33, 0x7fafdebb, 0x6526b10, - 0x7fb11b48, 0x645e9af, 0x7fb2555f, 0x6396810, - 0x7fb38d02, 0x62ce634, 0x7fb4c231, 0x620641a, - 0x7fb5f4ea, 0x613e1c5, 0x7fb7252f, 0x6075f33, - 0x7fb852ff, 0x5fadc66, 0x7fb97e5a, 0x5ee595d, - 0x7fbaa740, 0x5e1d61b, 0x7fbbcdb1, 0x5d5529e, - 0x7fbcf1ad, 0x5c8cee7, 0x7fbe1334, 0x5bc4af8, - 0x7fbf3246, 0x5afc6d0, 0x7fc04ee3, 0x5a3426f, - 0x7fc1690a, 0x596bdd7, 0x7fc280bc, 0x58a3908, - 0x7fc395f9, 0x57db403, 0x7fc4a8c1, 0x5712ec7, - 0x7fc5b913, 0x564a955, 0x7fc6c6f0, 0x55823ae, - 0x7fc7d258, 0x54b9dd3, 0x7fc8db4a, 0x53f17c3, - 0x7fc9e1c6, 0x532917f, 0x7fcae5cd, 0x5260b08, - 0x7fcbe75e, 0x519845e, 0x7fcce67a, 0x50cfd82, - 0x7fcde320, 0x5007674, 0x7fcedd50, 0x4f3ef35, - 0x7fcfd50b, 0x4e767c5, 0x7fd0ca4f, 0x4dae024, - 0x7fd1bd1e, 0x4ce5854, 0x7fd2ad77, 0x4c1d054, - 0x7fd39b5a, 0x4b54825, 0x7fd486c7, 0x4a8bfc7, - 0x7fd56fbe, 0x49c373c, 0x7fd6563f, 0x48fae83, - 0x7fd73a4a, 0x483259d, 0x7fd81bdf, 0x4769c8b, - 0x7fd8fafe, 0x46a134c, 0x7fd9d7a7, 0x45d89e2, - 0x7fdab1d9, 0x451004d, 0x7fdb8996, 0x444768d, - 0x7fdc5edc, 0x437eca4, 0x7fdd31ac, 0x42b6290, - 0x7fde0205, 0x41ed854, 0x7fdecfe8, 0x4124dee, - 0x7fdf9b55, 0x405c361, 0x7fe0644b, 0x3f938ac, - 0x7fe12acb, 0x3ecadcf, 0x7fe1eed5, 0x3e022cc, - 0x7fe2b067, 0x3d397a3, 0x7fe36f84, 0x3c70c54, - 0x7fe42c2a, 0x3ba80df, 0x7fe4e659, 0x3adf546, - 0x7fe59e12, 0x3a16988, 0x7fe65354, 0x394dda7, - 0x7fe7061f, 0x38851a2, 0x7fe7b674, 0x37bc57b, - 0x7fe86452, 0x36f3931, 0x7fe90fb9, 0x362acc5, - 0x7fe9b8a9, 0x3562038, 0x7fea5f23, 0x3499389, - 0x7feb0326, 0x33d06bb, 0x7feba4b2, 0x33079cc, - 0x7fec43c7, 0x323ecbe, 0x7fece065, 0x3175f91, - 0x7fed7a8c, 0x30ad245, 0x7fee123d, 0x2fe44dc, - 0x7feea776, 0x2f1b755, 0x7fef3a39, 0x2e529b0, - 0x7fefca84, 0x2d89bf0, 0x7ff05858, 0x2cc0e13, - 0x7ff0e3b6, 0x2bf801a, 0x7ff16c9c, 0x2b2f207, - 0x7ff1f30b, 0x2a663d8, 0x7ff27703, 0x299d590, - 0x7ff2f884, 0x28d472e, 0x7ff3778e, 0x280b8b3, - 0x7ff3f420, 0x2742a1f, 0x7ff46e3c, 0x2679b73, - 0x7ff4e5e0, 0x25b0caf, 0x7ff55b0d, 0x24e7dd4, - 0x7ff5cdc3, 0x241eee2, 0x7ff63e01, 0x2355fd9, - 0x7ff6abc8, 0x228d0bb, 0x7ff71718, 0x21c4188, - 0x7ff77ff1, 0x20fb240, 0x7ff7e652, 0x20322e3, - 0x7ff84a3c, 0x1f69373, 0x7ff8abae, 0x1ea03ef, - 0x7ff90aaa, 0x1dd7459, 0x7ff9672d, 0x1d0e4b0, - 0x7ff9c13a, 0x1c454f5, 0x7ffa18cf, 0x1b7c528, - 0x7ffa6dec, 0x1ab354b, 0x7ffac092, 0x19ea55d, - 0x7ffb10c1, 0x192155f, 0x7ffb5e78, 0x1858552, - 0x7ffba9b8, 0x178f536, 0x7ffbf280, 0x16c650b, - 0x7ffc38d1, 0x15fd4d2, 0x7ffc7caa, 0x153448c, - 0x7ffcbe0c, 0x146b438, 0x7ffcfcf6, 0x13a23d8, - 0x7ffd3969, 0x12d936c, 0x7ffd7364, 0x12102f4, - 0x7ffdaae7, 0x1147271, 0x7ffddff3, 0x107e1e3, - 0x7ffe1288, 0xfb514b, 0x7ffe42a4, 0xeec0aa, - 0x7ffe704a, 0xe22fff, 0x7ffe9b77, 0xd59f4c, - 0x7ffec42d, 0xc90e90, 0x7ffeea6c, 0xbc7dcc, - 0x7fff0e32, 0xafed02, 0x7fff2f82, 0xa35c30, - 0x7fff4e59, 0x96cb58, 0x7fff6ab9, 0x8a3a7b, - 0x7fff84a1, 0x7da998, 0x7fff9c12, 0x7118b0, - 0x7fffb10b, 0x6487c4, 0x7fffc38c, 0x57f6d4, - 0x7fffd396, 0x4b65e1, 0x7fffe128, 0x3ed4ea, - 0x7fffec43, 0x3243f1, 0x7ffff4e6, 0x25b2f7, - 0x7ffffb11, 0x1921fb, 0x7ffffec4, 0xc90fe, - 0x7fffffff, 0x0, 0x7ffffec4, 0xfff36f02, - 0x7ffffb11, 0xffe6de05, 0x7ffff4e6, 0xffda4d09, - 0x7fffec43, 0xffcdbc0f, 0x7fffe128, 0xffc12b16, - 0x7fffd396, 0xffb49a1f, 0x7fffc38c, 0xffa8092c, - 0x7fffb10b, 0xff9b783c, 0x7fff9c12, 0xff8ee750, - 0x7fff84a1, 0xff825668, 0x7fff6ab9, 0xff75c585, - 0x7fff4e59, 0xff6934a8, 0x7fff2f82, 0xff5ca3d0, - 0x7fff0e32, 0xff5012fe, 0x7ffeea6c, 0xff438234, - 0x7ffec42d, 0xff36f170, 0x7ffe9b77, 0xff2a60b4, - 0x7ffe704a, 0xff1dd001, 0x7ffe42a4, 0xff113f56, - 0x7ffe1288, 0xff04aeb5, 0x7ffddff3, 0xfef81e1d, - 0x7ffdaae7, 0xfeeb8d8f, 0x7ffd7364, 0xfedefd0c, - 0x7ffd3969, 0xfed26c94, 0x7ffcfcf6, 0xfec5dc28, - 0x7ffcbe0c, 0xfeb94bc8, 0x7ffc7caa, 0xfeacbb74, - 0x7ffc38d1, 0xfea02b2e, 0x7ffbf280, 0xfe939af5, - 0x7ffba9b8, 0xfe870aca, 0x7ffb5e78, 0xfe7a7aae, - 0x7ffb10c1, 0xfe6deaa1, 0x7ffac092, 0xfe615aa3, - 0x7ffa6dec, 0xfe54cab5, 0x7ffa18cf, 0xfe483ad8, - 0x7ff9c13a, 0xfe3bab0b, 0x7ff9672d, 0xfe2f1b50, - 0x7ff90aaa, 0xfe228ba7, 0x7ff8abae, 0xfe15fc11, - 0x7ff84a3c, 0xfe096c8d, 0x7ff7e652, 0xfdfcdd1d, - 0x7ff77ff1, 0xfdf04dc0, 0x7ff71718, 0xfde3be78, - 0x7ff6abc8, 0xfdd72f45, 0x7ff63e01, 0xfdcaa027, - 0x7ff5cdc3, 0xfdbe111e, 0x7ff55b0d, 0xfdb1822c, - 0x7ff4e5e0, 0xfda4f351, 0x7ff46e3c, 0xfd98648d, - 0x7ff3f420, 0xfd8bd5e1, 0x7ff3778e, 0xfd7f474d, - 0x7ff2f884, 0xfd72b8d2, 0x7ff27703, 0xfd662a70, - 0x7ff1f30b, 0xfd599c28, 0x7ff16c9c, 0xfd4d0df9, - 0x7ff0e3b6, 0xfd407fe6, 0x7ff05858, 0xfd33f1ed, - 0x7fefca84, 0xfd276410, 0x7fef3a39, 0xfd1ad650, - 0x7feea776, 0xfd0e48ab, 0x7fee123d, 0xfd01bb24, - 0x7fed7a8c, 0xfcf52dbb, 0x7fece065, 0xfce8a06f, - 0x7fec43c7, 0xfcdc1342, 0x7feba4b2, 0xfccf8634, - 0x7feb0326, 0xfcc2f945, 0x7fea5f23, 0xfcb66c77, - 0x7fe9b8a9, 0xfca9dfc8, 0x7fe90fb9, 0xfc9d533b, - 0x7fe86452, 0xfc90c6cf, 0x7fe7b674, 0xfc843a85, - 0x7fe7061f, 0xfc77ae5e, 0x7fe65354, 0xfc6b2259, - 0x7fe59e12, 0xfc5e9678, 0x7fe4e659, 0xfc520aba, - 0x7fe42c2a, 0xfc457f21, 0x7fe36f84, 0xfc38f3ac, - 0x7fe2b067, 0xfc2c685d, 0x7fe1eed5, 0xfc1fdd34, - 0x7fe12acb, 0xfc135231, 0x7fe0644b, 0xfc06c754, - 0x7fdf9b55, 0xfbfa3c9f, 0x7fdecfe8, 0xfbedb212, - 0x7fde0205, 0xfbe127ac, 0x7fdd31ac, 0xfbd49d70, - 0x7fdc5edc, 0xfbc8135c, 0x7fdb8996, 0xfbbb8973, - 0x7fdab1d9, 0xfbaeffb3, 0x7fd9d7a7, 0xfba2761e, - 0x7fd8fafe, 0xfb95ecb4, 0x7fd81bdf, 0xfb896375, - 0x7fd73a4a, 0xfb7cda63, 0x7fd6563f, 0xfb70517d, - 0x7fd56fbe, 0xfb63c8c4, 0x7fd486c7, 0xfb574039, - 0x7fd39b5a, 0xfb4ab7db, 0x7fd2ad77, 0xfb3e2fac, - 0x7fd1bd1e, 0xfb31a7ac, 0x7fd0ca4f, 0xfb251fdc, - 0x7fcfd50b, 0xfb18983b, 0x7fcedd50, 0xfb0c10cb, - 0x7fcde320, 0xfaff898c, 0x7fcce67a, 0xfaf3027e, - 0x7fcbe75e, 0xfae67ba2, 0x7fcae5cd, 0xfad9f4f8, - 0x7fc9e1c6, 0xfacd6e81, 0x7fc8db4a, 0xfac0e83d, - 0x7fc7d258, 0xfab4622d, 0x7fc6c6f0, 0xfaa7dc52, - 0x7fc5b913, 0xfa9b56ab, 0x7fc4a8c1, 0xfa8ed139, - 0x7fc395f9, 0xfa824bfd, 0x7fc280bc, 0xfa75c6f8, - 0x7fc1690a, 0xfa694229, 0x7fc04ee3, 0xfa5cbd91, - 0x7fbf3246, 0xfa503930, 0x7fbe1334, 0xfa43b508, - 0x7fbcf1ad, 0xfa373119, 0x7fbbcdb1, 0xfa2aad62, - 0x7fbaa740, 0xfa1e29e5, 0x7fb97e5a, 0xfa11a6a3, - 0x7fb852ff, 0xfa05239a, 0x7fb7252f, 0xf9f8a0cd, - 0x7fb5f4ea, 0xf9ec1e3b, 0x7fb4c231, 0xf9df9be6, - 0x7fb38d02, 0xf9d319cc, 0x7fb2555f, 0xf9c697f0, - 0x7fb11b48, 0xf9ba1651, 0x7fafdebb, 0xf9ad94f0, - 0x7fae9fbb, 0xf9a113cd, 0x7fad5e45, 0xf99492ea, - 0x7fac1a5b, 0xf9881245, 0x7faad3fd, 0xf97b91e1, - 0x7fa98b2a, 0xf96f11bc, 0x7fa83fe3, 0xf96291d9, - 0x7fa6f228, 0xf9561237, 0x7fa5a1f9, 0xf94992d7, - 0x7fa44f55, 0xf93d13b8, 0x7fa2fa3d, 0xf93094dd, - 0x7fa1a2b2, 0xf9241645, 0x7fa048b2, 0xf91797f0, - 0x7f9eec3e, 0xf90b19e0, 0x7f9d8d56, 0xf8fe9c15, - 0x7f9c2bfb, 0xf8f21e8e, 0x7f9ac82c, 0xf8e5a14d, - 0x7f9961e8, 0xf8d92452, 0x7f97f932, 0xf8cca79e, - 0x7f968e07, 0xf8c02b31, 0x7f952069, 0xf8b3af0c, - 0x7f93b058, 0xf8a7332e, 0x7f923dd2, 0xf89ab799, - 0x7f90c8da, 0xf88e3c4d, 0x7f8f516e, 0xf881c14b, - 0x7f8dd78f, 0xf8754692, 0x7f8c5b3d, 0xf868cc24, - 0x7f8adc77, 0xf85c5201, 0x7f895b3e, 0xf84fd829, - 0x7f87d792, 0xf8435e9d, 0x7f865174, 0xf836e55d, - 0x7f84c8e2, 0xf82a6c6a, 0x7f833ddd, 0xf81df3c5, - 0x7f81b065, 0xf8117b6d, 0x7f80207b, 0xf8050364, - 0x7f7e8e1e, 0xf7f88ba9, 0x7f7cf94e, 0xf7ec143e, - 0x7f7b620c, 0xf7df9d22, 0x7f79c857, 0xf7d32657, - 0x7f782c30, 0xf7c6afdc, 0x7f768d96, 0xf7ba39b3, - 0x7f74ec8a, 0xf7adc3db, 0x7f73490b, 0xf7a14e55, - 0x7f71a31b, 0xf794d922, 0x7f6ffab8, 0xf7886442, - 0x7f6e4fe3, 0xf77befb5, 0x7f6ca29c, 0xf76f7b7d, - 0x7f6af2e3, 0xf7630799, 0x7f6940b8, 0xf756940a, - 0x7f678c1c, 0xf74a20d0, 0x7f65d50d, 0xf73daded, - 0x7f641b8d, 0xf7313b60, 0x7f625f9b, 0xf724c92a, - 0x7f60a138, 0xf718574b, 0x7f5ee063, 0xf70be5c4, - 0x7f5d1d1d, 0xf6ff7496, 0x7f5b5765, 0xf6f303c0, - 0x7f598f3c, 0xf6e69344, 0x7f57c4a2, 0xf6da2321, - 0x7f55f796, 0xf6cdb359, 0x7f54281a, 0xf6c143ec, - 0x7f52562c, 0xf6b4d4d9, 0x7f5081cd, 0xf6a86623, - 0x7f4eaafe, 0xf69bf7c9, 0x7f4cd1be, 0xf68f89cb, - 0x7f4af60d, 0xf6831c2b, 0x7f4917eb, 0xf676aee8, - 0x7f473759, 0xf66a4203, 0x7f455456, 0xf65dd57d, - 0x7f436ee3, 0xf6516956, 0x7f4186ff, 0xf644fd8f, - 0x7f3f9cab, 0xf6389228, 0x7f3dafe7, 0xf62c2721, - 0x7f3bc0b3, 0xf61fbc7b, 0x7f39cf0e, 0xf6135237, - 0x7f37dafa, 0xf606e854, 0x7f35e476, 0xf5fa7ed4, - 0x7f33eb81, 0xf5ee15b7, 0x7f31f01d, 0xf5e1acfd, - 0x7f2ff24a, 0xf5d544a7, 0x7f2df206, 0xf5c8dcb6, - 0x7f2bef53, 0xf5bc7529, 0x7f29ea31, 0xf5b00e02, - 0x7f27e29f, 0xf5a3a740, 0x7f25d89e, 0xf59740e5, - 0x7f23cc2e, 0xf58adaf0, 0x7f21bd4e, 0xf57e7563, - 0x7f1fabff, 0xf572103d, 0x7f1d9842, 0xf565ab80, - 0x7f1b8215, 0xf559472b, 0x7f19697a, 0xf54ce33f, - 0x7f174e70, 0xf5407fbd, 0x7f1530f7, 0xf5341ca5, - 0x7f13110f, 0xf527b9f7, 0x7f10eeb9, 0xf51b57b5, - 0x7f0ec9f5, 0xf50ef5de, 0x7f0ca2c2, 0xf5029473, - 0x7f0a7921, 0xf4f63374, 0x7f084d12, 0xf4e9d2e3, - 0x7f061e95, 0xf4dd72be, 0x7f03eda9, 0xf4d11308, - 0x7f01ba50, 0xf4c4b3c0, 0x7eff8489, 0xf4b854e7, - 0x7efd4c54, 0xf4abf67e, 0x7efb11b1, 0xf49f9884, - 0x7ef8d4a1, 0xf4933afa, 0x7ef69523, 0xf486dde1, - 0x7ef45338, 0xf47a8139, 0x7ef20ee0, 0xf46e2504, - 0x7eefc81a, 0xf461c940, 0x7eed7ee7, 0xf4556def, - 0x7eeb3347, 0xf4491311, 0x7ee8e53a, 0xf43cb8a7, - 0x7ee694c1, 0xf4305eb0, 0x7ee441da, 0xf424052f, - 0x7ee1ec87, 0xf417ac22, 0x7edf94c7, 0xf40b538b, - 0x7edd3a9a, 0xf3fefb6a, 0x7edade01, 0xf3f2a3bf, - 0x7ed87efc, 0xf3e64c8c, 0x7ed61d8a, 0xf3d9f5cf, - 0x7ed3b9ad, 0xf3cd9f8b, 0x7ed15363, 0xf3c149bf, - 0x7eceeaad, 0xf3b4f46c, 0x7ecc7f8b, 0xf3a89f92, - 0x7eca11fe, 0xf39c4b32, 0x7ec7a205, 0xf38ff74d, - 0x7ec52fa0, 0xf383a3e2, 0x7ec2bad0, 0xf37750f2, - 0x7ec04394, 0xf36afe7e, 0x7ebdc9ed, 0xf35eac86, - 0x7ebb4ddb, 0xf3525b0b, 0x7eb8cf5d, 0xf3460a0d, - 0x7eb64e75, 0xf339b98d, 0x7eb3cb21, 0xf32d698a, - 0x7eb14563, 0xf3211a07, 0x7eaebd3a, 0xf314cb02, - 0x7eac32a6, 0xf3087c7d, 0x7ea9a5a8, 0xf2fc2e77, - 0x7ea7163f, 0xf2efe0f2, 0x7ea4846c, 0xf2e393ef, - 0x7ea1f02f, 0xf2d7476c, 0x7e9f5988, 0xf2cafb6b, - 0x7e9cc076, 0xf2beafed, 0x7e9a24fb, 0xf2b264f2, - 0x7e978715, 0xf2a61a7a, 0x7e94e6c6, 0xf299d085, - 0x7e92440d, 0xf28d8715, 0x7e8f9eeb, 0xf2813e2a, - 0x7e8cf75f, 0xf274f5c3, 0x7e8a4d6a, 0xf268ade3, - 0x7e87a10c, 0xf25c6688, 0x7e84f245, 0xf2501fb5, - 0x7e824114, 0xf243d968, 0x7e7f8d7b, 0xf23793a3, - 0x7e7cd778, 0xf22b4e66, 0x7e7a1f0d, 0xf21f09b1, - 0x7e77643a, 0xf212c585, 0x7e74a6fd, 0xf20681e3, - 0x7e71e759, 0xf1fa3ecb, 0x7e6f254c, 0xf1edfc3d, - 0x7e6c60d7, 0xf1e1ba3a, 0x7e6999fa, 0xf1d578c2, - 0x7e66d0b4, 0xf1c937d6, 0x7e640507, 0xf1bcf777, - 0x7e6136f3, 0xf1b0b7a4, 0x7e5e6676, 0xf1a4785e, - 0x7e5b9392, 0xf19839a6, 0x7e58be47, 0xf18bfb7d, - 0x7e55e694, 0xf17fbde2, 0x7e530c7a, 0xf17380d6, - 0x7e502ff9, 0xf1674459, 0x7e4d5110, 0xf15b086d, - 0x7e4a6fc1, 0xf14ecd11, 0x7e478c0b, 0xf1429247, - 0x7e44a5ef, 0xf136580d, 0x7e41bd6c, 0xf12a1e66, - 0x7e3ed282, 0xf11de551, 0x7e3be532, 0xf111accf, - 0x7e38f57c, 0xf10574e0, 0x7e360360, 0xf0f93d86, - 0x7e330ede, 0xf0ed06bf, 0x7e3017f6, 0xf0e0d08d, - 0x7e2d1ea8, 0xf0d49af1, 0x7e2a22f4, 0xf0c865ea, - 0x7e2724db, 0xf0bc317a, 0x7e24245d, 0xf0affda0, - 0x7e212179, 0xf0a3ca5d, 0x7e1e1c30, 0xf09797b2, - 0x7e1b1482, 0xf08b659f, 0x7e180a6f, 0xf07f3424, - 0x7e14fdf7, 0xf0730342, 0x7e11ef1b, 0xf066d2fa, - 0x7e0eddd9, 0xf05aa34c, 0x7e0bca34, 0xf04e7438, - 0x7e08b42a, 0xf04245c0, 0x7e059bbb, 0xf03617e2, - 0x7e0280e9, 0xf029eaa1, 0x7dff63b2, 0xf01dbdfb, - 0x7dfc4418, 0xf01191f3, 0x7df9221a, 0xf0056687, - 0x7df5fdb8, 0xeff93bba, 0x7df2d6f3, 0xefed118a, - 0x7defadca, 0xefe0e7f9, 0x7dec823e, 0xefd4bf08, - 0x7de9544f, 0xefc896b5, 0x7de623fd, 0xefbc6f03, - 0x7de2f148, 0xefb047f2, 0x7ddfbc30, 0xefa42181, - 0x7ddc84b5, 0xef97fbb2, 0x7dd94ad8, 0xef8bd685, - 0x7dd60e99, 0xef7fb1fa, 0x7dd2cff7, 0xef738e12, - 0x7dcf8ef3, 0xef676ace, 0x7dcc4b8d, 0xef5b482d, - 0x7dc905c5, 0xef4f2630, 0x7dc5bd9b, 0xef4304d8, - 0x7dc2730f, 0xef36e426, 0x7dbf2622, 0xef2ac419, - 0x7dbbd6d4, 0xef1ea4b2, 0x7db88524, 0xef1285f2, - 0x7db53113, 0xef0667d9, 0x7db1daa2, 0xeefa4a67, - 0x7dae81cf, 0xeeee2d9d, 0x7dab269b, 0xeee2117c, - 0x7da7c907, 0xeed5f604, 0x7da46912, 0xeec9db35, - 0x7da106bd, 0xeebdc110, 0x7d9da208, 0xeeb1a796, - 0x7d9a3af2, 0xeea58ec6, 0x7d96d17d, 0xee9976a1, - 0x7d9365a8, 0xee8d5f29, 0x7d8ff772, 0xee81485c, - 0x7d8c86de, 0xee75323c, 0x7d8913ea, 0xee691cc9, - 0x7d859e96, 0xee5d0804, 0x7d8226e4, 0xee50f3ed, - 0x7d7eacd2, 0xee44e084, 0x7d7b3061, 0xee38cdcb, - 0x7d77b192, 0xee2cbbc1, 0x7d743064, 0xee20aa67, - 0x7d70acd7, 0xee1499bd, 0x7d6d26ec, 0xee0889c4, - 0x7d699ea3, 0xedfc7a7c, 0x7d6613fb, 0xedf06be6, - 0x7d6286f6, 0xede45e03, 0x7d5ef793, 0xedd850d2, - 0x7d5b65d2, 0xedcc4454, 0x7d57d1b3, 0xedc0388a, - 0x7d543b37, 0xedb42d74, 0x7d50a25e, 0xeda82313, - 0x7d4d0728, 0xed9c1967, 0x7d496994, 0xed901070, - 0x7d45c9a4, 0xed84082f, 0x7d422757, 0xed7800a5, - 0x7d3e82ae, 0xed6bf9d1, 0x7d3adba7, 0xed5ff3b5, - 0x7d373245, 0xed53ee51, 0x7d338687, 0xed47e9a5, - 0x7d2fd86c, 0xed3be5b1, 0x7d2c27f6, 0xed2fe277, - 0x7d287523, 0xed23dff7, 0x7d24bff6, 0xed17de31, - 0x7d21086c, 0xed0bdd25, 0x7d1d4e88, 0xecffdcd4, - 0x7d199248, 0xecf3dd3f, 0x7d15d3ad, 0xece7de66, - 0x7d1212b7, 0xecdbe04a, 0x7d0e4f67, 0xeccfe2ea, - 0x7d0a89bc, 0xecc3e648, 0x7d06c1b6, 0xecb7ea63, - 0x7d02f757, 0xecabef3d, 0x7cff2a9d, 0xec9ff4d6, - 0x7cfb5b89, 0xec93fb2e, 0x7cf78a1b, 0xec880245, - 0x7cf3b653, 0xec7c0a1d, 0x7cefe032, 0xec7012b5, - 0x7cec07b8, 0xec641c0e, 0x7ce82ce4, 0xec582629, - 0x7ce44fb7, 0xec4c3106, 0x7ce07031, 0xec403ca5, - 0x7cdc8e52, 0xec344908, 0x7cd8aa1b, 0xec28562d, - 0x7cd4c38b, 0xec1c6417, 0x7cd0daa2, 0xec1072c4, - 0x7cccef62, 0xec048237, 0x7cc901c9, 0xebf8926f, - 0x7cc511d9, 0xebeca36c, 0x7cc11f90, 0xebe0b52f, - 0x7cbd2af0, 0xebd4c7ba, 0x7cb933f9, 0xebc8db0b, - 0x7cb53aaa, 0xebbcef23, 0x7cb13f04, 0xebb10404, - 0x7cad4107, 0xeba519ad, 0x7ca940b3, 0xeb99301f, - 0x7ca53e09, 0xeb8d475b, 0x7ca13908, 0xeb815f60, - 0x7c9d31b0, 0xeb75782f, 0x7c992803, 0xeb6991ca, - 0x7c951bff, 0xeb5dac2f, 0x7c910da5, 0xeb51c760, - 0x7c8cfcf6, 0xeb45e35d, 0x7c88e9f1, 0xeb3a0027, - 0x7c84d496, 0xeb2e1dbe, 0x7c80bce7, 0xeb223c22, - 0x7c7ca2e2, 0xeb165b54, 0x7c788688, 0xeb0a7b54, - 0x7c7467d9, 0xeafe9c24, 0x7c7046d6, 0xeaf2bdc3, - 0x7c6c237e, 0xeae6e031, 0x7c67fdd1, 0xeadb0370, - 0x7c63d5d1, 0xeacf277f, 0x7c5fab7c, 0xeac34c60, - 0x7c5b7ed4, 0xeab77212, 0x7c574fd8, 0xeaab9896, - 0x7c531e88, 0xea9fbfed, 0x7c4eeae5, 0xea93e817, - 0x7c4ab4ef, 0xea881114, 0x7c467ca6, 0xea7c3ae5, - 0x7c42420a, 0xea70658a, 0x7c3e051b, 0xea649105, - 0x7c39c5da, 0xea58bd54, 0x7c358446, 0xea4cea79, - 0x7c314060, 0xea411874, 0x7c2cfa28, 0xea354746, - 0x7c28b19e, 0xea2976ef, 0x7c2466c2, 0xea1da770, - 0x7c201994, 0xea11d8c8, 0x7c1bca16, 0xea060af9, - 0x7c177845, 0xe9fa3e03, 0x7c132424, 0xe9ee71e6, - 0x7c0ecdb2, 0xe9e2a6a3, 0x7c0a74f0, 0xe9d6dc3b, - 0x7c0619dc, 0xe9cb12ad, 0x7c01bc78, 0xe9bf49fa, - 0x7bfd5cc4, 0xe9b38223, 0x7bf8fac0, 0xe9a7bb28, - 0x7bf4966c, 0xe99bf509, 0x7bf02fc9, 0xe9902fc7, - 0x7bebc6d5, 0xe9846b63, 0x7be75b93, 0xe978a7dd, - 0x7be2ee01, 0xe96ce535, 0x7bde7e20, 0xe961236c, - 0x7bda0bf0, 0xe9556282, 0x7bd59771, 0xe949a278, - 0x7bd120a4, 0xe93de34e, 0x7bcca789, 0xe9322505, - 0x7bc82c1f, 0xe926679c, 0x7bc3ae67, 0xe91aab16, - 0x7bbf2e62, 0xe90eef71, 0x7bbaac0e, 0xe90334af, - 0x7bb6276e, 0xe8f77acf, 0x7bb1a080, 0xe8ebc1d3, - 0x7bad1744, 0xe8e009ba, 0x7ba88bbc, 0xe8d45286, - 0x7ba3fde7, 0xe8c89c37, 0x7b9f6dc5, 0xe8bce6cd, - 0x7b9adb57, 0xe8b13248, 0x7b96469d, 0xe8a57ea9, - 0x7b91af97, 0xe899cbf1, 0x7b8d1644, 0xe88e1a20, - 0x7b887aa6, 0xe8826936, 0x7b83dcbc, 0xe876b934, - 0x7b7f3c87, 0xe86b0a1a, 0x7b7a9a07, 0xe85f5be9, - 0x7b75f53c, 0xe853aea1, 0x7b714e25, 0xe8480243, - 0x7b6ca4c4, 0xe83c56cf, 0x7b67f919, 0xe830ac45, - 0x7b634b23, 0xe82502a7, 0x7b5e9ae4, 0xe81959f4, - 0x7b59e85a, 0xe80db22d, 0x7b553386, 0xe8020b52, - 0x7b507c69, 0xe7f66564, 0x7b4bc303, 0xe7eac063, - 0x7b470753, 0xe7df1c50, 0x7b42495a, 0xe7d3792b, - 0x7b3d8918, 0xe7c7d6f4, 0x7b38c68e, 0xe7bc35ad, - 0x7b3401bb, 0xe7b09555, 0x7b2f3aa0, 0xe7a4f5ed, - 0x7b2a713d, 0xe7995776, 0x7b25a591, 0xe78db9ef, - 0x7b20d79e, 0xe7821d59, 0x7b1c0764, 0xe77681b6, - 0x7b1734e2, 0xe76ae704, 0x7b126019, 0xe75f4d45, - 0x7b0d8909, 0xe753b479, 0x7b08afb2, 0xe7481ca1, - 0x7b03d414, 0xe73c85bc, 0x7afef630, 0xe730efcc, - 0x7afa1605, 0xe7255ad1, 0x7af53395, 0xe719c6cb, - 0x7af04edf, 0xe70e33bb, 0x7aeb67e3, 0xe702a1a1, - 0x7ae67ea1, 0xe6f7107e, 0x7ae1931a, 0xe6eb8052, - 0x7adca54e, 0xe6dff11d, 0x7ad7b53d, 0xe6d462e1, - 0x7ad2c2e8, 0xe6c8d59c, 0x7acdce4d, 0xe6bd4951, - 0x7ac8d76f, 0xe6b1bdff, 0x7ac3de4c, 0xe6a633a6, - 0x7abee2e5, 0xe69aaa48, 0x7ab9e53a, 0xe68f21e5, - 0x7ab4e54c, 0xe6839a7c, 0x7aafe31b, 0xe6781410, - 0x7aaadea6, 0xe66c8e9f, 0x7aa5d7ee, 0xe6610a2a, - 0x7aa0cef3, 0xe65586b3, 0x7a9bc3b6, 0xe64a0438, - 0x7a96b636, 0xe63e82bc, 0x7a91a674, 0xe633023e, - 0x7a8c9470, 0xe62782be, 0x7a87802a, 0xe61c043d, - 0x7a8269a3, 0xe61086bc, 0x7a7d50da, 0xe6050a3b, - 0x7a7835cf, 0xe5f98ebb, 0x7a731884, 0xe5ee143b, - 0x7a6df8f8, 0xe5e29abc, 0x7a68d72b, 0xe5d72240, - 0x7a63b31d, 0xe5cbaac5, 0x7a5e8cd0, 0xe5c0344d, - 0x7a596442, 0xe5b4bed8, 0x7a543974, 0xe5a94a67, - 0x7a4f0c67, 0xe59dd6f9, 0x7a49dd1a, 0xe5926490, - 0x7a44ab8e, 0xe586f32c, 0x7a3f77c3, 0xe57b82cd, - 0x7a3a41b9, 0xe5701374, 0x7a350970, 0xe564a521, - 0x7a2fcee8, 0xe55937d5, 0x7a2a9223, 0xe54dcb8f, - 0x7a25531f, 0xe5426051, 0x7a2011de, 0xe536f61b, - 0x7a1ace5f, 0xe52b8cee, 0x7a1588a2, 0xe52024c9, - 0x7a1040a8, 0xe514bdad, 0x7a0af671, 0xe509579b, - 0x7a05a9fd, 0xe4fdf294, 0x7a005b4d, 0xe4f28e96, - 0x79fb0a60, 0xe4e72ba4, 0x79f5b737, 0xe4dbc9bd, - 0x79f061d2, 0xe4d068e2, 0x79eb0a31, 0xe4c50914, - 0x79e5b054, 0xe4b9aa52, 0x79e0543c, 0xe4ae4c9d, - 0x79daf5e8, 0xe4a2eff6, 0x79d5955a, 0xe497945d, - 0x79d03291, 0xe48c39d3, 0x79cacd8d, 0xe480e057, - 0x79c5664f, 0xe47587eb, 0x79bffcd7, 0xe46a308f, - 0x79ba9125, 0xe45eda43, 0x79b52339, 0xe4538507, - 0x79afb313, 0xe44830dd, 0x79aa40b4, 0xe43cddc4, - 0x79a4cc1c, 0xe4318bbe, 0x799f554b, 0xe4263ac9, - 0x7999dc42, 0xe41aeae8, 0x799460ff, 0xe40f9c1a, - 0x798ee385, 0xe4044e60, 0x798963d2, 0xe3f901ba, - 0x7983e1e8, 0xe3edb628, 0x797e5dc6, 0xe3e26bac, - 0x7978d76c, 0xe3d72245, 0x79734edc, 0xe3cbd9f4, - 0x796dc414, 0xe3c092b9, 0x79683715, 0xe3b54c95, - 0x7962a7e0, 0xe3aa0788, 0x795d1675, 0xe39ec393, - 0x795782d3, 0xe39380b6, 0x7951ecfc, 0xe3883ef2, - 0x794c54ee, 0xe37cfe47, 0x7946baac, 0xe371beb5, - 0x79411e33, 0xe366803c, 0x793b7f86, 0xe35b42df, - 0x7935dea4, 0xe350069b, 0x79303b8e, 0xe344cb73, - 0x792a9642, 0xe3399167, 0x7924eec3, 0xe32e5876, - 0x791f4510, 0xe32320a2, 0x79199929, 0xe317e9eb, - 0x7913eb0e, 0xe30cb451, 0x790e3ac0, 0xe3017fd5, - 0x7908883f, 0xe2f64c77, 0x7902d38b, 0xe2eb1a37, - 0x78fd1ca4, 0xe2dfe917, 0x78f7638b, 0xe2d4b916, - 0x78f1a840, 0xe2c98a35, 0x78ebeac2, 0xe2be5c74, - 0x78e62b13, 0xe2b32fd4, 0x78e06932, 0xe2a80456, - 0x78daa520, 0xe29cd9f8, 0x78d4dedd, 0xe291b0bd, - 0x78cf1669, 0xe28688a4, 0x78c94bc4, 0xe27b61af, - 0x78c37eef, 0xe2703bdc, 0x78bdafea, 0xe265172e, - 0x78b7deb4, 0xe259f3a3, 0x78b20b4f, 0xe24ed13d, - 0x78ac35ba, 0xe243affc, 0x78a65df6, 0xe2388fe1, - 0x78a08402, 0xe22d70eb, 0x789aa7e0, 0xe222531c, - 0x7894c98f, 0xe2173674, 0x788ee910, 0xe20c1af3, - 0x78890663, 0xe2010099, 0x78832187, 0xe1f5e768, - 0x787d3a7e, 0xe1eacf5f, 0x78775147, 0xe1dfb87f, - 0x787165e3, 0xe1d4a2c8, 0x786b7852, 0xe1c98e3b, - 0x78658894, 0xe1be7ad8, 0x785f96a9, 0xe1b368a0, - 0x7859a292, 0xe1a85793, 0x7853ac4f, 0xe19d47b1, - 0x784db3e0, 0xe19238fb, 0x7847b946, 0xe1872b72, - 0x7841bc7f, 0xe17c1f15, 0x783bbd8e, 0xe17113e5, - 0x7835bc71, 0xe16609e3, 0x782fb92a, 0xe15b0110, - 0x7829b3b9, 0xe14ff96a, 0x7823ac1d, 0xe144f2f3, - 0x781da256, 0xe139edac, 0x78179666, 0xe12ee995, - 0x7811884d, 0xe123e6ad, 0x780b780a, 0xe118e4f6, - 0x7805659e, 0xe10de470, 0x77ff5109, 0xe102e51c, - 0x77f93a4b, 0xe0f7e6f9, 0x77f32165, 0xe0ecea09, - 0x77ed0657, 0xe0e1ee4b, 0x77e6e921, 0xe0d6f3c1, - 0x77e0c9c3, 0xe0cbfa6a, 0x77daa83d, 0xe0c10247, - 0x77d48490, 0xe0b60b58, 0x77ce5ebd, 0xe0ab159e, - 0x77c836c2, 0xe0a0211a, 0x77c20ca1, 0xe0952dcb, - 0x77bbe05a, 0xe08a3bb2, 0x77b5b1ec, 0xe07f4acf, - 0x77af8159, 0xe0745b24, 0x77a94ea0, 0xe0696cb0, - 0x77a319c2, 0xe05e7f74, 0x779ce2be, 0xe053936f, - 0x7796a996, 0xe048a8a4, 0x77906e49, 0xe03dbf11, - 0x778a30d8, 0xe032d6b8, 0x7783f143, 0xe027ef99, - 0x777daf89, 0xe01d09b4, 0x77776bac, 0xe012250a, - 0x777125ac, 0xe007419b, 0x776add88, 0xdffc5f67, - 0x77649341, 0xdff17e70, 0x775e46d8, 0xdfe69eb4, - 0x7757f84c, 0xdfdbc036, 0x7751a79e, 0xdfd0e2f5, - 0x774b54ce, 0xdfc606f1, 0x7744ffdd, 0xdfbb2c2c, - 0x773ea8ca, 0xdfb052a5, 0x77384f95, 0xdfa57a5d, - 0x7731f440, 0xdf9aa354, 0x772b96ca, 0xdf8fcd8b, - 0x77253733, 0xdf84f902, 0x771ed57c, 0xdf7a25ba, - 0x771871a5, 0xdf6f53b3, 0x77120bae, 0xdf6482ed, - 0x770ba398, 0xdf59b369, 0x77053962, 0xdf4ee527, - 0x76fecd0e, 0xdf441828, 0x76f85e9a, 0xdf394c6b, - 0x76f1ee09, 0xdf2e81f3, 0x76eb7b58, 0xdf23b8be, - 0x76e5068a, 0xdf18f0ce, 0x76de8f9e, 0xdf0e2a22, - 0x76d81695, 0xdf0364bc, 0x76d19b6e, 0xdef8a09b, - 0x76cb1e2a, 0xdeedddc0, 0x76c49ec9, 0xdee31c2b, - 0x76be1d4c, 0xded85bdd, 0x76b799b3, 0xdecd9cd7, - 0x76b113fd, 0xdec2df18, 0x76aa8c2c, 0xdeb822a1, - 0x76a4023f, 0xdead6773, 0x769d7637, 0xdea2ad8d, - 0x7696e814, 0xde97f4f1, 0x769057d6, 0xde8d3d9e, - 0x7689c57d, 0xde828796, 0x7683310b, 0xde77d2d8, - 0x767c9a7e, 0xde6d1f65, 0x767601d7, 0xde626d3e, - 0x766f6717, 0xde57bc62, 0x7668ca3e, 0xde4d0cd2, - 0x76622b4c, 0xde425e8f, 0x765b8a41, 0xde37b199, - 0x7654e71d, 0xde2d05f1, 0x764e41e2, 0xde225b96, - 0x76479a8e, 0xde17b28a, 0x7640f123, 0xde0d0acc, - 0x763a45a0, 0xde02645d, 0x76339806, 0xddf7bf3e, - 0x762ce855, 0xdded1b6e, 0x7626368d, 0xdde278ef, - 0x761f82af, 0xddd7d7c1, 0x7618ccba, 0xddcd37e4, - 0x761214b0, 0xddc29958, 0x760b5a90, 0xddb7fc1e, - 0x76049e5b, 0xddad6036, 0x75fde011, 0xdda2c5a2, - 0x75f71fb1, 0xdd982c60, 0x75f05d3d, 0xdd8d9472, - 0x75e998b5, 0xdd82fdd8, 0x75e2d219, 0xdd786892, - 0x75dc0968, 0xdd6dd4a2, 0x75d53ea5, 0xdd634206, - 0x75ce71ce, 0xdd58b0c0, 0x75c7a2e3, 0xdd4e20d0, - 0x75c0d1e7, 0xdd439236, 0x75b9fed7, 0xdd3904f4, - 0x75b329b5, 0xdd2e7908, 0x75ac5282, 0xdd23ee74, - 0x75a5793c, 0xdd196538, 0x759e9de5, 0xdd0edd55, - 0x7597c07d, 0xdd0456ca, 0x7590e104, 0xdcf9d199, - 0x7589ff7a, 0xdcef4dc2, 0x75831be0, 0xdce4cb44, - 0x757c3636, 0xdcda4a21, 0x75754e7c, 0xdccfca59, - 0x756e64b2, 0xdcc54bec, 0x756778d9, 0xdcbacedb, - 0x75608af1, 0xdcb05326, 0x75599afa, 0xdca5d8cd, - 0x7552a8f4, 0xdc9b5fd2, 0x754bb4e1, 0xdc90e834, - 0x7544bebf, 0xdc8671f3, 0x753dc68f, 0xdc7bfd11, - 0x7536cc52, 0xdc71898d, 0x752fd008, 0xdc671768, - 0x7528d1b1, 0xdc5ca6a2, 0x7521d14d, 0xdc52373c, - 0x751acedd, 0xdc47c936, 0x7513ca60, 0xdc3d5c91, - 0x750cc3d8, 0xdc32f14d, 0x7505bb44, 0xdc28876a, - 0x74feb0a5, 0xdc1e1ee9, 0x74f7a3fb, 0xdc13b7c9, - 0x74f09546, 0xdc09520d, 0x74e98487, 0xdbfeedb3, - 0x74e271bd, 0xdbf48abd, 0x74db5cea, 0xdbea292b, - 0x74d4460c, 0xdbdfc8fc, 0x74cd2d26, 0xdbd56a32, - 0x74c61236, 0xdbcb0cce, 0x74bef53d, 0xdbc0b0ce, - 0x74b7d63c, 0xdbb65634, 0x74b0b533, 0xdbabfd01, - 0x74a99221, 0xdba1a534, 0x74a26d08, 0xdb974ece, - 0x749b45e7, 0xdb8cf9cf, 0x74941cbf, 0xdb82a638, - 0x748cf190, 0xdb785409, 0x7485c45b, 0xdb6e0342, - 0x747e951f, 0xdb63b3e5, 0x747763dd, 0xdb5965f1, - 0x74703095, 0xdb4f1967, 0x7468fb47, 0xdb44ce46, - 0x7461c3f5, 0xdb3a8491, 0x745a8a9d, 0xdb303c46, - 0x74534f41, 0xdb25f566, 0x744c11e0, 0xdb1baff2, - 0x7444d27b, 0xdb116beb, 0x743d9112, 0xdb072950, - 0x74364da6, 0xdafce821, 0x742f0836, 0xdaf2a860, - 0x7427c0c3, 0xdae86a0d, 0x7420774d, 0xdade2d28, - 0x74192bd5, 0xdad3f1b1, 0x7411de5b, 0xdac9b7a9, - 0x740a8edf, 0xdabf7f11, 0x74033d61, 0xdab547e8, - 0x73fbe9e2, 0xdaab122f, 0x73f49462, 0xdaa0dde7, - 0x73ed3ce1, 0xda96ab0f, 0x73e5e360, 0xda8c79a9, - 0x73de87de, 0xda8249b4, 0x73d72a5d, 0xda781b31, - 0x73cfcadc, 0xda6dee21, 0x73c8695b, 0xda63c284, - 0x73c105db, 0xda599859, 0x73b9a05d, 0xda4f6fa3, - 0x73b238e0, 0xda454860, 0x73aacf65, 0xda3b2292, - 0x73a363ec, 0xda30fe38, 0x739bf675, 0xda26db54, - 0x73948701, 0xda1cb9e5, 0x738d1590, 0xda1299ec, - 0x7385a222, 0xda087b69, 0x737e2cb7, 0xd9fe5e5e, - 0x7376b551, 0xd9f442c9, 0x736f3bee, 0xd9ea28ac, - 0x7367c090, 0xd9e01006, 0x73604336, 0xd9d5f8d9, - 0x7358c3e2, 0xd9cbe325, 0x73514292, 0xd9c1cee9, - 0x7349bf48, 0xd9b7bc27, 0x73423a04, 0xd9adaadf, - 0x733ab2c6, 0xd9a39b11, 0x7333298f, 0xd9998cbe, - 0x732b9e5e, 0xd98f7fe6, 0x73241134, 0xd9857489, - 0x731c8211, 0xd97b6aa8, 0x7314f0f6, 0xd9716243, - 0x730d5de3, 0xd9675b5a, 0x7305c8d7, 0xd95d55ef, - 0x72fe31d5, 0xd9535201, 0x72f698db, 0xd9494f90, - 0x72eefdea, 0xd93f4e9e, 0x72e76102, 0xd9354f2a, - 0x72dfc224, 0xd92b5135, 0x72d82150, 0xd92154bf, - 0x72d07e85, 0xd91759c9, 0x72c8d9c6, 0xd90d6053, - 0x72c13311, 0xd903685d, 0x72b98a67, 0xd8f971e8, - 0x72b1dfc9, 0xd8ef7cf4, 0x72aa3336, 0xd8e58982, - 0x72a284b0, 0xd8db9792, 0x729ad435, 0xd8d1a724, - 0x729321c7, 0xd8c7b838, 0x728b6d66, 0xd8bdcad0, - 0x7283b712, 0xd8b3deeb, 0x727bfecc, 0xd8a9f48a, - 0x72744493, 0xd8a00bae, 0x726c8868, 0xd8962456, - 0x7264ca4c, 0xd88c3e83, 0x725d0a3e, 0xd8825a35, - 0x72554840, 0xd878776d, 0x724d8450, 0xd86e962b, - 0x7245be70, 0xd864b670, 0x723df6a0, 0xd85ad83c, - 0x72362ce0, 0xd850fb8e, 0x722e6130, 0xd8472069, - 0x72269391, 0xd83d46cc, 0x721ec403, 0xd8336eb7, - 0x7216f287, 0xd829982b, 0x720f1f1c, 0xd81fc328, - 0x720749c3, 0xd815efae, 0x71ff727c, 0xd80c1dbf, - 0x71f79948, 0xd8024d59, 0x71efbe27, 0xd7f87e7f, - 0x71e7e118, 0xd7eeb130, 0x71e0021e, 0xd7e4e56c, - 0x71d82137, 0xd7db1b34, 0x71d03e64, 0xd7d15288, - 0x71c859a5, 0xd7c78b68, 0x71c072fb, 0xd7bdc5d6, - 0x71b88a66, 0xd7b401d1, 0x71b09fe7, 0xd7aa3f5a, - 0x71a8b37c, 0xd7a07e70, 0x71a0c528, 0xd796bf16, - 0x7198d4ea, 0xd78d014a, 0x7190e2c3, 0xd783450d, - 0x7188eeb2, 0xd7798a60, 0x7180f8b8, 0xd76fd143, - 0x717900d6, 0xd76619b6, 0x7171070c, 0xd75c63ba, - 0x71690b59, 0xd752af4f, 0x71610dbf, 0xd748fc75, - 0x71590e3e, 0xd73f4b2e, 0x71510cd5, 0xd7359b78, - 0x71490986, 0xd72bed55, 0x71410450, 0xd72240c5, - 0x7138fd35, 0xd71895c9, 0x7130f433, 0xd70eec60, - 0x7128e94c, 0xd705448b, 0x7120dc80, 0xd6fb9e4b, - 0x7118cdcf, 0xd6f1f99f, 0x7110bd39, 0xd6e85689, - 0x7108aabf, 0xd6deb508, 0x71009661, 0xd6d5151d, - 0x70f8801f, 0xd6cb76c9, 0x70f067fb, 0xd6c1da0b, - 0x70e84df3, 0xd6b83ee4, 0x70e03208, 0xd6aea555, - 0x70d8143b, 0xd6a50d5d, 0x70cff48c, 0xd69b76fe, - 0x70c7d2fb, 0xd691e237, 0x70bfaf89, 0xd6884f09, - 0x70b78a36, 0xd67ebd74, 0x70af6302, 0xd6752d79, - 0x70a739ed, 0xd66b9f18, 0x709f0ef8, 0xd6621251, - 0x7096e223, 0xd6588725, 0x708eb36f, 0xd64efd94, - 0x708682dc, 0xd645759f, 0x707e5069, 0xd63bef46, - 0x70761c18, 0xd6326a88, 0x706de5e9, 0xd628e767, - 0x7065addb, 0xd61f65e4, 0x705d73f0, 0xd615e5fd, - 0x70553828, 0xd60c67b4, 0x704cfa83, 0xd602eb0a, - 0x7044bb00, 0xd5f96ffd, 0x703c79a2, 0xd5eff690, - 0x70343667, 0xd5e67ec1, 0x702bf151, 0xd5dd0892, - 0x7023aa5f, 0xd5d39403, 0x701b6193, 0xd5ca2115, - 0x701316eb, 0xd5c0afc6, 0x700aca69, 0xd5b74019, - 0x70027c0c, 0xd5add20d, 0x6ffa2bd6, 0xd5a465a3, - 0x6ff1d9c7, 0xd59afadb, 0x6fe985de, 0xd59191b5, - 0x6fe1301c, 0xd5882a32, 0x6fd8d882, 0xd57ec452, - 0x6fd07f0f, 0xd5756016, 0x6fc823c5, 0xd56bfd7d, - 0x6fbfc6a3, 0xd5629c89, 0x6fb767aa, 0xd5593d3a, - 0x6faf06da, 0xd54fdf8f, 0x6fa6a433, 0xd5468389, - 0x6f9e3fb6, 0xd53d292a, 0x6f95d963, 0xd533d070, - 0x6f8d713a, 0xd52a795d, 0x6f85073c, 0xd52123f0, - 0x6f7c9b69, 0xd517d02b, 0x6f742dc1, 0xd50e7e0d, - 0x6f6bbe45, 0xd5052d97, 0x6f634cf5, 0xd4fbdec9, - 0x6f5ad9d1, 0xd4f291a4, 0x6f5264da, 0xd4e94627, - 0x6f49ee0f, 0xd4dffc54, 0x6f417573, 0xd4d6b42b, - 0x6f38fb03, 0xd4cd6dab, 0x6f307ec2, 0xd4c428d6, - 0x6f2800af, 0xd4bae5ab, 0x6f1f80ca, 0xd4b1a42c, - 0x6f16ff14, 0xd4a86458, 0x6f0e7b8e, 0xd49f2630, - 0x6f05f637, 0xd495e9b3, 0x6efd6f10, 0xd48caee4, - 0x6ef4e619, 0xd48375c1, 0x6eec5b53, 0xd47a3e4b, - 0x6ee3cebe, 0xd4710883, 0x6edb405a, 0xd467d469, - 0x6ed2b027, 0xd45ea1fd, 0x6eca1e27, 0xd4557140, - 0x6ec18a58, 0xd44c4232, 0x6eb8f4bc, 0xd44314d3, - 0x6eb05d53, 0xd439e923, 0x6ea7c41e, 0xd430bf24, - 0x6e9f291b, 0xd42796d5, 0x6e968c4d, 0xd41e7037, - 0x6e8dedb3, 0xd4154b4a, 0x6e854d4d, 0xd40c280e, - 0x6e7cab1c, 0xd4030684, 0x6e740720, 0xd3f9e6ad, - 0x6e6b615a, 0xd3f0c887, 0x6e62b9ca, 0xd3e7ac15, - 0x6e5a1070, 0xd3de9156, 0x6e51654c, 0xd3d5784a, - 0x6e48b860, 0xd3cc60f2, 0x6e4009aa, 0xd3c34b4f, - 0x6e37592c, 0xd3ba3760, 0x6e2ea6e6, 0xd3b12526, - 0x6e25f2d8, 0xd3a814a2, 0x6e1d3d03, 0xd39f05d3, - 0x6e148566, 0xd395f8ba, 0x6e0bcc03, 0xd38ced57, - 0x6e0310d9, 0xd383e3ab, 0x6dfa53e9, 0xd37adbb6, - 0x6df19534, 0xd371d579, 0x6de8d4b8, 0xd368d0f3, - 0x6de01278, 0xd35fce26, 0x6dd74e73, 0xd356cd11, - 0x6dce88aa, 0xd34dcdb4, 0x6dc5c11c, 0xd344d011, - 0x6dbcf7cb, 0xd33bd427, 0x6db42cb6, 0xd332d9f7, - 0x6dab5fdf, 0xd329e181, 0x6da29144, 0xd320eac6, - 0x6d99c0e7, 0xd317f5c6, 0x6d90eec8, 0xd30f0280, - 0x6d881ae8, 0xd30610f7, 0x6d7f4545, 0xd2fd2129, - 0x6d766de2, 0xd2f43318, 0x6d6d94bf, 0xd2eb46c3, - 0x6d64b9da, 0xd2e25c2b, 0x6d5bdd36, 0xd2d97350, - 0x6d52fed2, 0xd2d08c33, 0x6d4a1eaf, 0xd2c7a6d4, - 0x6d413ccd, 0xd2bec333, 0x6d38592c, 0xd2b5e151, - 0x6d2f73cd, 0xd2ad012e, 0x6d268cb0, 0xd2a422ca, - 0x6d1da3d5, 0xd29b4626, 0x6d14b93d, 0xd2926b41, - 0x6d0bcce8, 0xd289921e, 0x6d02ded7, 0xd280babb, - 0x6cf9ef09, 0xd277e518, 0x6cf0fd80, 0xd26f1138, - 0x6ce80a3a, 0xd2663f19, 0x6cdf153a, 0xd25d6ebc, - 0x6cd61e7f, 0xd254a021, 0x6ccd2609, 0xd24bd34a, - 0x6cc42bd9, 0xd2430835, 0x6cbb2fef, 0xd23a3ee4, - 0x6cb2324c, 0xd2317756, 0x6ca932ef, 0xd228b18d, - 0x6ca031da, 0xd21fed88, 0x6c972f0d, 0xd2172b48, - 0x6c8e2a87, 0xd20e6acc, 0x6c85244a, 0xd205ac17, - 0x6c7c1c55, 0xd1fcef27, 0x6c7312a9, 0xd1f433fd, - 0x6c6a0746, 0xd1eb7a9a, 0x6c60fa2d, 0xd1e2c2fd, - 0x6c57eb5e, 0xd1da0d28, 0x6c4edada, 0xd1d1591a, - 0x6c45c8a0, 0xd1c8a6d4, 0x6c3cb4b1, 0xd1bff656, - 0x6c339f0e, 0xd1b747a0, 0x6c2a87b6, 0xd1ae9ab4, - 0x6c216eaa, 0xd1a5ef90, 0x6c1853eb, 0xd19d4636, - 0x6c0f3779, 0xd1949ea6, 0x6c061953, 0xd18bf8e0, - 0x6bfcf97c, 0xd18354e4, 0x6bf3d7f2, 0xd17ab2b3, - 0x6beab4b6, 0xd172124d, 0x6be18fc9, 0xd16973b3, - 0x6bd8692b, 0xd160d6e5, 0x6bcf40dc, 0xd1583be2, - 0x6bc616dd, 0xd14fa2ad, 0x6bbceb2d, 0xd1470b44, - 0x6bb3bdce, 0xd13e75a8, 0x6baa8ec0, 0xd135e1d9, - 0x6ba15e03, 0xd12d4fd9, 0x6b982b97, 0xd124bfa6, - 0x6b8ef77d, 0xd11c3142, 0x6b85c1b5, 0xd113a4ad, - 0x6b7c8a3f, 0xd10b19e7, 0x6b73511c, 0xd10290f0, - 0x6b6a164d, 0xd0fa09c9, 0x6b60d9d0, 0xd0f18472, - 0x6b579ba8, 0xd0e900ec, 0x6b4e5bd4, 0xd0e07f36, - 0x6b451a55, 0xd0d7ff51, 0x6b3bd72a, 0xd0cf813e, - 0x6b329255, 0xd0c704fd, 0x6b294bd5, 0xd0be8a8d, - 0x6b2003ac, 0xd0b611f1, 0x6b16b9d9, 0xd0ad9b26, - 0x6b0d6e5c, 0xd0a5262f, 0x6b042137, 0xd09cb30b, - 0x6afad269, 0xd09441bb, 0x6af181f3, 0xd08bd23f, - 0x6ae82fd5, 0xd0836497, 0x6adedc10, 0xd07af8c4, - 0x6ad586a3, 0xd0728ec6, 0x6acc2f90, 0xd06a269d, - 0x6ac2d6d6, 0xd061c04a, 0x6ab97c77, 0xd0595bcd, - 0x6ab02071, 0xd050f926, 0x6aa6c2c6, 0xd0489856, - 0x6a9d6377, 0xd040395d, 0x6a940283, 0xd037dc3b, - 0x6a8a9fea, 0xd02f80f1, 0x6a813bae, 0xd027277e, - 0x6a77d5ce, 0xd01ecfe4, 0x6a6e6e4b, 0xd0167a22, - 0x6a650525, 0xd00e2639, 0x6a5b9a5d, 0xd005d42a, - 0x6a522df3, 0xcffd83f4, 0x6a48bfe7, 0xcff53597, - 0x6a3f503a, 0xcfece915, 0x6a35deeb, 0xcfe49e6d, - 0x6a2c6bfd, 0xcfdc55a1, 0x6a22f76e, 0xcfd40eaf, - 0x6a19813f, 0xcfcbc999, 0x6a100970, 0xcfc3865e, - 0x6a069003, 0xcfbb4500, 0x69fd14f6, 0xcfb3057d, - 0x69f3984c, 0xcfaac7d8, 0x69ea1a03, 0xcfa28c10, - 0x69e09a1c, 0xcf9a5225, 0x69d71899, 0xcf921a17, - 0x69cd9578, 0xcf89e3e8, 0x69c410ba, 0xcf81af97, - 0x69ba8a61, 0xcf797d24, 0x69b1026c, 0xcf714c91, - 0x69a778db, 0xcf691ddd, 0x699dedaf, 0xcf60f108, - 0x699460e8, 0xcf58c613, 0x698ad287, 0xcf509cfe, - 0x6981428c, 0xcf4875ca, 0x6977b0f7, 0xcf405077, - 0x696e1dc9, 0xcf382d05, 0x69648902, 0xcf300b74, - 0x695af2a3, 0xcf27ebc5, 0x69515aab, 0xcf1fcdf8, - 0x6947c11c, 0xcf17b20d, 0x693e25f5, 0xcf0f9805, - 0x69348937, 0xcf077fe1, 0x692aeae3, 0xceff699f, - 0x69214af8, 0xcef75541, 0x6917a977, 0xceef42c7, - 0x690e0661, 0xcee73231, 0x690461b5, 0xcedf2380, - 0x68fabb75, 0xced716b4, 0x68f113a0, 0xcecf0bcd, - 0x68e76a37, 0xcec702cb, 0x68ddbf3b, 0xcebefbb0, - 0x68d412ab, 0xceb6f67a, 0x68ca6488, 0xceaef32b, - 0x68c0b4d2, 0xcea6f1c2, 0x68b7038b, 0xce9ef241, - 0x68ad50b1, 0xce96f4a7, 0x68a39c46, 0xce8ef8f4, - 0x6899e64a, 0xce86ff2a, 0x68902ebd, 0xce7f0748, - 0x688675a0, 0xce77114e, 0x687cbaf3, 0xce6f1d3d, - 0x6872feb6, 0xce672b16, 0x686940ea, 0xce5f3ad8, - 0x685f8190, 0xce574c84, 0x6855c0a6, 0xce4f6019, - 0x684bfe2f, 0xce47759a, 0x68423a2a, 0xce3f8d05, - 0x68387498, 0xce37a65b, 0x682ead78, 0xce2fc19c, - 0x6824e4cc, 0xce27dec9, 0x681b1a94, 0xce1ffde2, - 0x68114ed0, 0xce181ee8, 0x68078181, 0xce1041d9, - 0x67fdb2a7, 0xce0866b8, 0x67f3e241, 0xce008d84, - 0x67ea1052, 0xcdf8b63d, 0x67e03cd8, 0xcdf0e0e4, - 0x67d667d5, 0xcde90d79, 0x67cc9149, 0xcde13bfd, - 0x67c2b934, 0xcdd96c6f, 0x67b8df97, 0xcdd19ed0, - 0x67af0472, 0xcdc9d320, 0x67a527c4, 0xcdc20960, - 0x679b4990, 0xcdba4190, 0x679169d5, 0xcdb27bb0, - 0x67878893, 0xcdaab7c0, 0x677da5cb, 0xcda2f5c2, - 0x6773c17d, 0xcd9b35b4, 0x6769dbaa, 0xcd937798, - 0x675ff452, 0xcd8bbb6d, 0x67560b76, 0xcd840134, - 0x674c2115, 0xcd7c48ee, 0x67423530, 0xcd74929a, - 0x673847c8, 0xcd6cde39, 0x672e58dc, 0xcd652bcb, - 0x6724686e, 0xcd5d7b50, 0x671a767e, 0xcd55ccca, - 0x6710830c, 0xcd4e2037, 0x67068e18, 0xcd467599, - 0x66fc97a3, 0xcd3eccef, 0x66f29fad, 0xcd37263a, - 0x66e8a637, 0xcd2f817b, 0x66deab41, 0xcd27deb0, - 0x66d4aecb, 0xcd203ddc, 0x66cab0d6, 0xcd189efe, - 0x66c0b162, 0xcd110216, 0x66b6b070, 0xcd096725, - 0x66acadff, 0xcd01ce2b, 0x66a2aa11, 0xccfa3729, - 0x6698a4a6, 0xccf2a21d, 0x668e9dbd, 0xcceb0f0a, - 0x66849558, 0xcce37def, 0x667a8b77, 0xccdbeecc, - 0x6670801a, 0xccd461a2, 0x66667342, 0xccccd671, - 0x665c64ef, 0xccc54d3a, 0x66525521, 0xccbdc5fc, - 0x664843d9, 0xccb640b8, 0x663e3117, 0xccaebd6e, - 0x66341cdb, 0xcca73c1e, 0x662a0727, 0xcc9fbcca, - 0x661feffa, 0xcc983f70, 0x6615d754, 0xcc90c412, - 0x660bbd37, 0xcc894aaf, 0x6601a1a2, 0xcc81d349, - 0x65f78497, 0xcc7a5dde, 0x65ed6614, 0xcc72ea70, - 0x65e3461b, 0xcc6b78ff, 0x65d924ac, 0xcc64098b, - 0x65cf01c8, 0xcc5c9c14, 0x65c4dd6e, 0xcc55309b, - 0x65bab7a0, 0xcc4dc720, 0x65b0905d, 0xcc465fa3, - 0x65a667a7, 0xcc3efa25, 0x659c3d7c, 0xcc3796a5, - 0x659211df, 0xcc303524, 0x6587e4cf, 0xcc28d5a3, - 0x657db64c, 0xcc217822, 0x65738657, 0xcc1a1ca0, - 0x656954f1, 0xcc12c31f, 0x655f2219, 0xcc0b6b9e, - 0x6554edd1, 0xcc04161e, 0x654ab818, 0xcbfcc29f, - 0x654080ef, 0xcbf57121, 0x65364857, 0xcbee21a5, - 0x652c0e4f, 0xcbe6d42b, 0x6521d2d8, 0xcbdf88b3, - 0x651795f3, 0xcbd83f3d, 0x650d57a0, 0xcbd0f7ca, - 0x650317df, 0xcbc9b25a, 0x64f8d6b0, 0xcbc26eee, - 0x64ee9415, 0xcbbb2d85, 0x64e4500e, 0xcbb3ee20, - 0x64da0a9a, 0xcbacb0bf, 0x64cfc3ba, 0xcba57563, - 0x64c57b6f, 0xcb9e3c0b, 0x64bb31ba, 0xcb9704b9, - 0x64b0e699, 0xcb8fcf6b, 0x64a69a0f, 0xcb889c23, - 0x649c4c1b, 0xcb816ae1, 0x6491fcbe, 0xcb7a3ba5, - 0x6487abf7, 0xcb730e70, 0x647d59c8, 0xcb6be341, - 0x64730631, 0xcb64ba19, 0x6468b132, 0xcb5d92f8, - 0x645e5acc, 0xcb566ddf, 0x645402ff, 0xcb4f4acd, - 0x6449a9cc, 0xcb4829c4, 0x643f4f32, 0xcb410ac3, - 0x6434f332, 0xcb39edca, 0x642a95ce, 0xcb32d2da, - 0x64203704, 0xcb2bb9f4, 0x6415d6d5, 0xcb24a316, - 0x640b7543, 0xcb1d8e43, 0x6401124d, 0xcb167b79, - 0x63f6adf3, 0xcb0f6aba, 0x63ec4837, 0xcb085c05, - 0x63e1e117, 0xcb014f5b, 0x63d77896, 0xcafa44bc, - 0x63cd0eb3, 0xcaf33c28, 0x63c2a36f, 0xcaec35a0, - 0x63b836ca, 0xcae53123, 0x63adc8c4, 0xcade2eb3, - 0x63a3595e, 0xcad72e4f, 0x6398e898, 0xcad02ff8, - 0x638e7673, 0xcac933ae, 0x638402ef, 0xcac23971, - 0x63798e0d, 0xcabb4141, 0x636f17cc, 0xcab44b1f, - 0x6364a02e, 0xcaad570c, 0x635a2733, 0xcaa66506, - 0x634facda, 0xca9f750f, 0x63453125, 0xca988727, - 0x633ab414, 0xca919b4e, 0x633035a7, 0xca8ab184, - 0x6325b5df, 0xca83c9ca, 0x631b34bc, 0xca7ce420, - 0x6310b23e, 0xca760086, 0x63062e67, 0xca6f1efc, - 0x62fba936, 0xca683f83, 0x62f122ab, 0xca61621b, - 0x62e69ac8, 0xca5a86c4, 0x62dc118c, 0xca53ad7e, - 0x62d186f8, 0xca4cd64b, 0x62c6fb0c, 0xca460129, - 0x62bc6dca, 0xca3f2e19, 0x62b1df30, 0xca385d1d, - 0x62a74f40, 0xca318e32, 0x629cbdfa, 0xca2ac15b, - 0x62922b5e, 0xca23f698, 0x6287976e, 0xca1d2de7, - 0x627d0228, 0xca16674b, 0x62726b8e, 0xca0fa2c3, - 0x6267d3a0, 0xca08e04f, 0x625d3a5e, 0xca021fef, - 0x62529fca, 0xc9fb61a5, 0x624803e2, 0xc9f4a570, - 0x623d66a8, 0xc9edeb50, 0x6232c81c, 0xc9e73346, - 0x6228283f, 0xc9e07d51, 0x621d8711, 0xc9d9c973, - 0x6212e492, 0xc9d317ab, 0x620840c2, 0xc9cc67fa, - 0x61fd9ba3, 0xc9c5ba60, 0x61f2f534, 0xc9bf0edd, - 0x61e84d76, 0xc9b86572, 0x61dda46a, 0xc9b1be1e, - 0x61d2fa0f, 0xc9ab18e3, 0x61c84e67, 0xc9a475bf, - 0x61bda171, 0xc99dd4b4, 0x61b2f32e, 0xc99735c2, - 0x61a8439e, 0xc99098e9, 0x619d92c2, 0xc989fe29, - 0x6192e09b, 0xc9836582, 0x61882d28, 0xc97ccef5, - 0x617d786a, 0xc9763a83, 0x6172c262, 0xc96fa82a, - 0x61680b0f, 0xc96917ec, 0x615d5273, 0xc96289c9, - 0x6152988d, 0xc95bfdc1, 0x6147dd5f, 0xc95573d4, - 0x613d20e8, 0xc94eec03, 0x61326329, 0xc948664d, - 0x6127a423, 0xc941e2b4, 0x611ce3d5, 0xc93b6137, - 0x61122240, 0xc934e1d6, 0x61075f65, 0xc92e6492, - 0x60fc9b44, 0xc927e96b, 0x60f1d5de, 0xc9217062, - 0x60e70f32, 0xc91af976, 0x60dc4742, 0xc91484a8, - 0x60d17e0d, 0xc90e11f7, 0x60c6b395, 0xc907a166, - 0x60bbe7d8, 0xc90132f2, 0x60b11ad9, 0xc8fac69e, - 0x60a64c97, 0xc8f45c68, 0x609b7d13, 0xc8edf452, - 0x6090ac4d, 0xc8e78e5b, 0x6085da46, 0xc8e12a84, - 0x607b06fe, 0xc8dac8cd, 0x60703275, 0xc8d46936, - 0x60655cac, 0xc8ce0bc0, 0x605a85a3, 0xc8c7b06b, - 0x604fad5b, 0xc8c15736, 0x6044d3d4, 0xc8bb0023, - 0x6039f90f, 0xc8b4ab32, 0x602f1d0b, 0xc8ae5862, - 0x60243fca, 0xc8a807b4, 0x6019614c, 0xc8a1b928, - 0x600e8190, 0xc89b6cbf, 0x6003a099, 0xc8952278, - 0x5ff8be65, 0xc88eda54, 0x5feddaf6, 0xc8889454, - 0x5fe2f64c, 0xc8825077, 0x5fd81067, 0xc87c0ebd, - 0x5fcd2948, 0xc875cf28, 0x5fc240ef, 0xc86f91b7, - 0x5fb7575c, 0xc869566a, 0x5fac6c91, 0xc8631d42, - 0x5fa1808c, 0xc85ce63e, 0x5f969350, 0xc856b160, - 0x5f8ba4dc, 0xc8507ea7, 0x5f80b531, 0xc84a4e14, - 0x5f75c44e, 0xc8441fa6, 0x5f6ad235, 0xc83df35f, - 0x5f5fdee6, 0xc837c93e, 0x5f54ea62, 0xc831a143, - 0x5f49f4a8, 0xc82b7b70, 0x5f3efdb9, 0xc82557c3, - 0x5f340596, 0xc81f363d, 0x5f290c3f, 0xc81916df, - 0x5f1e11b5, 0xc812f9a9, 0x5f1315f7, 0xc80cde9b, - 0x5f081907, 0xc806c5b5, 0x5efd1ae4, 0xc800aef7, - 0x5ef21b90, 0xc7fa9a62, 0x5ee71b0a, 0xc7f487f6, - 0x5edc1953, 0xc7ee77b3, 0x5ed1166b, 0xc7e8699a, - 0x5ec61254, 0xc7e25daa, 0x5ebb0d0d, 0xc7dc53e3, - 0x5eb00696, 0xc7d64c47, 0x5ea4fef0, 0xc7d046d6, - 0x5e99f61d, 0xc7ca438f, 0x5e8eec1b, 0xc7c44272, - 0x5e83e0eb, 0xc7be4381, 0x5e78d48e, 0xc7b846ba, - 0x5e6dc705, 0xc7b24c20, 0x5e62b84f, 0xc7ac53b1, - 0x5e57a86d, 0xc7a65d6e, 0x5e4c9760, 0xc7a06957, - 0x5e418528, 0xc79a776c, 0x5e3671c5, 0xc79487ae, - 0x5e2b5d38, 0xc78e9a1d, 0x5e204781, 0xc788aeb9, - 0x5e1530a1, 0xc782c582, 0x5e0a1898, 0xc77cde79, - 0x5dfeff67, 0xc776f99d, 0x5df3e50d, 0xc77116f0, - 0x5de8c98c, 0xc76b3671, 0x5dddace4, 0xc7655820, - 0x5dd28f15, 0xc75f7bfe, 0x5dc7701f, 0xc759a20a, - 0x5dbc5004, 0xc753ca46, 0x5db12ec3, 0xc74df4b1, - 0x5da60c5d, 0xc748214c, 0x5d9ae8d2, 0xc7425016, - 0x5d8fc424, 0xc73c8111, 0x5d849e51, 0xc736b43c, - 0x5d79775c, 0xc730e997, 0x5d6e4f43, 0xc72b2123, - 0x5d632608, 0xc7255ae0, 0x5d57fbaa, 0xc71f96ce, - 0x5d4cd02c, 0xc719d4ed, 0x5d41a38c, 0xc714153e, - 0x5d3675cb, 0xc70e57c0, 0x5d2b46ea, 0xc7089c75, - 0x5d2016e9, 0xc702e35c, 0x5d14e5c9, 0xc6fd2c75, - 0x5d09b389, 0xc6f777c1, 0x5cfe802b, 0xc6f1c540, - 0x5cf34baf, 0xc6ec14f2, 0x5ce81615, 0xc6e666d7, - 0x5cdcdf5e, 0xc6e0baf0, 0x5cd1a78a, 0xc6db113d, - 0x5cc66e99, 0xc6d569be, 0x5cbb348d, 0xc6cfc472, - 0x5caff965, 0xc6ca215c, 0x5ca4bd21, 0xc6c4807a, - 0x5c997fc4, 0xc6bee1cd, 0x5c8e414b, 0xc6b94554, - 0x5c8301b9, 0xc6b3ab12, 0x5c77c10e, 0xc6ae1304, - 0x5c6c7f4a, 0xc6a87d2d, 0x5c613c6d, 0xc6a2e98b, - 0x5c55f878, 0xc69d5820, 0x5c4ab36b, 0xc697c8eb, - 0x5c3f6d47, 0xc6923bec, 0x5c34260c, 0xc68cb124, - 0x5c28ddbb, 0xc6872894, 0x5c1d9454, 0xc681a23a, - 0x5c1249d8, 0xc67c1e18, 0x5c06fe46, 0xc6769c2e, - 0x5bfbb1a0, 0xc6711c7b, 0x5bf063e6, 0xc66b9f01, - 0x5be51518, 0xc66623be, 0x5bd9c537, 0xc660aab5, - 0x5bce7442, 0xc65b33e4, 0x5bc3223c, 0xc655bf4c, - 0x5bb7cf23, 0xc6504ced, 0x5bac7af9, 0xc64adcc7, - 0x5ba125bd, 0xc6456edb, 0x5b95cf71, 0xc6400329, - 0x5b8a7815, 0xc63a99b1, 0x5b7f1fa9, 0xc6353273, - 0x5b73c62d, 0xc62fcd6f, 0x5b686ba3, 0xc62a6aa6, - 0x5b5d100a, 0xc6250a18, 0x5b51b363, 0xc61fabc4, - 0x5b4655ae, 0xc61a4fac, 0x5b3af6ec, 0xc614f5cf, - 0x5b2f971e, 0xc60f9e2e, 0x5b243643, 0xc60a48c9, - 0x5b18d45c, 0xc604f5a0, 0x5b0d716a, 0xc5ffa4b3, - 0x5b020d6c, 0xc5fa5603, 0x5af6a865, 0xc5f5098f, - 0x5aeb4253, 0xc5efbf58, 0x5adfdb37, 0xc5ea775e, - 0x5ad47312, 0xc5e531a1, 0x5ac909e5, 0xc5dfee22, - 0x5abd9faf, 0xc5daace1, 0x5ab23471, 0xc5d56ddd, - 0x5aa6c82b, 0xc5d03118, 0x5a9b5adf, 0xc5caf690, - 0x5a8fec8c, 0xc5c5be47, 0x5a847d33, 0xc5c0883d, - 0x5a790cd4, 0xc5bb5472, 0x5a6d9b70, 0xc5b622e6, - 0x5a622907, 0xc5b0f399, 0x5a56b599, 0xc5abc68c, - 0x5a4b4128, 0xc5a69bbe, 0x5a3fcbb3, 0xc5a17330, - 0x5a34553b, 0xc59c4ce3, 0x5a28ddc0, 0xc59728d5, - 0x5a1d6544, 0xc5920708, 0x5a11ebc5, 0xc58ce77c, - 0x5a067145, 0xc587ca31, 0x59faf5c5, 0xc582af26, - 0x59ef7944, 0xc57d965d, 0x59e3fbc3, 0xc5787fd6, - 0x59d87d42, 0xc5736b90, 0x59ccfdc2, 0xc56e598c, - 0x59c17d44, 0xc56949ca, 0x59b5fbc8, 0xc5643c4a, - 0x59aa794d, 0xc55f310d, 0x599ef5d6, 0xc55a2812, - 0x59937161, 0xc555215a, 0x5987ebf0, 0xc5501ce5, - 0x597c6584, 0xc54b1ab4, 0x5970de1b, 0xc5461ac6, - 0x596555b8, 0xc5411d1b, 0x5959cc5a, 0xc53c21b4, - 0x594e4201, 0xc5372891, 0x5942b6af, 0xc53231b3, - 0x59372a64, 0xc52d3d18, 0x592b9d1f, 0xc5284ac3, - 0x59200ee3, 0xc5235ab2, 0x59147fae, 0xc51e6ce6, - 0x5908ef82, 0xc519815f, 0x58fd5e5f, 0xc514981d, - 0x58f1cc45, 0xc50fb121, 0x58e63935, 0xc50acc6b, - 0x58daa52f, 0xc505e9fb, 0x58cf1034, 0xc50109d0, - 0x58c37a44, 0xc4fc2bec, 0x58b7e35f, 0xc4f7504e, - 0x58ac4b87, 0xc4f276f7, 0x58a0b2bb, 0xc4ed9fe7, - 0x589518fc, 0xc4e8cb1e, 0x58897e4a, 0xc4e3f89c, - 0x587de2a7, 0xc4df2862, 0x58724611, 0xc4da5a6f, - 0x5866a88a, 0xc4d58ec3, 0x585b0a13, 0xc4d0c560, - 0x584f6aab, 0xc4cbfe45, 0x5843ca53, 0xc4c73972, - 0x5838290c, 0xc4c276e8, 0x582c86d5, 0xc4bdb6a6, - 0x5820e3b0, 0xc4b8f8ad, 0x58153f9d, 0xc4b43cfd, - 0x58099a9c, 0xc4af8397, 0x57fdf4ae, 0xc4aacc7a, - 0x57f24dd3, 0xc4a617a6, 0x57e6a60c, 0xc4a1651c, - 0x57dafd59, 0xc49cb4dd, 0x57cf53bb, 0xc49806e7, - 0x57c3a931, 0xc4935b3c, 0x57b7fdbd, 0xc48eb1db, - 0x57ac515f, 0xc48a0ac4, 0x57a0a417, 0xc48565f9, - 0x5794f5e6, 0xc480c379, 0x578946cc, 0xc47c2344, - 0x577d96ca, 0xc477855a, 0x5771e5e0, 0xc472e9bc, - 0x5766340f, 0xc46e5069, 0x575a8157, 0xc469b963, - 0x574ecdb8, 0xc46524a9, 0x57431933, 0xc460923b, - 0x573763c9, 0xc45c0219, 0x572bad7a, 0xc4577444, - 0x571ff646, 0xc452e8bc, 0x57143e2d, 0xc44e5f80, - 0x57088531, 0xc449d892, 0x56fccb51, 0xc44553f2, - 0x56f1108f, 0xc440d19e, 0x56e554ea, 0xc43c5199, - 0x56d99864, 0xc437d3e1, 0x56cddafb, 0xc4335877, - 0x56c21cb2, 0xc42edf5c, 0x56b65d88, 0xc42a688f, - 0x56aa9d7e, 0xc425f410, 0x569edc94, 0xc42181e0, - 0x56931acb, 0xc41d11ff, 0x56875823, 0xc418a46d, - 0x567b949d, 0xc414392b, 0x566fd039, 0xc40fd037, - 0x56640af7, 0xc40b6994, 0x565844d8, 0xc4070540, - 0x564c7ddd, 0xc402a33c, 0x5640b606, 0xc3fe4388, - 0x5634ed53, 0xc3f9e624, 0x562923c5, 0xc3f58b10, - 0x561d595d, 0xc3f1324e, 0x56118e1a, 0xc3ecdbdc, - 0x5605c1fd, 0xc3e887bb, 0x55f9f507, 0xc3e435ea, - 0x55ee2738, 0xc3dfe66c, 0x55e25890, 0xc3db993e, - 0x55d68911, 0xc3d74e62, 0x55cab8ba, 0xc3d305d8, - 0x55bee78c, 0xc3cebfa0, 0x55b31587, 0xc3ca7bba, - 0x55a742ac, 0xc3c63a26, 0x559b6efb, 0xc3c1fae5, - 0x558f9a76, 0xc3bdbdf6, 0x5583c51b, 0xc3b9835a, - 0x5577eeec, 0xc3b54b11, 0x556c17e9, 0xc3b1151b, - 0x55604013, 0xc3ace178, 0x5554676a, 0xc3a8b028, - 0x55488dee, 0xc3a4812c, 0x553cb3a0, 0xc3a05484, - 0x5530d881, 0xc39c2a2f, 0x5524fc90, 0xc398022f, - 0x55191fcf, 0xc393dc82, 0x550d423d, 0xc38fb92a, - 0x550163dc, 0xc38b9827, 0x54f584ac, 0xc3877978, - 0x54e9a4ac, 0xc3835d1e, 0x54ddc3de, 0xc37f4319, - 0x54d1e242, 0xc37b2b6a, 0x54c5ffd9, 0xc377160f, - 0x54ba1ca3, 0xc373030a, 0x54ae38a0, 0xc36ef25b, - 0x54a253d1, 0xc36ae401, 0x54966e36, 0xc366d7fd, - 0x548a87d1, 0xc362ce50, 0x547ea0a0, 0xc35ec6f8, - 0x5472b8a5, 0xc35ac1f7, 0x5466cfe1, 0xc356bf4d, - 0x545ae653, 0xc352bef9, 0x544efbfc, 0xc34ec0fc, - 0x544310dd, 0xc34ac556, 0x543724f5, 0xc346cc07, - 0x542b3846, 0xc342d510, 0x541f4ad1, 0xc33ee070, - 0x54135c94, 0xc33aee27, 0x54076d91, 0xc336fe37, - 0x53fb7dc9, 0xc333109e, 0x53ef8d3c, 0xc32f255e, - 0x53e39be9, 0xc32b3c75, 0x53d7a9d3, 0xc32755e5, - 0x53cbb6f8, 0xc32371ae, 0x53bfc35b, 0xc31f8fcf, - 0x53b3cefa, 0xc31bb049, 0x53a7d9d7, 0xc317d31c, - 0x539be3f2, 0xc313f848, 0x538fed4b, 0xc3101fce, - 0x5383f5e3, 0xc30c49ad, 0x5377fdbb, 0xc30875e5, - 0x536c04d2, 0xc304a477, 0x53600b2a, 0xc300d563, - 0x535410c3, 0xc2fd08a9, 0x5348159d, 0xc2f93e4a, - 0x533c19b8, 0xc2f57644, 0x53301d16, 0xc2f1b099, - 0x53241fb6, 0xc2eded49, 0x5318219a, 0xc2ea2c53, - 0x530c22c1, 0xc2e66db8, 0x5300232c, 0xc2e2b178, - 0x52f422db, 0xc2def794, 0x52e821cf, 0xc2db400a, - 0x52dc2009, 0xc2d78add, 0x52d01d89, 0xc2d3d80a, - 0x52c41a4f, 0xc2d02794, 0x52b8165b, 0xc2cc7979, - 0x52ac11af, 0xc2c8cdbb, 0x52a00c4b, 0xc2c52459, - 0x5294062f, 0xc2c17d52, 0x5287ff5b, 0xc2bdd8a9, - 0x527bf7d1, 0xc2ba365c, 0x526fef90, 0xc2b6966c, - 0x5263e699, 0xc2b2f8d8, 0x5257dced, 0xc2af5da2, - 0x524bd28c, 0xc2abc4c9, 0x523fc776, 0xc2a82e4d, - 0x5233bbac, 0xc2a49a2e, 0x5227af2e, 0xc2a1086d, - 0x521ba1fd, 0xc29d790a, 0x520f941a, 0xc299ec05, - 0x52038584, 0xc296615d, 0x51f7763c, 0xc292d914, - 0x51eb6643, 0xc28f5329, 0x51df5599, 0xc28bcf9c, - 0x51d3443f, 0xc2884e6e, 0x51c73235, 0xc284cf9f, - 0x51bb1f7c, 0xc281532e, 0x51af0c13, 0xc27dd91c, - 0x51a2f7fc, 0xc27a616a, 0x5196e337, 0xc276ec16, - 0x518acdc4, 0xc2737922, 0x517eb7a4, 0xc270088e, - 0x5172a0d7, 0xc26c9a58, 0x5166895f, 0xc2692e83, - 0x515a713a, 0xc265c50e, 0x514e586a, 0xc2625df8, - 0x51423ef0, 0xc25ef943, 0x513624cb, 0xc25b96ee, - 0x512a09fc, 0xc25836f9, 0x511dee84, 0xc254d965, - 0x5111d263, 0xc2517e31, 0x5105b599, 0xc24e255e, - 0x50f99827, 0xc24aceed, 0x50ed7a0e, 0xc2477adc, - 0x50e15b4e, 0xc244292c, 0x50d53be7, 0xc240d9de, - 0x50c91bda, 0xc23d8cf1, 0x50bcfb28, 0xc23a4265, - 0x50b0d9d0, 0xc236fa3b, 0x50a4b7d3, 0xc233b473, - 0x50989532, 0xc230710d, 0x508c71ee, 0xc22d3009, - 0x50804e06, 0xc229f167, 0x5074297b, 0xc226b528, - 0x5068044e, 0xc2237b4b, 0x505bde7f, 0xc22043d0, - 0x504fb80e, 0xc21d0eb8, 0x504390fd, 0xc219dc03, - 0x5037694b, 0xc216abb1, 0x502b40f8, 0xc2137dc2, - 0x501f1807, 0xc2105236, 0x5012ee76, 0xc20d290d, - 0x5006c446, 0xc20a0248, 0x4ffa9979, 0xc206dde6, - 0x4fee6e0d, 0xc203bbe8, 0x4fe24205, 0xc2009c4e, - 0x4fd6155f, 0xc1fd7f17, 0x4fc9e81e, 0xc1fa6445, - 0x4fbdba40, 0xc1f74bd6, 0x4fb18bc8, 0xc1f435cc, - 0x4fa55cb4, 0xc1f12227, 0x4f992d06, 0xc1ee10e5, - 0x4f8cfcbe, 0xc1eb0209, 0x4f80cbdc, 0xc1e7f591, - 0x4f749a61, 0xc1e4eb7e, 0x4f68684e, 0xc1e1e3d0, - 0x4f5c35a3, 0xc1dede87, 0x4f500260, 0xc1dbdba3, - 0x4f43ce86, 0xc1d8db25, 0x4f379a16, 0xc1d5dd0c, - 0x4f2b650f, 0xc1d2e158, 0x4f1f2f73, 0xc1cfe80a, - 0x4f12f941, 0xc1ccf122, 0x4f06c27a, 0xc1c9fca0, - 0x4efa8b20, 0xc1c70a84, 0x4eee5331, 0xc1c41ace, - 0x4ee21aaf, 0xc1c12d7e, 0x4ed5e19a, 0xc1be4294, - 0x4ec9a7f3, 0xc1bb5a11, 0x4ebd6db9, 0xc1b873f5, - 0x4eb132ef, 0xc1b5903f, 0x4ea4f793, 0xc1b2aef0, - 0x4e98bba7, 0xc1afd007, 0x4e8c7f2a, 0xc1acf386, - 0x4e80421e, 0xc1aa196c, 0x4e740483, 0xc1a741b9, - 0x4e67c65a, 0xc1a46c6e, 0x4e5b87a2, 0xc1a1998a, - 0x4e4f485c, 0xc19ec90d, 0x4e430889, 0xc19bfaf9, - 0x4e36c82a, 0xc1992f4c, 0x4e2a873e, 0xc1966606, - 0x4e1e45c6, 0xc1939f29, 0x4e1203c3, 0xc190dab4, - 0x4e05c135, 0xc18e18a7, 0x4df97e1d, 0xc18b5903, - 0x4ded3a7b, 0xc1889bc6, 0x4de0f64f, 0xc185e0f3, - 0x4dd4b19a, 0xc1832888, 0x4dc86c5d, 0xc1807285, - 0x4dbc2698, 0xc17dbeec, 0x4dafe04b, 0xc17b0dbb, - 0x4da39978, 0xc1785ef4, 0x4d97521d, 0xc175b296, - 0x4d8b0a3d, 0xc17308a1, 0x4d7ec1d6, 0xc1706115, - 0x4d7278eb, 0xc16dbbf3, 0x4d662f7b, 0xc16b193a, - 0x4d59e586, 0xc16878eb, 0x4d4d9b0e, 0xc165db05, - 0x4d415013, 0xc1633f8a, 0x4d350495, 0xc160a678, - 0x4d28b894, 0xc15e0fd1, 0x4d1c6c11, 0xc15b7b94, - 0x4d101f0e, 0xc158e9c1, 0x4d03d189, 0xc1565a58, - 0x4cf78383, 0xc153cd5a, 0x4ceb34fe, 0xc15142c6, - 0x4cdee5f9, 0xc14eba9d, 0x4cd29676, 0xc14c34df, - 0x4cc64673, 0xc149b18b, 0x4cb9f5f3, 0xc14730a3, - 0x4cada4f5, 0xc144b225, 0x4ca1537a, 0xc1423613, - 0x4c950182, 0xc13fbc6c, 0x4c88af0e, 0xc13d4530, - 0x4c7c5c1e, 0xc13ad060, 0x4c7008b3, 0xc1385dfb, - 0x4c63b4ce, 0xc135ee02, 0x4c57606e, 0xc1338075, - 0x4c4b0b94, 0xc1311553, 0x4c3eb641, 0xc12eac9d, - 0x4c326075, 0xc12c4653, 0x4c260a31, 0xc129e276, - 0x4c19b374, 0xc1278104, 0x4c0d5c41, 0xc12521ff, - 0x4c010496, 0xc122c566, 0x4bf4ac75, 0xc1206b39, - 0x4be853de, 0xc11e1379, 0x4bdbfad1, 0xc11bbe26, - 0x4bcfa150, 0xc1196b3f, 0x4bc34759, 0xc1171ac6, - 0x4bb6ecef, 0xc114ccb9, 0x4baa9211, 0xc1128119, - 0x4b9e36c0, 0xc11037e6, 0x4b91dafc, 0xc10df120, - 0x4b857ec7, 0xc10bacc8, 0x4b79221f, 0xc1096add, - 0x4b6cc506, 0xc1072b5f, 0x4b60677c, 0xc104ee4f, - 0x4b540982, 0xc102b3ac, 0x4b47ab19, 0xc1007b77, - 0x4b3b4c40, 0xc0fe45b0, 0x4b2eecf8, 0xc0fc1257, - 0x4b228d42, 0xc0f9e16b, 0x4b162d1d, 0xc0f7b2ee, - 0x4b09cc8c, 0xc0f586df, 0x4afd6b8d, 0xc0f35d3e, - 0x4af10a22, 0xc0f1360b, 0x4ae4a84b, 0xc0ef1147, - 0x4ad84609, 0xc0eceef1, 0x4acbe35b, 0xc0eacf09, - 0x4abf8043, 0xc0e8b190, 0x4ab31cc1, 0xc0e69686, - 0x4aa6b8d5, 0xc0e47deb, 0x4a9a5480, 0xc0e267be, - 0x4a8defc3, 0xc0e05401, 0x4a818a9d, 0xc0de42b2, - 0x4a752510, 0xc0dc33d2, 0x4a68bf1b, 0xc0da2762, - 0x4a5c58c0, 0xc0d81d61, 0x4a4ff1fe, 0xc0d615cf, - 0x4a438ad7, 0xc0d410ad, 0x4a37234a, 0xc0d20dfa, - 0x4a2abb59, 0xc0d00db6, 0x4a1e5303, 0xc0ce0fe3, - 0x4a11ea49, 0xc0cc147f, 0x4a05812c, 0xc0ca1b8a, - 0x49f917ac, 0xc0c82506, 0x49ecadc9, 0xc0c630f2, - 0x49e04385, 0xc0c43f4d, 0x49d3d8df, 0xc0c25019, - 0x49c76dd8, 0xc0c06355, 0x49bb0271, 0xc0be7901, - 0x49ae96aa, 0xc0bc911d, 0x49a22a83, 0xc0baabaa, - 0x4995bdfd, 0xc0b8c8a7, 0x49895118, 0xc0b6e815, - 0x497ce3d5, 0xc0b509f3, 0x49707635, 0xc0b32e42, - 0x49640837, 0xc0b15502, 0x495799dd, 0xc0af7e33, - 0x494b2b27, 0xc0ada9d4, 0x493ebc14, 0xc0abd7e6, - 0x49324ca7, 0xc0aa086a, 0x4925dcdf, 0xc0a83b5e, - 0x49196cbc, 0xc0a670c4, 0x490cfc40, 0xc0a4a89b, - 0x49008b6a, 0xc0a2e2e3, 0x48f41a3c, 0xc0a11f9d, - 0x48e7a8b5, 0xc09f5ec8, 0x48db36d6, 0xc09da065, - 0x48cec4a0, 0xc09be473, 0x48c25213, 0xc09a2af3, - 0x48b5df30, 0xc09873e4, 0x48a96bf6, 0xc096bf48, - 0x489cf867, 0xc0950d1d, 0x48908483, 0xc0935d64, - 0x4884104b, 0xc091b01d, 0x48779bbe, 0xc0900548, - 0x486b26de, 0xc08e5ce5, 0x485eb1ab, 0xc08cb6f5, - 0x48523c25, 0xc08b1376, 0x4845c64d, 0xc089726a, - 0x48395024, 0xc087d3d0, 0x482cd9a9, 0xc08637a9, - 0x482062de, 0xc0849df4, 0x4813ebc2, 0xc08306b2, - 0x48077457, 0xc08171e2, 0x47fafc9c, 0xc07fdf85, - 0x47ee8493, 0xc07e4f9b, 0x47e20c3b, 0xc07cc223, - 0x47d59396, 0xc07b371e, 0x47c91aa3, 0xc079ae8c, - 0x47bca163, 0xc078286e, 0x47b027d7, 0xc076a4c2, - 0x47a3adff, 0xc0752389, 0x479733dc, 0xc073a4c3, - 0x478ab96e, 0xc0722871, 0x477e3eb5, 0xc070ae92, - 0x4771c3b3, 0xc06f3726, 0x47654867, 0xc06dc22e, - 0x4758ccd2, 0xc06c4fa8, 0x474c50f4, 0xc06adf97, - 0x473fd4cf, 0xc06971f9, 0x47335862, 0xc06806ce, - 0x4726dbae, 0xc0669e18, 0x471a5eb3, 0xc06537d4, - 0x470de172, 0xc063d405, 0x470163eb, 0xc06272aa, - 0x46f4e620, 0xc06113c2, 0x46e86810, 0xc05fb74e, - 0x46dbe9bb, 0xc05e5d4e, 0x46cf6b23, 0xc05d05c3, - 0x46c2ec48, 0xc05bb0ab, 0x46b66d29, 0xc05a5e07, - 0x46a9edc9, 0xc0590dd8, 0x469d6e27, 0xc057c01d, - 0x4690ee44, 0xc05674d6, 0x46846e1f, 0xc0552c03, - 0x4677edbb, 0xc053e5a5, 0x466b6d16, 0xc052a1bb, - 0x465eec33, 0xc0516045, 0x46526b10, 0xc0502145, - 0x4645e9af, 0xc04ee4b8, 0x46396810, 0xc04daaa1, - 0x462ce634, 0xc04c72fe, 0x4620641a, 0xc04b3dcf, - 0x4613e1c5, 0xc04a0b16, 0x46075f33, 0xc048dad1, - 0x45fadc66, 0xc047ad01, 0x45ee595d, 0xc04681a6, - 0x45e1d61b, 0xc04558c0, 0x45d5529e, 0xc044324f, - 0x45c8cee7, 0xc0430e53, 0x45bc4af8, 0xc041eccc, - 0x45afc6d0, 0xc040cdba, 0x45a3426f, 0xc03fb11d, - 0x4596bdd7, 0xc03e96f6, 0x458a3908, 0xc03d7f44, - 0x457db403, 0xc03c6a07, 0x45712ec7, 0xc03b573f, - 0x4564a955, 0xc03a46ed, 0x455823ae, 0xc0393910, - 0x454b9dd3, 0xc0382da8, 0x453f17c3, 0xc03724b6, - 0x4532917f, 0xc0361e3a, 0x45260b08, 0xc0351a33, - 0x4519845e, 0xc03418a2, 0x450cfd82, 0xc0331986, - 0x45007674, 0xc0321ce0, 0x44f3ef35, 0xc03122b0, - 0x44e767c5, 0xc0302af5, 0x44dae024, 0xc02f35b1, - 0x44ce5854, 0xc02e42e2, 0x44c1d054, 0xc02d5289, - 0x44b54825, 0xc02c64a6, 0x44a8bfc7, 0xc02b7939, - 0x449c373c, 0xc02a9042, 0x448fae83, 0xc029a9c1, - 0x4483259d, 0xc028c5b6, 0x44769c8b, 0xc027e421, - 0x446a134c, 0xc0270502, 0x445d89e2, 0xc0262859, - 0x4451004d, 0xc0254e27, 0x4444768d, 0xc024766a, - 0x4437eca4, 0xc023a124, 0x442b6290, 0xc022ce54, - 0x441ed854, 0xc021fdfb, 0x44124dee, 0xc0213018, - 0x4405c361, 0xc02064ab, 0x43f938ac, 0xc01f9bb5, - 0x43ecadcf, 0xc01ed535, 0x43e022cc, 0xc01e112b, - 0x43d397a3, 0xc01d4f99, 0x43c70c54, 0xc01c907c, - 0x43ba80df, 0xc01bd3d6, 0x43adf546, 0xc01b19a7, - 0x43a16988, 0xc01a61ee, 0x4394dda7, 0xc019acac, - 0x438851a2, 0xc018f9e1, 0x437bc57b, 0xc018498c, - 0x436f3931, 0xc0179bae, 0x4362acc5, 0xc016f047, - 0x43562038, 0xc0164757, 0x43499389, 0xc015a0dd, - 0x433d06bb, 0xc014fcda, 0x433079cc, 0xc0145b4e, - 0x4323ecbe, 0xc013bc39, 0x43175f91, 0xc0131f9b, - 0x430ad245, 0xc0128574, 0x42fe44dc, 0xc011edc3, - 0x42f1b755, 0xc011588a, 0x42e529b0, 0xc010c5c7, - 0x42d89bf0, 0xc010357c, 0x42cc0e13, 0xc00fa7a8, - 0x42bf801a, 0xc00f1c4a, 0x42b2f207, 0xc00e9364, - 0x42a663d8, 0xc00e0cf5, 0x4299d590, 0xc00d88fd, - 0x428d472e, 0xc00d077c, 0x4280b8b3, 0xc00c8872, - 0x42742a1f, 0xc00c0be0, 0x42679b73, 0xc00b91c4, - 0x425b0caf, 0xc00b1a20, 0x424e7dd4, 0xc00aa4f3, - 0x4241eee2, 0xc00a323d, 0x42355fd9, 0xc009c1ff, - 0x4228d0bb, 0xc0095438, 0x421c4188, 0xc008e8e8, - 0x420fb240, 0xc008800f, 0x420322e3, 0xc00819ae, - 0x41f69373, 0xc007b5c4, 0x41ea03ef, 0xc0075452, - 0x41dd7459, 0xc006f556, 0x41d0e4b0, 0xc00698d3, - 0x41c454f5, 0xc0063ec6, 0x41b7c528, 0xc005e731, - 0x41ab354b, 0xc0059214, 0x419ea55d, 0xc0053f6e, - 0x4192155f, 0xc004ef3f, 0x41858552, 0xc004a188, - 0x4178f536, 0xc0045648, 0x416c650b, 0xc0040d80, - 0x415fd4d2, 0xc003c72f, 0x4153448c, 0xc0038356, - 0x4146b438, 0xc00341f4, 0x413a23d8, 0xc003030a, - 0x412d936c, 0xc002c697, 0x412102f4, 0xc0028c9c, - 0x41147271, 0xc0025519, 0x4107e1e3, 0xc002200d, - 0x40fb514b, 0xc001ed78, 0x40eec0aa, 0xc001bd5c, - 0x40e22fff, 0xc0018fb6, 0x40d59f4c, 0xc0016489, - 0x40c90e90, 0xc0013bd3, 0x40bc7dcc, 0xc0011594, - 0x40afed02, 0xc000f1ce, 0x40a35c30, 0xc000d07e, - 0x4096cb58, 0xc000b1a7, 0x408a3a7b, 0xc0009547, - 0x407da998, 0xc0007b5f, 0x407118b0, 0xc00063ee, - 0x406487c4, 0xc0004ef5, 0x4057f6d4, 0xc0003c74, - 0x404b65e1, 0xc0002c6a, 0x403ed4ea, 0xc0001ed8, - 0x403243f1, 0xc00013bd, 0x4025b2f7, 0xc0000b1a, - 0x401921fb, 0xc00004ef, 0x400c90fe, 0xc000013c, -}; - -/** -* @brief Initialization function for the Q31 RFFT/RIFFT. -* @param[in, out] *S points to an instance of the Q31 RFFT/RIFFT structure. -* @param[in, out] *S_CFFT points to an instance of the Q31 CFFT/CIFFT structure. -* @param[in] fftLenReal length of the FFT. -* @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. -* @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. -* @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. -* -* \par Description: -* \par -* The parameter fftLenReal Specifies length of RFFT/RIFFT Process. Supported FFT Lengths are 128, 512, 2048. -* \par -* The parameter ifftFlagR controls whether a forward or inverse transform is computed. -* Set(=1) ifftFlagR to calculate RIFFT, otherwise RFFT is calculated. -* \par -* The parameter bitReverseFlag controls whether output is in normal order or bit reversed order. -* Set(=1) bitReverseFlag for output to be in normal order otherwise output is in bit reversed order. -* \par -* This function also initializes Twiddle factor table. -*/ - -arm_status arm_rfft_init_q31( - arm_rfft_instance_q31 * S, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag) -{ - /* Initialise the default arm status */ - arm_status status = ARM_MATH_SUCCESS; - - /* Initialize the Real FFT length */ - S->fftLenReal = (uint16_t) fftLenReal; - - /* Initialize the Complex FFT length */ - S->fftLenBy2 = (uint16_t) fftLenReal / 2u; - - /* Initialize the Twiddle coefficientA pointer */ - S->pTwiddleAReal = (q31_t *) realCoefAQ31; - - /* Initialize the Twiddle coefficientB pointer */ - S->pTwiddleBReal = (q31_t *) realCoefBQ31; - - /* Initialize the Flag for selection of RFFT or RIFFT */ - S->ifftFlagR = (uint8_t) ifftFlagR; - - /* Initialize the Flag for calculation Bit reversal or not */ - S->bitReverseFlagR = (uint8_t) bitReverseFlag; - - /* Initialization of coef modifier depending on the FFT length */ - switch (S->fftLenReal) - { - case 8192: - S->twidCoefRModifier = 1u; - break; - case 2048u: - S->twidCoefRModifier = 4u; - break; - case 512u: - S->twidCoefRModifier = 16u; - break; - case 128u: - S->twidCoefRModifier = 64u; - break; - default: - /* Reporting argument error if rfftSize is not valid value */ - status = ARM_MATH_ARGUMENT_ERROR; - break; - } - - /* Init Complex FFT Instance */ - S->pCfft = S_CFFT; - - if(S->ifftFlagR) - { - /* Initializes the CIFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 1u, 1u); - } - else - { - /* Initializes the CFFT Module for fftLenreal/2 length */ - arm_cfft_radix4_init_q31(S->pCfft, (uint16_t) S->fftLenBy2, 0u, 1u); - } - - /* return the status of RFFT Init function */ - return (status); - -} - - /** - * @} end of RFFT_RIFFT group - */ diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c deleted file mode 100644 index c0c201277e..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q15.c +++ /dev/null @@ -1,460 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_q15.c -* -* Description: RFFT & RIFFT Q15 process function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - - -#include "arm_math.h" - -/*-------------------------------------------------------------------- -* Internal functions prototypes ---------------------------------------------------------------------*/ - -void arm_split_rfft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier); - -void arm_split_rifft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the Q15 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q15 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - * - * \par Input an output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different RFFT sizes. - * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: - * \par - * \image html RFFTQ15.gif "Input and Output Formats for Q15 RFFT" - * \par - * \image html RIFFTQ15.gif "Input and Output Formats for Q15 RIFFT" - */ - -void arm_rfft_q15( - const arm_rfft_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst) -{ - const arm_cfft_radix4_instance_q15 *S_CFFT = S->pCfft; - - /* Calculation of RIFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - /* Complex readix-4 IFFT process */ - arm_radix4_butterfly_inverse_q15(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q15(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - /* Calculation of RFFT of input */ - - /* Complex readix-4 FFT process */ - arm_radix4_butterfly_q15(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q15(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - arm_split_rfft_q15(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - - /** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param *pSrc points to the input buffer. - * @param fftLen length of FFT. - * @param *pATable points to the A twiddle Coef buffer. - * @param *pBTable points to the B twiddle Coef buffer. - * @param *pDst points to the output buffer. - * @param modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - * The function implements a Real FFT - */ - -void arm_split_rfft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q15_t *pSrc1, *pSrc2; - - -// pSrc[2u * fftLen] = pSrc[0]; -// pSrc[(2u * fftLen) + 1u] = pSrc[1]; - - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - pSrc1 = &pSrc[2]; - pSrc2 = &pSrc[(2u * fftLen) - 2u]; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - i = 1u; - - while(i < fftLen) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] */ - outR = __SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA)); - -#else - - /* -(pSrc[2 * i + 1] * pATable[2 * i + 1] - pSrc[2 * i] * pATable[2 * i]) */ - outR = -(__SMUSD(*__SIMD32(pSrc1), *__SIMD32(pCoefA))); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ - outR = __SMLAD(*__SIMD32(pSrc2), *__SIMD32(pCoefB), outR) >> 15u; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - -#ifndef ARM_MATH_BIG_ENDIAN - - outI = __SMUSDX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); - -#else - - outI = __SMUSDX(*__SIMD32(pCoefB), *__SIMD32(pSrc2)--); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] */ - outI = __SMLADX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), outI); - - /* write output */ - pDst[2u * i] = (q15_t) outR; - pDst[(2u * i) + 1u] = outI >> 15u; - - /* write complex conjugate output */ - pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; - pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i++; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - - -#else - - /* Run the below code for Cortex-M0 */ - - i = 1u; - - while(i < fftLen) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - outR = *pSrc1 * *pCoefA; - outR = outR - (*(pSrc1 + 1) * *(pCoefA + 1)); - outR = outR + (*pSrc2 * *pCoefB); - outR = (outR + (*(pSrc2 + 1) * *(pCoefB + 1))) >> 15; - - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - */ - - outI = *pSrc2 * *(pCoefB + 1); - outI = outI - (*(pSrc2 + 1) * *pCoefB); - outI = outI + (*(pSrc1 + 1) * *pCoefA); - outI = outI + (*pSrc1 * *(pCoefA + 1)); - - /* update input pointers */ - pSrc1 += 2u; - pSrc2 -= 2u; - - /* write output */ - pDst[2u * i] = (q15_t) outR; - pDst[(2u * i) + 1u] = outI >> 15u; - - /* write complex conjugate output */ - pDst[(4u * fftLen) - (2u * i)] = (q15_t) outR; - pDst[((4u * fftLen) - (2u * i)) + 1u] = -(outI >> 15u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i++; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - -#endif /* #ifndef ARM_MATH_CM0 */ - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - * The function implements a Real IFFT - */ -void arm_split_rifft_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pATable, - q15_t * pBTable, - q15_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q15_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q15_t *pSrc1, *pSrc2; - q15_t *pDst1 = &pDst[0]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - pSrc1 = &pSrc[0]; - pSrc2 = &pSrc[2u * fftLen]; - -#ifndef ARM_MATH_CM0 - - /* Run the below code for Cortex-M4 and Cortex-M3 */ - - i = fftLen; - - while(i > 0u) - { - - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - - -#ifndef ARM_MATH_BIG_ENDIAN - - /* pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]) */ - outR = __SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB)); - -#else - - /* -(-pIn[2 * n - 2 * i] * pBTable[2 * i] + - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1])) */ - outR = -(__SMUSD(*__SIMD32(pSrc2), *__SIMD32(pCoefB))); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] */ - outR = __SMLAD(*__SIMD32(pSrc1), *__SIMD32(pCoefA), outR) >> 15u; - - /* - -pIn[2 * n - 2 * i] * pBTable[2 * i + 1] + - pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = __SMUADX(*__SIMD32(pSrc2)--, *__SIMD32(pCoefB)); - - /* pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] */ - -#ifndef ARM_MATH_BIG_ENDIAN - - outI = __SMLSDX(*__SIMD32(pCoefA), *__SIMD32(pSrc1)++, -outI); - -#else - - outI = __SMLSDX(*__SIMD32(pSrc1)++, *__SIMD32(pCoefA), -outI); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - /* write output */ - -#ifndef ARM_MATH_BIG_ENDIAN - - *__SIMD32(pDst1)++ = __PKHBT(outR, (outI >> 15u), 16); - -#else - - *__SIMD32(pDst1)++ = __PKHBT((outI >> 15u), outR, 16); - -#endif /* #ifndef ARM_MATH_BIG_ENDIAN */ - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i--; - - } - - -#else - - /* Run the below code for Cortex-M0 */ - - i = fftLen; - - while(i > 0u) - { - - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - outR = *pSrc2 * *pCoefB; - outR = outR - (*(pSrc2 + 1) * *(pCoefB + 1)); - outR = outR + (*pSrc1 * *pCoefA); - outR = (outR + (*(pSrc1 + 1) * *(pCoefA + 1))) >> 15; - - /* - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - */ - - outI = *(pSrc1 + 1) * *pCoefA; - outI = outI - (*pSrc1 * *(pCoefA + 1)); - outI = outI - (*pSrc2 * *(pCoefB + 1)); - outI = outI - (*(pSrc2 + 1) * *(pCoefB)); - - /* update input pointers */ - pSrc1 += 2u; - pSrc2 -= 2u; - - /* write output */ - *pDst1++ = (q15_t) outR; - *pDst1++ = (q15_t) (outI >> 15); - - /* update coefficient pointer */ - pCoefB = pCoefB + (2u * modifier); - pCoefA = pCoefA + (2u * modifier); - - i--; - - } - -#endif /* #ifndef ARM_MATH_CM0 */ - -} diff --git a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c b/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c deleted file mode 100644 index afcb470416..0000000000 --- a/src/modules/mathlib/CMSIS/DSP_Lib/Source/TransformFunctions/arm_rfft_q31.c +++ /dev/null @@ -1,326 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 15. February 2012 -* $Revision: V1.1.0 -* -* Project: CMSIS DSP Library -* Title: arm_rfft_q31.c -* -* Description: RFFT & RIFFT Q31 process function -* -* -* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 -* -* Version 1.1.0 2012/02/15 -* Updated with more optimizations, bug fixes and minor API changes. -* -* Version 1.0.10 2011/7/15 -* Big Endian support added and Merged M0 and M3/M4 Source code. -* -* Version 1.0.3 2010/11/29 -* Re-organized the CMSIS folders and updated documentation. -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. -* -* Version 0.0.7 2010/06/10 -* Misra-C changes done -* -------------------------------------------------------------------- */ - -#include "arm_math.h" - -/*-------------------------------------------------------------------- -* Internal functions prototypes ---------------------------------------------------------------------*/ - -void arm_split_rfft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier); - -void arm_split_rifft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier); - -/** - * @addtogroup RFFT_RIFFT - * @{ - */ - -/** - * @brief Processing function for the Q31 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q31 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - * - * \par Input an output formats: - * \par - * Internally input is downscaled by 2 for every stage to avoid saturations inside CFFT/CIFFT process. - * Hence the output format is different for different RFFT sizes. - * The input and output formats for different RFFT sizes and number of bits to upscale are mentioned in the tables below for RFFT and RIFFT: - * \par - * \image html RFFTQ31.gif "Input and Output Formats for Q31 RFFT" - * - * \par - * \image html RIFFTQ31.gif "Input and Output Formats for Q31 RIFFT" - */ - -void arm_rfft_q31( - const arm_rfft_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst) -{ - const arm_cfft_radix4_instance_q31 *S_CFFT = S->pCfft; - - /* Calculation of RIFFT of input */ - if(S->ifftFlagR == 1u) - { - /* Real IFFT core process */ - arm_split_rifft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - - /* Complex readix-4 IFFT process */ - arm_radix4_butterfly_inverse_q31(pDst, S_CFFT->fftLen, - S_CFFT->pTwiddle, - S_CFFT->twidCoefModifier); - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q31(pDst, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - } - else - { - /* Calculation of RFFT of input */ - - /* Complex readix-4 FFT process */ - arm_radix4_butterfly_q31(pSrc, S_CFFT->fftLen, - S_CFFT->pTwiddle, S_CFFT->twidCoefModifier); - - /* Bit reversal process */ - if(S->bitReverseFlagR == 1u) - { - arm_bitreversal_q31(pSrc, S_CFFT->fftLen, - S_CFFT->bitRevFactor, S_CFFT->pBitRevTable); - } - - /* Real FFT core process */ - arm_split_rfft_q31(pSrc, S->fftLenBy2, S->pTwiddleAReal, - S->pTwiddleBReal, pDst, S->twidCoefRModifier); - } - -} - - - /** - * @} end of RFFT_RIFFT group - */ - -/** - * @brief Core Real FFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rfft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier) -{ - uint32_t i; /* Loop Counter */ - q31_t outR, outI; /* Temporary variables for output */ - q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - q31_t *pOut1 = &pDst[2], *pOut2 = &pDst[(4u * fftLen) - 1u]; - q31_t *pIn1 = &pSrc[2], *pIn2 = &pSrc[(2u * fftLen) - 1u]; - - /* Init coefficient pointers */ - pCoefA = &pATable[modifier * 2u]; - pCoefB = &pBTable[modifier * 2u]; - - i = fftLen - 1u; - - while(i > 0u) - { - /* - outR = (pSrc[2 * i] * pATable[2 * i] - pSrc[2 * i + 1] * pATable[2 * i + 1] - + pSrc[2 * n - 2 * i] * pBTable[2 * i] + - pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - */ - - /* outI = (pIn[2 * i + 1] * pATable[2 * i] + pIn[2 * i] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); */ - - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pSrc[2 * i] * pATable[2 * i] */ - outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); - - /* outI = pIn[2 * i] * pATable[2 * i + 1] */ - outI = ((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); - - /* - pSrc[2 * i + 1] * pATable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (-CoefA2))) >> 32); - - /* (pIn[2 * i + 1] * pATable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); - - /* pSrc[2 * n - 2 * i] * pBTable[2 * i] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (-CoefA2))) >> 32); - CoefB1 = *pCoefB; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefB1))) >> 32); - - /* pSrc[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (-CoefA2))) >> 32); - - /* write output */ - *pOut1++ = (outR << 1u); - *pOut1++ = (outI << 1u); - - /* write complex conjugate output */ - *pOut2-- = -(outI << 1u); - *pOut2-- = (outR << 1u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - i--; - - } - - pDst[2u * fftLen] = pSrc[0] - pSrc[1]; - pDst[(2u * fftLen) + 1u] = 0; - - pDst[0] = pSrc[0] + pSrc[1]; - pDst[1] = 0; - -} - - -/** - * @brief Core Real IFFT process - * @param[in] *pSrc points to the input buffer. - * @param[in] fftLen length of FFT. - * @param[in] *pATable points to the twiddle Coef A buffer. - * @param[in] *pBTable points to the twiddle Coef B buffer. - * @param[out] *pDst points to the output buffer. - * @param[in] modifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - -void arm_split_rifft_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pATable, - q31_t * pBTable, - q31_t * pDst, - uint32_t modifier) -{ - q31_t outR, outI; /* Temporary variables for output */ - q31_t *pCoefA, *pCoefB; /* Temporary pointers for twiddle factors */ - q31_t CoefA1, CoefA2, CoefB1; /* Temporary variables for twiddle coefficients */ - q31_t *pIn1 = &pSrc[0], *pIn2 = &pSrc[(2u * fftLen) + 1u]; - - pCoefA = &pATable[0]; - pCoefB = &pBTable[0]; - - while(fftLen > 0u) - { - /* - outR = (pIn[2 * i] * pATable[2 * i] + pIn[2 * i + 1] * pATable[2 * i + 1] + - pIn[2 * n - 2 * i] * pBTable[2 * i] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1]); - - outI = (pIn[2 * i + 1] * pATable[2 * i] - pIn[2 * i] * pATable[2 * i + 1] - - pIn[2 * n - 2 * i] * pBTable[2 * i + 1] - - pIn[2 * n - 2 * i + 1] * pBTable[2 * i]); - - */ - CoefA1 = *pCoefA++; - CoefA2 = *pCoefA; - - /* outR = (pIn[2 * i] * pATable[2 * i] */ - outR = ((int32_t) (((q63_t) * pIn1 * CoefA1) >> 32)); - - /* - pIn[2 * i] * pATable[2 * i + 1] */ - outI = -((int32_t) (((q63_t) * pIn1++ * CoefA2) >> 32)); - - /* pIn[2 * i + 1] * pATable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn1 * (CoefA2))) >> 32); - - /* pIn[2 * i + 1] * pATable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn1++ * (CoefA1))) >> 32); - - /* pIn[2 * n - 2 * i] * pBTable[2 * i] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefA2))) >> 32); - - CoefB1 = *pCoefB; - - /* pIn[2 * n - 2 * i] * pBTable[2 * i + 1] */ - outI = - (q31_t) ((((q63_t) outI << 32) - ((q63_t) * pIn2-- * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i + 1] */ - outR = - (q31_t) ((((q63_t) outR << 32) + ((q63_t) * pIn2 * (CoefB1))) >> 32); - - /* pIn[2 * n - 2 * i + 1] * pBTable[2 * i] */ - outI = - (q31_t) ((((q63_t) outI << 32) + ((q63_t) * pIn2-- * (CoefA2))) >> 32); - - /* write output */ - *pDst++ = (outR << 1u); - *pDst++ = (outI << 1u); - - /* update coefficient pointer */ - pCoefB = pCoefB + (modifier * 2u); - pCoefA = pCoefA + ((modifier * 2u) - 1u); - - /* Decrement loop count */ - fftLen--; - - } - - -} diff --git a/src/modules/mathlib/CMSIS/Include/arm_common_tables.h b/src/modules/mathlib/CMSIS/Include/arm_common_tables.h index 5fd6ff4af9..9c37ab4e5a 100644 --- a/src/modules/mathlib/CMSIS/Include/arm_common_tables.h +++ b/src/modules/mathlib/CMSIS/Include/arm_common_tables.h @@ -1,24 +1,41 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010 ARM Limited. All rights reserved. -* -* $Date: 11. November 2010 -* $Revision: V1.0.2 -* -* Project: CMSIS DSP Library -* Title: arm_common_tables.h -* -* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions -* +/* ---------------------------------------------------------------------- +* Copyright (C) 2010-2013 ARM Limited. All rights reserved. +* +* $Date: 17. January 2013 +* $Revision: V1.4.1 +* +* Project: CMSIS DSP Library +* Title: arm_common_tables.h +* +* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions +* * Target Processor: Cortex-M4/Cortex-M3 -* -* Version 1.0.2 2010/11/11 -* Documentation updated. -* -* Version 1.0.1 2010/10/05 -* Production release and review comments incorporated. -* -* Version 1.0.0 2010/09/20 -* Production release and review comments incorporated. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* - Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* - Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in +* the documentation and/or other materials provided with the +* distribution. +* - Neither the name of ARM LIMITED nor the names of its contributors +* may be used to endorse or promote products derived from this +* software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. * -------------------------------------------------------------------- */ #ifndef _ARM_COMMON_TABLES_H @@ -31,8 +48,46 @@ extern const q15_t armRecipTableQ15[64]; extern const q31_t armRecipTableQ31[64]; extern const q31_t realCoefAQ31[1024]; extern const q31_t realCoefBQ31[1024]; -extern const float32_t twiddleCoef[6144]; +extern const float32_t twiddleCoef_16[32]; +extern const float32_t twiddleCoef_32[64]; +extern const float32_t twiddleCoef_64[128]; +extern const float32_t twiddleCoef_128[256]; +extern const float32_t twiddleCoef_256[512]; +extern const float32_t twiddleCoef_512[1024]; +extern const float32_t twiddleCoef_1024[2048]; +extern const float32_t twiddleCoef_2048[4096]; +extern const float32_t twiddleCoef_4096[8192]; +#define twiddleCoef twiddleCoef_4096 extern const q31_t twiddleCoefQ31[6144]; extern const q15_t twiddleCoefQ15[6144]; +extern const float32_t twiddleCoef_rfft_32[32]; +extern const float32_t twiddleCoef_rfft_64[64]; +extern const float32_t twiddleCoef_rfft_128[128]; +extern const float32_t twiddleCoef_rfft_256[256]; +extern const float32_t twiddleCoef_rfft_512[512]; +extern const float32_t twiddleCoef_rfft_1024[1024]; +extern const float32_t twiddleCoef_rfft_2048[2048]; +extern const float32_t twiddleCoef_rfft_4096[4096]; + + +#define ARMBITREVINDEXTABLE__16_TABLE_LENGTH ((uint16_t)20 ) +#define ARMBITREVINDEXTABLE__32_TABLE_LENGTH ((uint16_t)48 ) +#define ARMBITREVINDEXTABLE__64_TABLE_LENGTH ((uint16_t)56 ) +#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208 ) +#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440 ) +#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448 ) +#define ARMBITREVINDEXTABLE1024_TABLE_LENGTH ((uint16_t)1800) +#define ARMBITREVINDEXTABLE2048_TABLE_LENGTH ((uint16_t)3808) +#define ARMBITREVINDEXTABLE4096_TABLE_LENGTH ((uint16_t)4032) + +extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE__16_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE__32_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE__64_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE1024_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE2048_TABLE_LENGTH]; +extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE4096_TABLE_LENGTH]; #endif /* ARM_COMMON_TABLES_H */ diff --git a/src/modules/mathlib/CMSIS/Include/arm_const_structs.h b/src/modules/mathlib/CMSIS/Include/arm_const_structs.h new file mode 100644 index 0000000000..406f737dcc --- /dev/null +++ b/src/modules/mathlib/CMSIS/Include/arm_const_structs.h @@ -0,0 +1,85 @@ +/* ---------------------------------------------------------------------- +* Copyright (C) 2010-2013 ARM Limited. All rights reserved. +* +* $Date: 17. January 2013 +* $Revision: V1.4.1 +* +* Project: CMSIS DSP Library +* Title: arm_const_structs.h +* +* Description: This file has constant structs that are initialized for +* user convenience. For example, some can be given as +* arguments to the arm_cfft_f32() function. +* +* Target Processor: Cortex-M4/Cortex-M3 +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* - Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* - Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in +* the documentation and/or other materials provided with the +* distribution. +* - Neither the name of ARM LIMITED nor the names of its contributors +* may be used to endorse or promote products derived from this +* software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +* -------------------------------------------------------------------- */ + +#ifndef _ARM_CONST_STRUCTS_H +#define _ARM_CONST_STRUCTS_H + +#include "arm_math.h" +#include "arm_common_tables.h" + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len16 = { + 16, twiddleCoef_16, armBitRevIndexTable16, ARMBITREVINDEXTABLE__16_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len32 = { + 32, twiddleCoef_32, armBitRevIndexTable32, ARMBITREVINDEXTABLE__32_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len64 = { + 64, twiddleCoef_64, armBitRevIndexTable64, ARMBITREVINDEXTABLE__64_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len128 = { + 128, twiddleCoef_128, armBitRevIndexTable128, ARMBITREVINDEXTABLE_128_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len256 = { + 256, twiddleCoef_256, armBitRevIndexTable256, ARMBITREVINDEXTABLE_256_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len512 = { + 512, twiddleCoef_512, armBitRevIndexTable512, ARMBITREVINDEXTABLE_512_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024 = { + 1024, twiddleCoef_1024, armBitRevIndexTable1024, ARMBITREVINDEXTABLE1024_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048 = { + 2048, twiddleCoef_2048, armBitRevIndexTable2048, ARMBITREVINDEXTABLE2048_TABLE_LENGTH + }; + + const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096 = { + 4096, twiddleCoef_4096, armBitRevIndexTable4096, ARMBITREVINDEXTABLE4096_TABLE_LENGTH + }; + +#endif diff --git a/src/modules/mathlib/CMSIS/Include/arm_math.h b/src/modules/mathlib/CMSIS/Include/arm_math.h index f224d3eb03..6f66f9ee3e 100644 --- a/src/modules/mathlib/CMSIS/Include/arm_math.h +++ b/src/modules/mathlib/CMSIS/Include/arm_math.h @@ -1,33 +1,41 @@ -/* ---------------------------------------------------------------------- - * Copyright (C) 2010-2011 ARM Limited. All rights reserved. - * - * $Date: 15. February 2012 - * $Revision: V1.1.0 - * - * Project: CMSIS DSP Library - * Title: arm_math.h - * - * Description: Public header file for CMSIS DSP Library - * - * Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 - * - * Version 1.1.0 2012/02/15 - * Updated with more optimizations, bug fixes and minor API changes. - * - * Version 1.0.10 2011/7/15 - * Big Endian support added and Merged M0 and M3/M4 Source code. - * - * Version 1.0.3 2010/11/29 - * Re-organized the CMSIS folders and updated documentation. - * - * Version 1.0.2 2010/11/11 - * Documentation updated. - * - * Version 1.0.1 2010/10/05 - * Production release and review comments incorporated. - * - * Version 1.0.0 2010/09/20 - * Production release and review comments incorporated. +/* ---------------------------------------------------------------------- +* Copyright (C) 2010-2013 ARM Limited. All rights reserved. +* +* $Date: 17. January 2013 +* $Revision: V1.4.1 +* +* Project: CMSIS DSP Library +* Title: arm_math.h +* +* Description: Public header file for CMSIS DSP Library +* +* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0 +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* - Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* - Redistributions in binary form must reproduce the above copyright +* notice, this list of conditions and the following disclaimer in +* the documentation and/or other materials provided with the +* distribution. +* - Neither the name of ARM LIMITED nor the names of its contributors +* may be used to endorse or promote products derived from this +* software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. * -------------------------------------------------------------------- */ /** @@ -35,10 +43,10 @@ * * Introduction * - * This user manual describes the CMSIS DSP software library, + * This user manual describes the CMSIS DSP software library, * a suite of common signal processing functions for use on Cortex-M processor based devices. * - * The library is divided into a number of functions each covering a specific category: + * The library is divided into a number of functions each covering a specific category: * - Basic math functions * - Fast math functions * - Complex math functions @@ -51,41 +59,7 @@ * - Interpolation functions * * The library has separate functions for operating on 8-bit integers, 16-bit integers, - * 32-bit integer and 32-bit floating-point values. - * - * Pre-processor Macros - * - * Each library project have differant pre-processor macros. - * - * - UNALIGNED_SUPPORT_DISABLE: - * - * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access - * - * - ARM_MATH_BIG_ENDIAN: - * - * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. - * - * - ARM_MATH_MATRIX_CHECK: - * - * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices - * - * - ARM_MATH_ROUNDING: - * - * Define macro ARM_MATH_ROUNDING for rounding on support functions - * - * - ARM_MATH_CMx: - * - * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target - * and ARM_MATH_CM0 for building library on cortex-M0 target. - * - * - __FPU_PRESENT: - * - * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries - * - * Toolchain Support - * - * The library has been developed and tested with MDK-ARM version 4.23. - * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. + * 32-bit integer and 32-bit floating-point values. * * Using the Library * @@ -100,33 +74,67 @@ * - arm_cortexM0b_math.lib (Big endian on Cortex-M3) * * The library functions are declared in the public file arm_math.h which is placed in the Include folder. - * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single - * public header file arm_math.h for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. - * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or - * ARM_MATH_CM0 depending on the target processor in the application. + * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single + * public header file arm_math.h for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. + * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or + * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application. * * Examples * * The library ships with a number of examples which demonstrate how to use the library functions. * + * Toolchain Support + * + * The library has been developed and tested with MDK-ARM version 4.60. + * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. + * * Building the Library * * The library installer contains project files to re build libraries on MDK Tool chain in the CMSIS\\DSP_Lib\\Source\\ARM folder. * - arm_cortexM0b_math.uvproj * - arm_cortexM0l_math.uvproj * - arm_cortexM3b_math.uvproj - * - arm_cortexM3l_math.uvproj + * - arm_cortexM3l_math.uvproj * - arm_cortexM4b_math.uvproj * - arm_cortexM4l_math.uvproj * - arm_cortexM4bf_math.uvproj * - arm_cortexM4lf_math.uvproj * * - * The project can be built by opening the appropriate project in MDK-ARM 4.23 chain and defining the optional pre processor MACROs detailed above. + * The project can be built by opening the appropriate project in MDK-ARM 4.60 chain and defining the optional pre processor MACROs detailed above. + * + * Pre-processor Macros + * + * Each library project have differant pre-processor macros. + * + * - UNALIGNED_SUPPORT_DISABLE: + * + * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access + * + * - ARM_MATH_BIG_ENDIAN: + * + * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. + * + * - ARM_MATH_MATRIX_CHECK: + * + * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices + * + * - ARM_MATH_ROUNDING: + * + * Define macro ARM_MATH_ROUNDING for rounding on support functions + * + * - ARM_MATH_CMx: + * + * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target + * and ARM_MATH_CM0 for building library on cortex-M0 target, ARM_MATH_CM0PLUS for building library on cortex-M0+ target. + * + * - __FPU_PRESENT: + * + * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries * * Copyright Notice * - * Copyright (C) 2010 ARM Limited. All rights reserved. + * Copyright (C) 2010-2013 ARM Limited. All rights reserved. */ @@ -258,7 +266,7 @@ #define __CMSIS_GENERIC /* disable NVIC and Systick functions */ -/* NuttX */ +/* PX4 */ #include #ifdef CONFIG_ARCH_CORTEXM4 # define ARM_MATH_CM4 1 @@ -276,6 +284,10 @@ #include "core_cm3.h" #elif defined (ARM_MATH_CM0) #include "core_cm0.h" +#define ARM_MATH_CM0_FAMILY +#elif defined (ARM_MATH_CM0PLUS) +#include "core_cm0plus.h" +#define ARM_MATH_CM0_FAMILY #else #include "ARMCM4.h" #warning "Define either ARM_MATH_CM4 OR ARM_MATH_CM3...By Default building on ARM_MATH_CM4....." @@ -377,17 +389,27 @@ extern "C" /** * @brief definition to read/write two 16 bit values. */ -#if defined (__GNUC__) - #define __SIMD32(addr) (*( int32_t **) & (addr)) - #define _SIMD32_OFFSET(addr) (*( int32_t * ) (addr)) +#if defined __CC_ARM +#define __SIMD32_TYPE int32_t __packed +#define CMSIS_UNUSED __attribute__((unused)) +#elif defined __ICCARM__ +#define CMSIS_UNUSED +#define __SIMD32_TYPE int32_t __packed +#elif defined __GNUC__ +#define __SIMD32_TYPE int32_t +#define CMSIS_UNUSED __attribute__((unused)) #else - #define __SIMD32(addr) (*(__packed int32_t **) & (addr)) - #define _SIMD32_OFFSET(addr) (*(__packed int32_t * ) (addr)) -#endif +#error Unknown compiler +#endif - #define __SIMD64(addr) (*(int64_t **) & (addr)) +#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) +#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr)) -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0) +#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr)) + +#define __SIMD64(addr) (*(int64_t **) & (addr)) + +#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) /** * @brief definition to pack two 16 bit values. */ @@ -421,7 +443,7 @@ extern "C" /** * @brief Clips Q63 to Q31 values. */ - __STATIC_INLINE q31_t clip_q63_to_q31( + static __INLINE q31_t clip_q63_to_q31( q63_t x) { return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? @@ -431,7 +453,7 @@ extern "C" /** * @brief Clips Q63 to Q15 values. */ - __STATIC_INLINE q15_t clip_q63_to_q15( + static __INLINE q15_t clip_q63_to_q15( q63_t x) { return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? @@ -441,7 +463,7 @@ extern "C" /** * @brief Clips Q31 to Q7 values. */ - __STATIC_INLINE q7_t clip_q31_to_q7( + static __INLINE q7_t clip_q31_to_q7( q31_t x) { return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? @@ -451,7 +473,7 @@ extern "C" /** * @brief Clips Q31 to Q15 values. */ - __STATIC_INLINE q15_t clip_q31_to_q15( + static __INLINE q15_t clip_q31_to_q15( q31_t x) { return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? @@ -462,7 +484,7 @@ extern "C" * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. */ - __STATIC_INLINE q63_t mult32x64( + static __INLINE q63_t mult32x64( q63_t x, q31_t y) { @@ -471,20 +493,18 @@ extern "C" } -#if defined (ARM_MATH_CM0) && defined ( __CC_ARM ) +#if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM ) #define __CLZ __clz #endif -#if defined (ARM_MATH_CM0) && defined ( __TASKING__ ) -/* No need to redefine __CLZ */ -#endif +#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) || defined (__TASKING__) ) -#if defined (ARM_MATH_CM0) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) ) - - __STATIC_INLINE uint32_t __CLZ(q31_t data); + static __INLINE uint32_t __CLZ( + q31_t data); - __STATIC_INLINE uint32_t __CLZ(q31_t data) + static __INLINE uint32_t __CLZ( + q31_t data) { uint32_t count = 0; uint32_t mask = 0x80000000; @@ -502,10 +522,10 @@ extern "C" #endif /** - * @brief Function to Calculates 1/in(reciprocal) value of Q31 Data type. + * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type. */ - __STATIC_INLINE uint32_t arm_recip_q31( + static __INLINE uint32_t arm_recip_q31( q31_t in, q31_t * dst, q31_t * pRecipTable) @@ -554,9 +574,9 @@ extern "C" } /** - * @brief Function to Calculates 1/in(reciprocal) value of Q15 Data type. + * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type. */ - __STATIC_INLINE uint32_t arm_recip_q15( + static __INLINE uint32_t arm_recip_q15( q15_t in, q15_t * dst, q15_t * pRecipTable) @@ -607,9 +627,9 @@ extern "C" /* * @brief C custom defined intrinisic function for only M0 processors */ -#if defined(ARM_MATH_CM0) +#if defined(ARM_MATH_CM0_FAMILY) - __STATIC_INLINE q31_t __SSAT( + static __INLINE q31_t __SSAT( q31_t x, uint32_t y) { @@ -645,19 +665,19 @@ extern "C" } -#endif /* end of ARM_MATH_CM0 */ +#endif /* end of ARM_MATH_CM0_FAMILY */ /* * @brief C custom defined intrinsic function for M3 and M0 processors */ -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0) +#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) /* * @brief C custom defined QADD8 for M3 and M0 processors */ - __STATIC_INLINE q31_t __QADD8( + static __INLINE q31_t __QADD8( q31_t x, q31_t y) { @@ -684,7 +704,7 @@ extern "C" /* * @brief C custom defined QSUB8 for M3 and M0 processors */ - __STATIC_INLINE q31_t __QSUB8( + static __INLINE q31_t __QSUB8( q31_t x, q31_t y) { @@ -714,7 +734,7 @@ extern "C" /* * @brief C custom defined QADD16 for M3 and M0 processors */ - __STATIC_INLINE q31_t __QADD16( + static __INLINE q31_t __QADD16( q31_t x, q31_t y) { @@ -737,7 +757,7 @@ extern "C" /* * @brief C custom defined SHADD16 for M3 and M0 processors */ - __STATIC_INLINE q31_t __SHADD16( + static __INLINE q31_t __SHADD16( q31_t x, q31_t y) { @@ -760,7 +780,7 @@ extern "C" /* * @brief C custom defined QSUB16 for M3 and M0 processors */ - __STATIC_INLINE q31_t __QSUB16( + static __INLINE q31_t __QSUB16( q31_t x, q31_t y) { @@ -782,7 +802,7 @@ extern "C" /* * @brief C custom defined SHSUB16 for M3 and M0 processors */ - __STATIC_INLINE q31_t __SHSUB16( + static __INLINE q31_t __SHSUB16( q31_t x, q31_t y) { @@ -804,7 +824,7 @@ extern "C" /* * @brief C custom defined QASX for M3 and M0 processors */ - __STATIC_INLINE q31_t __QASX( + static __INLINE q31_t __QASX( q31_t x, q31_t y) { @@ -822,7 +842,7 @@ extern "C" /* * @brief C custom defined SHASX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SHASX( + static __INLINE q31_t __SHASX( q31_t x, q31_t y) { @@ -845,7 +865,7 @@ extern "C" /* * @brief C custom defined QSAX for M3 and M0 processors */ - __STATIC_INLINE q31_t __QSAX( + static __INLINE q31_t __QSAX( q31_t x, q31_t y) { @@ -863,7 +883,7 @@ extern "C" /* * @brief C custom defined SHSAX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SHSAX( + static __INLINE q31_t __SHSAX( q31_t x, q31_t y) { @@ -885,7 +905,7 @@ extern "C" /* * @brief C custom defined SMUSDX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMUSDX( + static __INLINE q31_t __SMUSDX( q31_t x, q31_t y) { @@ -897,7 +917,7 @@ extern "C" /* * @brief C custom defined SMUADX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMUADX( + static __INLINE q31_t __SMUADX( q31_t x, q31_t y) { @@ -909,7 +929,7 @@ extern "C" /* * @brief C custom defined QADD for M3 and M0 processors */ - __STATIC_INLINE q31_t __QADD( + static __INLINE q31_t __QADD( q31_t x, q31_t y) { @@ -919,7 +939,7 @@ extern "C" /* * @brief C custom defined QSUB for M3 and M0 processors */ - __STATIC_INLINE q31_t __QSUB( + static __INLINE q31_t __QSUB( q31_t x, q31_t y) { @@ -929,7 +949,7 @@ extern "C" /* * @brief C custom defined SMLAD for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMLAD( + static __INLINE q31_t __SMLAD( q31_t x, q31_t y, q31_t sum) @@ -942,7 +962,7 @@ extern "C" /* * @brief C custom defined SMLADX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMLADX( + static __INLINE q31_t __SMLADX( q31_t x, q31_t y, q31_t sum) @@ -955,7 +975,7 @@ extern "C" /* * @brief C custom defined SMLSDX for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMLSDX( + static __INLINE q31_t __SMLSDX( q31_t x, q31_t y, q31_t sum) @@ -968,7 +988,7 @@ extern "C" /* * @brief C custom defined SMLALD for M3 and M0 processors */ - __STATIC_INLINE q63_t __SMLALD( + static __INLINE q63_t __SMLALD( q31_t x, q31_t y, q63_t sum) @@ -981,7 +1001,7 @@ extern "C" /* * @brief C custom defined SMLALDX for M3 and M0 processors */ - __STATIC_INLINE q63_t __SMLALDX( + static __INLINE q63_t __SMLALDX( q31_t x, q31_t y, q63_t sum) @@ -994,7 +1014,7 @@ extern "C" /* * @brief C custom defined SMUAD for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMUAD( + static __INLINE q31_t __SMUAD( q31_t x, q31_t y) { @@ -1006,7 +1026,7 @@ extern "C" /* * @brief C custom defined SMUSD for M3 and M0 processors */ - __STATIC_INLINE q31_t __SMUSD( + static __INLINE q31_t __SMUSD( q31_t x, q31_t y) { @@ -1019,7 +1039,7 @@ extern "C" /* * @brief C custom defined SXTB16 for M3 and M0 processors */ - __STATIC_INLINE q31_t __SXTB16( + static __INLINE q31_t __SXTB16( q31_t x) { @@ -1028,7 +1048,7 @@ extern "C" } -#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0) */ +#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) */ /** @@ -1528,6 +1548,7 @@ extern "C" * @param[in] *pSrcA points to the first input matrix structure * @param[in] *pSrcB points to the second input matrix structure * @param[out] *pDst points to output matrix structure + * @param[in] *pState points to the array for storing intermediate results * @return The function returns either * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. */ @@ -1543,7 +1564,7 @@ extern "C" * @param[in] *pSrcA points to the first input matrix structure * @param[in] *pSrcB points to the second input matrix structure * @param[out] *pDst points to output matrix structure - * @param[in] *pState points to the array for storing intermediate results + * @param[in] *pState points to the array for storing intermediate results * @return The function returns either * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. */ @@ -1725,7 +1746,7 @@ extern "C" typedef struct { q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ -#ifdef ARM_MATH_CM0 +#ifdef ARM_MATH_CM0_FAMILY q15_t A1; q15_t A2; #else @@ -1943,52 +1964,8 @@ extern "C" uint32_t blockSize); - /** - * @brief Instance structure for the Q15 CFFT/CIFFT function. - */ - - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q15_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q15; - - /** - * @brief Instance structure for the Q31 CFFT/CIFFT function. - */ - - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q31_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q31; - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - float32_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - float32_t onebyfftLen; /**< value of 1/fftLen. */ - } arm_cfft_radix4_instance_f32; /** @@ -2006,6 +1983,43 @@ extern "C" uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ } arm_cfft_radix2_instance_q15; + arm_status arm_cfft_radix2_init_q15( + arm_cfft_radix2_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + void arm_cfft_radix2_q15( + const arm_cfft_radix2_instance_q15 * S, + q15_t * pSrc); + + + + /** + * @brief Instance structure for the Q15 CFFT/CIFFT function. + */ + + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + q15_t *pTwiddle; /**< points to the twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q15; + + arm_status arm_cfft_radix4_init_q15( + arm_cfft_radix4_instance_q15 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + void arm_cfft_radix4_q15( + const arm_cfft_radix4_instance_q15 * S, + q15_t * pSrc); + /** * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function. */ @@ -2021,6 +2035,42 @@ extern "C" uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ } arm_cfft_radix2_instance_q31; + arm_status arm_cfft_radix2_init_q31( + arm_cfft_radix2_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + + void arm_cfft_radix2_q31( + const arm_cfft_radix2_instance_q31 * S, + q31_t * pSrc); + + /** + * @brief Instance structure for the Q31 CFFT/CIFFT function. + */ + + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + q31_t *pTwiddle; /**< points to the twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + } arm_cfft_radix4_instance_q31; + + + void arm_cfft_radix4_q31( + const arm_cfft_radix4_instance_q31 * S, + q31_t * pSrc); + + arm_status arm_cfft_radix4_init_q31( + arm_cfft_radix4_instance_q31 * S, + uint16_t fftLen, + uint8_t ifftFlag, + uint8_t bitReverseFlag); + /** * @brief Instance structure for the floating-point CFFT/CIFFT function. */ @@ -2037,401 +2087,63 @@ extern "C" float32_t onebyfftLen; /**< value of 1/fftLen. */ } arm_cfft_radix2_instance_f32; - - /** - * @brief Processing function for the Q15 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix4_q15( - const arm_cfft_radix4_instance_q15 * S, - q15_t * pSrc); - - /** - * @brief Processing function for the Q15 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix2_q15( - const arm_cfft_radix2_instance_q15 * S, - q15_t * pSrc); - - /** - * @brief Initialization function for the Q15 CFFT/CIFFT. - * @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. - */ - - arm_status arm_cfft_radix4_init_q15( - arm_cfft_radix4_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Initialization function for the Q15 CFFT/CIFFT. - * @param[in,out] *S points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. - */ - - arm_status arm_cfft_radix2_init_q15( - arm_cfft_radix2_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Processing function for the Q31 CFFT/CIFFT. - * @param[in] *S points to an instance of the Q31 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix4_q31( - const arm_cfft_radix4_instance_q31 * S, - q31_t * pSrc); - - /** - * @brief Initialization function for the Q31 CFFT/CIFFT. - * @param[in,out] *S points to an instance of the Q31 CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. - */ - - arm_status arm_cfft_radix4_init_q31( - arm_cfft_radix4_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Processing function for the Radix-2 Q31 CFFT/CIFFT. - * @param[in] *S points to an instance of the Radix-2 Q31 CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix2_q31( - const arm_cfft_radix2_instance_q31 * S, - q31_t * pSrc); - - /** - * @brief Initialization function for the Radix-2 Q31 CFFT/CIFFT. - * @param[in,out] *S points to an instance of the Radix-2 Q31 CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. - */ - - arm_status arm_cfft_radix2_init_q31( - arm_cfft_radix2_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - - - /** - * @brief Processing function for the floating-point CFFT/CIFFT. - * @param[in] *S points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix2_f32( - const arm_cfft_radix2_instance_f32 * S, - float32_t * pSrc); - - /** - * @brief Initialization function for the floating-point CFFT/CIFFT. - * @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. - */ - +/* Deprecated */ arm_status arm_cfft_radix2_init_f32( arm_cfft_radix2_instance_f32 * S, uint16_t fftLen, uint8_t ifftFlag, uint8_t bitReverseFlag); - /** - * @brief Processing function for the floating-point CFFT/CIFFT. - * @param[in] *S points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in, out] *pSrc points to the complex data buffer. Processing occurs in-place. - * @return none. - */ - - void arm_cfft_radix4_f32( - const arm_cfft_radix4_instance_f32 * S, +/* Deprecated */ + void arm_cfft_radix2_f32( + const arm_cfft_radix2_instance_f32 * S, float32_t * pSrc); /** - * @brief Initialization function for the floating-point CFFT/CIFFT. - * @param[in,out] *S points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in] fftLen length of the FFT. - * @param[in] ifftFlag flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLen is not a supported value. + * @brief Instance structure for the floating-point CFFT/CIFFT function. */ + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ + uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ + float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ + uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ + float32_t onebyfftLen; /**< value of 1/fftLen. */ + } arm_cfft_radix4_instance_f32; + +/* Deprecated */ arm_status arm_cfft_radix4_init_f32( arm_cfft_radix4_instance_f32 * S, uint16_t fftLen, uint8_t ifftFlag, uint8_t bitReverseFlag); - - - /*---------------------------------------------------------------------- - * Internal functions prototypes FFT function - ----------------------------------------------------------------------*/ +/* Deprecated */ + void arm_cfft_radix4_f32( + const arm_cfft_radix4_instance_f32 * S, + float32_t * pSrc); /** - * @brief Core function for the floating-point CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to the twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. + * @brief Instance structure for the floating-point CFFT/CIFFT function. */ - void arm_radix4_butterfly_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the floating-point CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @param[in] onebyfftLen value of 1/fftLen. - * @return none. - */ - - void arm_radix4_butterfly_inverse_f32( - float32_t * pSrc, - uint16_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier, - float32_t onebyfftLen); - - /** - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of floating-point data type. - * @param[in] fftSize length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table. - * @param[in] *pBitRevTab points to the bit reversal table. - * @return none. - */ - - void arm_bitreversal_f32( - float32_t * pSrc, - uint16_t fftSize, - uint16_t bitRevFactor, - uint16_t * pBitRevTab); - - /** - * @brief Core function for the Q31 CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix4_butterfly_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier); - - /** - * @brief Core function for the f32 FFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of f32 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix2_butterfly_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the Radix-2 Q31 CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix2_butterfly_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the Radix-2 Q15 CFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix2_butterfly_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the Radix-2 Q15 CFFT Inverse butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix2_butterfly_inverse_q15( - q15_t * pSrc, - uint32_t fftLen, - q15_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the Radix-2 Q31 CFFT Inverse butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix2_butterfly_inverse_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint16_t twidCoefModifier); - - /** - * @brief Core function for the f32 IFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of f32 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to Twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @param[in] onebyfftLen 1/fftLenfth - * @return none. - */ - - void arm_radix2_butterfly_inverse_f32( - float32_t * pSrc, - uint32_t fftLen, - float32_t * pCoef, - uint16_t twidCoefModifier, - float32_t onebyfftLen); - - /** - * @brief Core function for the Q31 CIFFT butterfly process. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix4_butterfly_inverse_q31( - q31_t * pSrc, - uint32_t fftLen, - q31_t * pCoef, - uint32_t twidCoefModifier); - - /** - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q31 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - - void arm_bitreversal_q31( - q31_t * pSrc, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTab); - - /** - * @brief Core function for the Q15 CFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix4_butterfly_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier); - - - /** - * @brief Core function for the Q15 CIFFT butterfly process. - * @param[in, out] *pSrc16 points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] *pCoef16 points to twiddle coefficient buffer. - * @param[in] twidCoefModifier twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. - * @return none. - */ - - void arm_radix4_butterfly_inverse_q15( - q15_t * pSrc16, - uint32_t fftLen, - q15_t * pCoef16, - uint32_t twidCoefModifier); - - /** - * @brief In-place bit reversal function. - * @param[in, out] *pSrc points to the in-place buffer of Q15 data type. - * @param[in] fftLen length of the FFT. - * @param[in] bitRevFactor bit reversal modifier that supports different size FFTs with the same bit reversal table - * @param[in] *pBitRevTab points to bit reversal table. - * @return none. - */ - - void arm_bitreversal_q15( - q15_t * pSrc, - uint32_t fftLen, - uint16_t bitRevFactor, - uint16_t * pBitRevTab); + typedef struct + { + uint16_t fftLen; /**< length of the FFT. */ + const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ + const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ + uint16_t bitRevLength; /**< bit reversal table length. */ + } arm_cfft_instance_f32; + void arm_cfft_f32( + const arm_cfft_instance_f32 * S, + float32_t * p1, + uint8_t ifftFlag, + uint8_t bitReverseFlag); /** * @brief Instance structure for the Q15 RFFT/RIFFT function. @@ -2449,6 +2161,18 @@ extern "C" arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ } arm_rfft_instance_q15; + arm_status arm_rfft_init_q15( + arm_rfft_instance_q15 * S, + arm_cfft_radix4_instance_q15 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q15( + const arm_rfft_instance_q15 * S, + q15_t * pSrc, + q15_t * pDst); + /** * @brief Instance structure for the Q31 RFFT/RIFFT function. */ @@ -2465,6 +2189,18 @@ extern "C" arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ } arm_rfft_instance_q31; + arm_status arm_rfft_init_q31( + arm_rfft_instance_q31 * S, + arm_cfft_radix4_instance_q31 * S_CFFT, + uint32_t fftLenReal, + uint32_t ifftFlagR, + uint32_t bitReverseFlag); + + void arm_rfft_q31( + const arm_rfft_instance_q31 * S, + q31_t * pSrc, + q31_t * pDst); + /** * @brief Instance structure for the floating-point RFFT/RIFFT function. */ @@ -2481,76 +2217,6 @@ extern "C" arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ } arm_rfft_instance_f32; - /** - * @brief Processing function for the Q15 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q15 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - */ - - void arm_rfft_q15( - const arm_rfft_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst); - - /** - * @brief Initialization function for the Q15 RFFT/RIFFT. - * @param[in, out] *S points to an instance of the Q15 RFFT/RIFFT structure. - * @param[in] *S_CFFT points to an instance of the Q15 CFFT/CIFFT structure. - * @param[in] fftLenReal length of the FFT. - * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. - */ - - arm_status arm_rfft_init_q15( - arm_rfft_instance_q15 * S, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - /** - * @brief Processing function for the Q31 RFFT/RIFFT. - * @param[in] *S points to an instance of the Q31 RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - */ - - void arm_rfft_q31( - const arm_rfft_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst); - - /** - * @brief Initialization function for the Q31 RFFT/RIFFT. - * @param[in, out] *S points to an instance of the Q31 RFFT/RIFFT structure. - * @param[in, out] *S_CFFT points to an instance of the Q31 CFFT/CIFFT structure. - * @param[in] fftLenReal length of the FFT. - * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. - */ - - arm_status arm_rfft_init_q31( - arm_rfft_instance_q31 * S, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - /** - * @brief Initialization function for the floating-point RFFT/RIFFT. - * @param[in,out] *S points to an instance of the floating-point RFFT/RIFFT structure. - * @param[in,out] *S_CFFT points to an instance of the floating-point CFFT/CIFFT structure. - * @param[in] fftLenReal length of the FFT. - * @param[in] ifftFlagR flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. - * @param[in] bitReverseFlag flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported value. - */ - arm_status arm_rfft_init_f32( arm_rfft_instance_f32 * S, arm_cfft_radix4_instance_f32 * S_CFFT, @@ -2558,19 +2224,31 @@ extern "C" uint32_t ifftFlagR, uint32_t bitReverseFlag); - /** - * @brief Processing function for the floating-point RFFT/RIFFT. - * @param[in] *S points to an instance of the floating-point RFFT/RIFFT structure. - * @param[in] *pSrc points to the input buffer. - * @param[out] *pDst points to the output buffer. - * @return none. - */ - void arm_rfft_f32( const arm_rfft_instance_f32 * S, float32_t * pSrc, float32_t * pDst); + /** + * @brief Instance structure for the floating-point RFFT/RIFFT function. + */ + +typedef struct + { + arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */ + uint16_t fftLenRFFT; /**< length of the real sequence */ + float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */ + } arm_rfft_fast_instance_f32 ; + +arm_status arm_rfft_fast_init_f32 ( + arm_rfft_fast_instance_f32 * S, + uint16_t fftLen); + +void arm_rfft_fast_f32( + arm_rfft_fast_instance_f32 * S, + float32_t * p, float32_t * pOut, + uint8_t ifftFlag); + /** * @brief Instance structure for the floating-point DCT4/IDCT4 function. */ @@ -3167,7 +2845,7 @@ extern "C" q31_t * pDst, uint32_t blockSize); /** - * @brief Copies the elements of a floating-point vector. + * @brief Copies the elements of a floating-point vector. * @param[in] *pSrc input pointer * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3179,7 +2857,7 @@ extern "C" uint32_t blockSize); /** - * @brief Copies the elements of a Q7 vector. + * @brief Copies the elements of a Q7 vector. * @param[in] *pSrc input pointer * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3191,7 +2869,7 @@ extern "C" uint32_t blockSize); /** - * @brief Copies the elements of a Q15 vector. + * @brief Copies the elements of a Q15 vector. * @param[in] *pSrc input pointer * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3203,7 +2881,7 @@ extern "C" uint32_t blockSize); /** - * @brief Copies the elements of a Q31 vector. + * @brief Copies the elements of a Q31 vector. * @param[in] *pSrc input pointer * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3214,7 +2892,7 @@ extern "C" q31_t * pDst, uint32_t blockSize); /** - * @brief Fills a constant value into a floating-point vector. + * @brief Fills a constant value into a floating-point vector. * @param[in] value input value to be filled * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3226,7 +2904,7 @@ extern "C" uint32_t blockSize); /** - * @brief Fills a constant value into a Q7 vector. + * @brief Fills a constant value into a Q7 vector. * @param[in] value input value to be filled * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3238,7 +2916,7 @@ extern "C" uint32_t blockSize); /** - * @brief Fills a constant value into a Q15 vector. + * @brief Fills a constant value into a Q15 vector. * @param[in] value input value to be filled * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3250,7 +2928,7 @@ extern "C" uint32_t blockSize); /** - * @brief Fills a constant value into a Q31 vector. + * @brief Fills a constant value into a Q31 vector. * @param[in] value input value to be filled * @param[out] *pDst output pointer * @param[in] blockSize number of samples to process @@ -3261,14 +2939,14 @@ extern "C" q31_t * pDst, uint32_t blockSize); -/** - * @brief Convolution of floating-point sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. +/** + * @brief Convolution of floating-point sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. */ void arm_conv_f32( @@ -3278,17 +2956,17 @@ extern "C" uint32_t srcBLen, float32_t * pDst); - - /** - * @brief Convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return none. + + /** + * @brief Convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return none. */ @@ -3302,14 +2980,14 @@ extern "C" q15_t * pScratch2); -/** - * @brief Convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - * @return none. +/** + * @brief Convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1. + * @return none. */ void arm_conv_q15( @@ -3343,9 +3021,9 @@ extern "C" * @param[in] *pSrcB points to the second input sequence. * @param[in] srcBLen length of the second input sequence. * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return none. + * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return none. */ void arm_conv_fast_opt_q15( @@ -3394,16 +3072,16 @@ extern "C" q31_t * pDst); - /** - * @brief Convolution of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return none. + /** + * @brief Convolution of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1. + * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + * @return none. */ void arm_conv_opt_q7( @@ -3456,18 +3134,18 @@ extern "C" uint32_t firstIndex, uint32_t numPoints); - /** - * @brief Partial convolution of Q15 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + /** + * @brief Partial convolution of Q15 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. */ arm_status arm_conv_partial_opt_q15( @@ -3534,9 +3212,9 @@ extern "C" * @param[out] *pDst points to the block of output data * @param[in] firstIndex is the first output sample to start with. * @param[in] numPoints is the number of output points to be computed. - * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. */ arm_status arm_conv_partial_fast_opt_q15( @@ -3595,18 +3273,18 @@ extern "C" uint32_t numPoints); - /** - * @brief Partial convolution of Q7 sequences - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. + /** + * @brief Partial convolution of Q7 sequences + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data + * @param[in] firstIndex is the first output sample to start with. + * @param[in] numPoints is the number of output points to be computed. + * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. */ arm_status arm_conv_partial_opt_q7( @@ -4098,8 +3776,8 @@ extern "C" * @brief Initialization function for the Q15 FIR lattice filter. * @param[in] *S points to an instance of the Q15 FIR lattice structure. * @param[in] numStages number of filter stages. - * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] *pState points to the state buffer. The array is of length numStages. + * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages. + * @param[in] *pState points to the state buffer. The array is of length numStages. * @return none. */ @@ -4666,15 +4344,15 @@ extern "C" float32_t * pDst); - /** - * @brief Correlation of Q15 sequences - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @return none. + /** + * @brief Correlation of Q15 sequences + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @return none. */ void arm_correlate_opt_q15( q15_t * pSrcA, @@ -4728,7 +4406,7 @@ extern "C" * @param[in] *pSrcB points to the second input sequence. * @param[in] srcBLen length of the second input sequence. * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. * @return none. */ @@ -4776,16 +4454,16 @@ extern "C" - /** - * @brief Correlation of Q7 sequences. - * @param[in] *pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] *pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return none. + /** + * @brief Correlation of Q7 sequences. + * @param[in] *pSrcA points to the first input sequence. + * @param[in] srcALen length of the first input sequence. + * @param[in] *pSrcB points to the second input sequence. + * @param[in] srcBLen length of the second input sequence. + * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. + * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. + * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). + * @return none. */ void arm_correlate_opt_q7( @@ -5031,9 +4709,9 @@ extern "C" /* * @brief Floating-point sin_cos function. - * @param[in] theta input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cos output. + * @param[in] theta input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cos output. * @return none. */ @@ -5044,9 +4722,9 @@ extern "C" /* * @brief Q31 sin_cos function. - * @param[in] theta scaled input value in degrees - * @param[out] *pSinVal points to the processed sine output. - * @param[out] *pCosVal points to the processed cosine output. + * @param[in] theta scaled input value in degrees + * @param[out] *pSinVal points to the processed sine output. + * @param[out] *pCosVal points to the processed cosine output. * @return none. */ @@ -5144,7 +4822,7 @@ extern "C" /** * @defgroup PID PID Motor Control * - * A Proportional Integral Derivative (PID) controller is a generic feedback control + * A Proportional Integral Derivative (PID) controller is a generic feedback control * loop mechanism widely used in industrial control systems. * A PID controller is the most commonly used type of feedback controller. * @@ -5163,39 +4841,39 @@ extern "C" * * \par * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant - * - * \par - * \image html PID.gif "Proportional Integral Derivative Controller" + * + * \par + * \image html PID.gif "Proportional Integral Derivative Controller" * * \par * The PID controller calculates an "error" value as the difference between * the measured output and the reference input. - * The controller attempts to minimize the error by adjusting the process control inputs. - * The proportional value determines the reaction to the current error, - * the integral value determines the reaction based on the sum of recent errors, + * The controller attempts to minimize the error by adjusting the process control inputs. + * The proportional value determines the reaction to the current error, + * the integral value determines the reaction based on the sum of recent errors, * and the derivative value determines the reaction based on the rate at which the error has been changing. * - * \par Instance Structure - * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. - * A separate instance structure must be defined for each PID Controller. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Reset Functions - * There is also an associated reset function for each data type which clears the state array. + * \par Instance Structure + * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. + * A separate instance structure must be defined for each PID Controller. + * There are separate instance structure declarations for each of the 3 supported data types. * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: + * \par Reset Functions + * There is also an associated reset function for each data type which clears the state array. + * + * \par Initialization Functions + * There is also an associated initialization function for each data type. + * The initialization function performs the following operations: * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. - * - Zeros out the values in the state buffer. - * - * \par - * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * - Zeros out the values in the state buffer. * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the PID Controller functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. + * \par + * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. + * + * \par Fixed-Point Behavior + * Care must be taken when using the fixed-point versions of the PID Controller functions. + * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. + * Refer to the function specific documentation below for usage guidelines. */ /** @@ -5211,7 +4889,7 @@ extern "C" */ - __STATIC_INLINE float32_t arm_pid_f32( + static __INLINE float32_t arm_pid_f32( arm_pid_instance_f32 * S, float32_t in) { @@ -5237,16 +4915,16 @@ extern "C" * @param[in] in input sample to process * @return out processed output sample. * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. + * Scaling and Overflow Behavior: + * \par + * The function is implemented using an internal 64-bit accumulator. + * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. + * Thus, if the accumulator result overflows it wraps around rather than clip. + * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. + * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. */ - __STATIC_INLINE q31_t arm_pid_q31( + static __INLINE q31_t arm_pid_q31( arm_pid_instance_q31 * S, q31_t in) { @@ -5284,48 +4962,43 @@ extern "C" * @param[in] in input sample to process * @return out processed output sample. * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. + * Scaling and Overflow Behavior: + * \par + * The function is implemented using a 64-bit internal accumulator. + * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. + * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. + * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. + * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. * Lastly, the accumulator is saturated to yield a result in 1.15 format. */ - __STATIC_INLINE q15_t arm_pid_q15( + static __INLINE q15_t arm_pid_q15( arm_pid_instance_q15 * S, q15_t in) { q63_t acc; q15_t out; +#ifndef ARM_MATH_CM0_FAMILY + __SIMD32_TYPE *vstate; + /* Implementation of PID controller */ -#ifdef ARM_MATH_CM0 - - /* acc = A0 * x[n] */ - acc = ((q31_t) S->A0) * in; - -#else - /* acc = A0 * x[n] */ acc = (q31_t) __SMUAD(S->A0, in); -#endif + /* acc += A1 * x[n-1] + A2 * x[n-2] */ + vstate = __SIMD32_CONST(S->state); + acc = __SMLALD(S->A1, (q31_t) *vstate, acc); -#ifdef ARM_MATH_CM0 +#else + /* acc = A0 * x[n] */ + acc = ((q31_t) S->A0) * in; /* acc += A1 * x[n-1] + A2 * x[n-2] */ acc += (q31_t) S->A1 * S->state[0]; acc += (q31_t) S->A2 * S->state[1]; -#else - - /* acc += A1 * x[n-1] + A2 * x[n-2] */ - acc = __SMLALD(S->A1, (q31_t) __SIMD32(S->state), acc); - #endif /* acc += y[n-1] */ @@ -5378,7 +5051,7 @@ extern "C" * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta * can be calculated using only Ia and Ib. * - * The function operates on a single sample of data and each call to the function returns the processed output. + * The function operates on a single sample of data and each call to the function returns the processed output. * The library provides separate functions for Q31 and floating-point data types. * \par Algorithm * \image html clarkeFormula.gif @@ -5405,7 +5078,7 @@ extern "C" * @return none. */ - __STATIC_INLINE void arm_clarke_f32( + static __INLINE void arm_clarke_f32( float32_t Ia, float32_t Ib, float32_t * pIalpha, @@ -5435,7 +5108,7 @@ extern "C" * There is saturation on the addition, hence there is no risk of overflow. */ - __STATIC_INLINE void arm_clarke_q31( + static __INLINE void arm_clarke_q31( q31_t Ia, q31_t Ib, q31_t * pIalpha, @@ -5482,8 +5155,8 @@ extern "C" /** * @defgroup inv_clarke Vector Inverse Clarke Transform * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. - * - * The function operates on a single sample of data and each call to the function returns the processed output. + * + * The function operates on a single sample of data and each call to the function returns the processed output. * The library provides separate functions for Q31 and floating-point data types. * \par Algorithm * \image html clarkeInvFormula.gif @@ -5510,7 +5183,7 @@ extern "C" */ - __STATIC_INLINE void arm_inv_clarke_f32( + static __INLINE void arm_inv_clarke_f32( float32_t Ialpha, float32_t Ibeta, float32_t * pIa, @@ -5520,12 +5193,12 @@ extern "C" *pIa = Ialpha; /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ - *pIb = -0.5f * Ialpha + (float32_t) 0.8660254039f *Ibeta; + *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta; } /** - * @brief Inverse Clarke transform for Q31 version + * @brief Inverse Clarke transform for Q31 version * @param[in] Ialpha input two-phase orthogonal vector axis alpha * @param[in] Ibeta input two-phase orthogonal vector axis beta * @param[out] *pIa points to output three-phase coordinate a @@ -5539,7 +5212,7 @@ extern "C" * There is saturation on the subtraction, hence there is no risk of overflow. */ - __STATIC_INLINE void arm_inv_clarke_q31( + static __INLINE void arm_inv_clarke_q31( q31_t Ialpha, q31_t Ibeta, q31_t * pIa, @@ -5587,19 +5260,19 @@ extern "C" * @defgroup park Vector Park Transform * * Forward Park transform converts the input two-coordinate vector to flux and torque components. - * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents - * from the stationary to the moving reference frame and control the spatial relationship between + * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents + * from the stationary to the moving reference frame and control the spatial relationship between * the stator vector current and rotor flux vector. - * If we consider the d axis aligned with the rotor flux, the diagram below shows the + * If we consider the d axis aligned with the rotor flux, the diagram below shows the * current vector and the relationship from the two reference frames: * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" * - * The function operates on a single sample of data and each call to the function returns the processed output. + * The function operates on a single sample of data and each call to the function returns the processed output. * The library provides separate functions for Q31 and floating-point data types. * \par Algorithm * \image html parkFormula.gif - * where Ialpha and Ibeta are the stator vector components, - * pId and pIq are rotor vector components and cosVal and sinVal are the + * where Ialpha and Ibeta are the stator vector components, + * pId and pIq are rotor vector components and cosVal and sinVal are the * cosine and sine values of theta (rotor flux position). * \par Fixed-Point Behavior * Care must be taken when using the Q31 version of the Park transform. @@ -5626,7 +5299,7 @@ extern "C" * */ - __STATIC_INLINE void arm_park_f32( + static __INLINE void arm_park_f32( float32_t Ialpha, float32_t Ibeta, float32_t * pId, @@ -5643,7 +5316,7 @@ extern "C" } /** - * @brief Park transform for Q31 version + * @brief Park transform for Q31 version * @param[in] Ialpha input two-phase vector coordinate alpha * @param[in] Ibeta input two-phase vector coordinate beta * @param[out] *pId points to output rotor reference frame d @@ -5660,7 +5333,7 @@ extern "C" */ - __STATIC_INLINE void arm_park_q31( + static __INLINE void arm_park_q31( q31_t Ialpha, q31_t Ibeta, q31_t * pId, @@ -5716,12 +5389,12 @@ extern "C" * @defgroup inv_park Vector Inverse Park transform * Inverse Park transform converts the input flux and torque components to two-coordinate vector. * - * The function operates on a single sample of data and each call to the function returns the processed output. + * The function operates on a single sample of data and each call to the function returns the processed output. * The library provides separate functions for Q31 and floating-point data types. * \par Algorithm * \image html parkInvFormula.gif - * where pIalpha and pIbeta are the stator vector components, - * Id and Iq are rotor vector components and cosVal and sinVal are the + * where pIalpha and pIbeta are the stator vector components, + * Id and Iq are rotor vector components and cosVal and sinVal are the * cosine and sine values of theta (rotor flux position). * \par Fixed-Point Behavior * Care must be taken when using the Q31 version of the Park transform. @@ -5745,7 +5418,7 @@ extern "C" * @return none. */ - __STATIC_INLINE void arm_inv_park_f32( + static __INLINE void arm_inv_park_f32( float32_t Id, float32_t Iq, float32_t * pIalpha, @@ -5763,7 +5436,7 @@ extern "C" /** - * @brief Inverse Park transform for Q31 version + * @brief Inverse Park transform for Q31 version * @param[in] Id input coordinate of rotor reference frame d * @param[in] Iq input coordinate of rotor reference frame q * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha @@ -5780,7 +5453,7 @@ extern "C" */ - __STATIC_INLINE void arm_inv_park_q31( + static __INLINE void arm_inv_park_q31( q31_t Id, q31_t Iq, q31_t * pIalpha, @@ -5839,7 +5512,7 @@ extern "C" * Linear interpolation is a method of curve fitting using linear polynomials. * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line * - * \par + * \par * \image html LinearInterp.gif "Linear interpolation" * * \par @@ -5859,10 +5532,10 @@ extern "C" * sample of data and each call to the function returns a single processed value. * S points to an instance of the Linear Interpolate function data structure. * x is the input sample value. The functions returns the output value. - * + * * \par - * if x is outside of the table boundary, Linear interpolation returns first value of the table - * if x is below input range and returns last value of table if x is above range. + * if x is outside of the table boundary, Linear interpolation returns first value of the table + * if x is below input range and returns last value of table if x is above range. */ /** @@ -5878,7 +5551,7 @@ extern "C" * */ - __STATIC_INLINE float32_t arm_linear_interp_f32( + static __INLINE float32_t arm_linear_interp_f32( arm_linear_interp_instance_f32 * S, float32_t x) { @@ -5891,14 +5564,14 @@ extern "C" float32_t *pYData = S->pYData; /* pointer to output table */ /* Calculation of index */ - i = (x - S->x1) / xSpacing; + i = (int32_t) ((x - S->x1) / xSpacing); if(i < 0) { /* Iniatilize output for below specified range as least output value of table */ y = pYData[0]; } - else if((unsigned)i >= S->nValues) + else if((uint32_t)i >= S->nValues) { /* Iniatilize output for above specified range as last output value of table */ y = pYData[S->nValues - 1]; @@ -5937,7 +5610,7 @@ extern "C" */ - __STATIC_INLINE q31_t arm_linear_interp_q31( + static __INLINE q31_t arm_linear_interp_q31( q31_t * pYData, q31_t x, uint32_t nValues) @@ -5952,7 +5625,7 @@ extern "C" /* Index value calculation */ index = ((x & 0xFFF00000) >> 20); - if(index >= (nValues - 1)) + if(index >= (int32_t)(nValues - 1)) { return (pYData[nValues - 1]); } @@ -5994,12 +5667,12 @@ extern "C" * * \par * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. + * This function can support maximum of table size 2^12. * */ - __STATIC_INLINE q15_t arm_linear_interp_q15( + static __INLINE q15_t arm_linear_interp_q15( q15_t * pYData, q31_t x, uint32_t nValues) @@ -6014,7 +5687,7 @@ extern "C" /* Index value calculation */ index = ((x & 0xFFF00000) >> 20u); - if(index >= (nValues - 1)) + if(index >= (int32_t)(nValues - 1)) { return (pYData[nValues - 1]); } @@ -6059,7 +5732,7 @@ extern "C" */ - __STATIC_INLINE q7_t arm_linear_interp_q7( + static __INLINE q7_t arm_linear_interp_q7( q7_t * pYData, q31_t x, uint32_t nValues) @@ -6067,22 +5740,22 @@ extern "C" q31_t y; /* output */ q7_t y0, y1; /* Nearest output values */ q31_t fract; /* fractional part */ - int32_t index; /* Index to read nearest output values */ + uint32_t index; /* Index to read nearest output values */ /* Input is in 12.20 format */ /* 12 bits for the table index */ /* Index value calculation */ - index = ((x & 0xFFF00000) >> 20u); + if (x < 0) + { + return (pYData[0]); + } + index = (x >> 20) & 0xfff; if(index >= (nValues - 1)) { return (pYData[nValues - 1]); } - else if(index < 0) - { - return (pYData[0]); - } else { @@ -6174,14 +5847,14 @@ extern "C" * @defgroup SQRT Square Root * * Computes the square root of a number. - * There are separate functions for Q15, Q31, and floating-point data types. + * There are separate functions for Q15, Q31, and floating-point data types. * The square root function is computed using the Newton-Raphson algorithm. * This is an iterative algorithm of the form: *
    *      x1 = x0 - f(x0)/f'(x0)
    * 
* where x1 is the current estimate, - * x0 is the previous estimate and + * x0 is the previous estimate, and * f'(x0) is the derivative of f() evaluated at x0. * For the square root function, the algorithm reduces to: *
@@ -6204,21 +5877,19 @@ extern "C"
    * in is negative value and returns zero output for negative values.
    */
 
-  __STATIC_INLINE arm_status arm_sqrt_f32(
+  static __INLINE arm_status arm_sqrt_f32(
   float32_t in,
   float32_t * pOut)
   {
     if(in > 0)
     {
 
-//    #if __FPU_USED
-    #if (__FPU_USED == 1) && defined ( __CC_ARM   )
-        *pOut = __sqrtf(in);
-    #elif (__FPU_USED == 1) && defined ( __TMS_740 )
-        *pOut = __builtin_sqrtf(in);
-    #else
-        *pOut = sqrtf(in);
-    #endif
+//      #if __FPU_USED
+#if (__FPU_USED == 1) && defined ( __CC_ARM   )
+      *pOut = __sqrtf(in);
+#else
+      *pOut = sqrtf(in);
+#endif
 
       return (ARM_MATH_SUCCESS);
     }
@@ -6266,7 +5937,7 @@ extern "C"
    * @brief floating-point Circular write function.
    */
 
-  __STATIC_INLINE void arm_circularWrite_f32(
+  static __INLINE void arm_circularWrite_f32(
   int32_t * circBuffer,
   int32_t L,
   uint16_t * writeOffset,
@@ -6311,7 +5982,7 @@ extern "C"
   /**
    * @brief floating-point Circular Read function.
    */
-  __STATIC_INLINE void arm_circularRead_f32(
+  static __INLINE void arm_circularRead_f32(
   int32_t * circBuffer,
   int32_t L,
   int32_t * readOffset,
@@ -6366,7 +6037,7 @@ extern "C"
    * @brief Q15 Circular write function.
    */
 
-  __STATIC_INLINE void arm_circularWrite_q15(
+  static __INLINE void arm_circularWrite_q15(
   q15_t * circBuffer,
   int32_t L,
   uint16_t * writeOffset,
@@ -6411,7 +6082,7 @@ extern "C"
   /**
    * @brief Q15 Circular Read function.
    */
-  __STATIC_INLINE void arm_circularRead_q15(
+  static __INLINE void arm_circularRead_q15(
   q15_t * circBuffer,
   int32_t L,
   int32_t * readOffset,
@@ -6468,7 +6139,7 @@ extern "C"
    * @brief Q7 Circular write function.
    */
 
-  __STATIC_INLINE void arm_circularWrite_q7(
+  static __INLINE void arm_circularWrite_q7(
   q7_t * circBuffer,
   int32_t L,
   uint16_t * writeOffset,
@@ -6513,7 +6184,7 @@ extern "C"
   /**
    * @brief Q7 Circular Read function.
    */
-  __STATIC_INLINE void arm_circularRead_q7(
+  static __INLINE void arm_circularRead_q7(
   q7_t * circBuffer,
   int32_t L,
   int32_t * readOffset,
@@ -7084,11 +6755,11 @@ extern "C"
   uint32_t numSamples);
 
   /**
-   * @brief Converts the elements of the floating-point vector to Q31 vector. 
-   * @param[in]       *pSrc points to the floating-point input vector 
+   * @brief Converts the elements of the floating-point vector to Q31 vector.
+   * @param[in]       *pSrc points to the floating-point input vector
    * @param[out]      *pDst points to the Q31 output vector
-   * @param[in]       blockSize length of the input vector 
-   * @return none. 
+   * @param[in]       blockSize length of the input vector
+   * @return none.
    */
   void arm_float_to_q31(
   float32_t * pSrc,
@@ -7096,10 +6767,10 @@ extern "C"
   uint32_t blockSize);
 
   /**
-   * @brief Converts the elements of the floating-point vector to Q15 vector. 
-   * @param[in]       *pSrc points to the floating-point input vector 
+   * @brief Converts the elements of the floating-point vector to Q15 vector.
+   * @param[in]       *pSrc points to the floating-point input vector
    * @param[out]      *pDst points to the Q15 output vector
-   * @param[in]       blockSize length of the input vector 
+   * @param[in]       blockSize length of the input vector
    * @return          none
    */
   void arm_float_to_q15(
@@ -7108,10 +6779,10 @@ extern "C"
   uint32_t blockSize);
 
   /**
-   * @brief Converts the elements of the floating-point vector to Q7 vector. 
-   * @param[in]       *pSrc points to the floating-point input vector 
+   * @brief Converts the elements of the floating-point vector to Q7 vector.
+   * @param[in]       *pSrc points to the floating-point input vector
    * @param[out]      *pDst points to the Q7 output vector
-   * @param[in]       blockSize length of the input vector 
+   * @param[in]       blockSize length of the input vector
    * @return          none
    */
   void arm_float_to_q7(
@@ -7231,12 +6902,12 @@ extern "C"
    *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
    *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
    * 
- * Note that the coordinates (x, y) contain integer and fractional components. + * Note that the coordinates (x, y) contain integer and fractional components. * The integer components specify which portion of the table to use while the * fractional components control the interpolation processor. * * \par - * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. + * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. */ /** @@ -7254,7 +6925,7 @@ extern "C" */ - __STATIC_INLINE float32_t arm_bilinear_interp_f32( + static __INLINE float32_t arm_bilinear_interp_f32( const arm_bilinear_interp_instance_f32 * S, float32_t X, float32_t Y) @@ -7322,7 +6993,7 @@ extern "C" * @return out interpolated value. */ - __STATIC_INLINE q31_t arm_bilinear_interp_q31( + static __INLINE q31_t arm_bilinear_interp_q31( arm_bilinear_interp_instance_q31 * S, q31_t X, q31_t Y) @@ -7398,7 +7069,7 @@ extern "C" * @return out interpolated value. */ - __STATIC_INLINE q15_t arm_bilinear_interp_q15( + static __INLINE q15_t arm_bilinear_interp_q15( arm_bilinear_interp_instance_q15 * S, q31_t X, q31_t Y) @@ -7478,7 +7149,7 @@ extern "C" * @return out interpolated value. */ - __STATIC_INLINE q7_t arm_bilinear_interp_q7( + static __INLINE q7_t arm_bilinear_interp_q7( arm_bilinear_interp_instance_q7 * S, q31_t X, q31_t Y) @@ -7551,6 +7222,84 @@ extern "C" */ +#if defined ( __CC_ARM ) //Keil +//SMMLAR + #define multAcc_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32) + +//SMMLSR + #define multSub_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32) + +//SMMULR + #define mult_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32) + +//Enter low optimization region - place directly above function definition + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("push") \ + _Pragma ("O1") + +//Exit low optimization region - place directly after end of function definition + #define LOW_OPTIMIZATION_EXIT \ + _Pragma ("pop") + +//Enter low optimization region - place directly above function definition + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + +//Exit low optimization region - place directly after end of function definition + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined(__ICCARM__) //IAR + //SMMLA + #define multAcc_32x32_keep32_R(a, x, y) \ + a += (q31_t) (((q63_t) x * y) >> 32) + + //SMMLS + #define multSub_32x32_keep32_R(a, x, y) \ + a -= (q31_t) (((q63_t) x * y) >> 32) + +//SMMUL + #define mult_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((q63_t) x * y ) >> 32) + +//Enter low optimization region - place directly above function definition + #define LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + +//Exit low optimization region - place directly after end of function definition + #define LOW_OPTIMIZATION_EXIT + +//Enter low optimization region - place directly above function definition + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \ + _Pragma ("optimize=low") + +//Exit low optimization region - place directly after end of function definition + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#elif defined(__GNUC__) + //SMMLA + #define multAcc_32x32_keep32_R(a, x, y) \ + a += (q31_t) (((q63_t) x * y) >> 32) + + //SMMLS + #define multSub_32x32_keep32_R(a, x, y) \ + a -= (q31_t) (((q63_t) x * y) >> 32) + +//SMMUL + #define mult_32x32_keep32_R(a, x, y) \ + a = (q31_t) (((q63_t) x * y ) >> 32) + + #define LOW_OPTIMIZATION_ENTER __attribute__(( optimize("-O1") )) + + #define LOW_OPTIMIZATION_EXIT + + #define IAR_ONLY_LOW_OPTIMIZATION_ENTER + + #define IAR_ONLY_LOW_OPTIMIZATION_EXIT + +#endif + diff --git a/src/modules/mathlib/CMSIS/Include/core_cm3.h b/src/modules/mathlib/CMSIS/Include/core_cm3.h index 733d6be539..8ac6dc0788 100644 --- a/src/modules/mathlib/CMSIS/Include/core_cm3.h +++ b/src/modules/mathlib/CMSIS/Include/core_cm3.h @@ -1,25 +1,40 @@ /**************************************************************************//** * @file core_cm3.h * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File - * @version V3.01 - * @date 22. March 2012 + * @version V3.20 + * @date 25. February 2013 * * @note - * Copyright (C) 2009-2012 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. * ******************************************************************************/ +/* Copyright (c) 2009 - 2013 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + #if defined ( __ICCARM__ ) #pragma system_include /* treat file as system include file for MISRA check */ #endif @@ -54,7 +69,7 @@ /* CMSIS CM3 definitions */ #define __CM3_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */ -#define __CM3_CMSIS_VERSION_SUB (0x01) /*!< [15:0] CMSIS HAL sub version */ +#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */ #define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | \ __CM3_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ @@ -636,14 +651,14 @@ typedef struct __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ uint32_t RESERVED2[15]; __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29]; + uint32_t RESERVED3[29]; __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43]; + uint32_t RESERVED4[43]; __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6]; + uint32_t RESERVED5[6]; __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ @@ -1516,9 +1531,9 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ - SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + SysTick->LOAD = ticks - 1; /* set reload register */ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ SysTick->VAL = 0; /* Load the SysTick Counter Value */ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | diff --git a/src/modules/mathlib/CMSIS/Include/core_cm4.h b/src/modules/mathlib/CMSIS/Include/core_cm4.h index 5f3b7d6198..93efd3a7ae 100644 --- a/src/modules/mathlib/CMSIS/Include/core_cm4.h +++ b/src/modules/mathlib/CMSIS/Include/core_cm4.h @@ -1,25 +1,40 @@ /**************************************************************************//** * @file core_cm4.h * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V3.01 - * @date 22. March 2012 + * @version V3.20 + * @date 25. February 2013 * * @note - * Copyright (C) 2009-2012 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. * ******************************************************************************/ +/* Copyright (c) 2009 - 2013 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + + #if defined ( __ICCARM__ ) #pragma system_include /* treat file as system include file for MISRA check */ #endif @@ -54,7 +69,7 @@ /* CMSIS CM4 definitions */ #define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (0x01) /*!< [15:0] CMSIS HAL sub version */ +#define __CM4_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */ #define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \ __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */ @@ -669,14 +684,14 @@ typedef struct __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ uint32_t RESERVED2[15]; __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29]; + uint32_t RESERVED3[29]; __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43]; + uint32_t RESERVED4[43]; __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6]; + uint32_t RESERVED5[6]; __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ @@ -1661,9 +1676,9 @@ __STATIC_INLINE void NVIC_SystemReset(void) */ __STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) { - if (ticks > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ + if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */ - SysTick->LOAD = (ticks & SysTick_LOAD_RELOAD_Msk) - 1; /* set reload register */ + SysTick->LOAD = ticks - 1; /* set reload register */ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */ SysTick->VAL = 0; /* Load the SysTick Counter Value */ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | diff --git a/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h b/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h index b5140073fb..af1831ee17 100644 --- a/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h +++ b/src/modules/mathlib/CMSIS/Include/core_cm4_simd.h @@ -1,25 +1,39 @@ /**************************************************************************//** * @file core_cm4_simd.h * @brief CMSIS Cortex-M4 SIMD Header File - * @version V3.01 - * @date 06. March 2012 + * @version V3.20 + * @date 25. February 2013 * * @note - * Copyright (C) 2010-2012 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. * ******************************************************************************/ +/* Copyright (c) 2009 - 2013 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + #ifdef __cplusplus extern "C" { @@ -110,6 +124,8 @@ #define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) +#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ + ((int64_t)(ARG3) << 32) ) >> 32)) /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ @@ -624,6 +640,14 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, __RES; \ }) +__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) +{ + int32_t result; + + __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); + return(result); +} + /*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/ diff --git a/src/modules/mathlib/CMSIS/Include/core_cmFunc.h b/src/modules/mathlib/CMSIS/Include/core_cmFunc.h index adb07b5d34..139bc3c5ec 100644 --- a/src/modules/mathlib/CMSIS/Include/core_cmFunc.h +++ b/src/modules/mathlib/CMSIS/Include/core_cmFunc.h @@ -1,25 +1,39 @@ /**************************************************************************//** * @file core_cmFunc.h * @brief CMSIS Cortex-M Core Function Access Header File - * @version V3.01 - * @date 06. March 2012 + * @version V3.20 + * @date 25. February 2013 * * @note - * Copyright (C) 2009-2012 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. * ******************************************************************************/ +/* Copyright (c) 2009 - 2013 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + #ifndef __CORE_CMFUNC_H #define __CORE_CMFUNC_H @@ -314,7 +328,7 @@ __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) { - __ASM volatile ("cpsie i"); + __ASM volatile ("cpsie i" : : : "memory"); } @@ -325,7 +339,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void) { - __ASM volatile ("cpsid i"); + __ASM volatile ("cpsid i" : : : "memory"); } @@ -352,7 +366,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control) { - __ASM volatile ("MSR control, %0" : : "r" (control) ); + __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); } @@ -424,7 +438,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) { - __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) ); + __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp"); } @@ -451,7 +465,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) { - __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) ); + __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp"); } @@ -478,7 +492,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) { - __ASM volatile ("MSR primask, %0" : : "r" (priMask) ); + __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); } @@ -491,7 +505,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t p */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) { - __ASM volatile ("cpsie f"); + __ASM volatile ("cpsie f" : : : "memory"); } @@ -502,7 +516,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void) { - __ASM volatile ("cpsid f"); + __ASM volatile ("cpsid f" : : : "memory"); } @@ -529,7 +543,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value) { - __ASM volatile ("MSR basepri, %0" : : "r" (value) ); + __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); } @@ -556,7 +570,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) { - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) ); + __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); } #endif /* (__CORTEX_M >= 0x03) */ @@ -575,7 +589,10 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) uint32_t result; + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); + __ASM volatile (""); return(result); #else return(0); @@ -592,7 +609,10 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void) __attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) { #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) ); + /* Empty asm statement works as a scheduling barrier */ + __ASM volatile (""); + __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); + __ASM volatile (""); #endif } diff --git a/src/modules/mathlib/CMSIS/Include/core_cmInstr.h b/src/modules/mathlib/CMSIS/Include/core_cmInstr.h index 624c175fd5..8946c2c492 100644 --- a/src/modules/mathlib/CMSIS/Include/core_cmInstr.h +++ b/src/modules/mathlib/CMSIS/Include/core_cmInstr.h @@ -1,25 +1,39 @@ /**************************************************************************//** * @file core_cmInstr.h * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V3.01 - * @date 06. March 2012 + * @version V3.20 + * @date 05. March 2013 * * @note - * Copyright (C) 2009-2012 ARM Limited. All rights reserved. - * - * @par - * ARM Limited (ARM) is supplying this software for use with Cortex-M - * processor based microcontrollers. This file can be freely distributed - * within development tools that are supporting such ARM based processors. - * - * @par - * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED - * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE. - * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR - * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER. * ******************************************************************************/ +/* Copyright (c) 2009 - 2013 ARM LIMITED + + All rights reserved. + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + * + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE + LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + POSSIBILITY OF SUCH DAMAGE. + ---------------------------------------------------------------------------*/ + #ifndef __CORE_CMINSTR_H #define __CORE_CMINSTR_H @@ -111,12 +125,13 @@ \param [in] value Value to reverse \return Reversed value */ +#ifndef __NO_EMBEDDED_ASM __attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) { rev16 r0, r0 bx lr } - +#endif /** \brief Reverse byte order in signed short value @@ -125,11 +140,13 @@ __attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(u \param [in] value Value to reverse \return Reversed value */ +#ifndef __NO_EMBEDDED_ASM __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value) { revsh r0, r0 bx lr } +#endif /** \brief Rotate Right in unsigned value (32 bit) @@ -143,6 +160,17 @@ __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(in #define __ROR __ror +/** \brief Breakpoint + + This function causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __breakpoint(value) + + #if (__CORTEX_M >= 0x03) /** \brief Reverse bit order of value @@ -279,6 +307,17 @@ __attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(in #elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/ /* GNU gcc specific functions */ +/* Define macros for porting to both thumb1 and thumb2. + * For thumb1, use low register (r0-r7), specified by constrant "l" + * Otherwise, use general registers, specified by constrant "r" */ +#if defined (__thumb__) && !defined (__thumb2__) +#define __CMSIS_GCC_OUT_REG(r) "=l" (r) +#define __CMSIS_GCC_USE_REG(r) "l" (r) +#else +#define __CMSIS_GCC_OUT_REG(r) "=r" (r) +#define __CMSIS_GCC_USE_REG(r) "r" (r) +#endif + /** \brief No Operation No Operation does nothing. This instruction can be used for code alignment purposes. @@ -364,10 +403,14 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value) { +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) + return __builtin_bswap32(value); +#else uint32_t result; - __ASM volatile ("rev %0, %1" : "=r" (result) : "r" (value) ); + __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); return(result); +#endif } @@ -382,7 +425,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t val { uint32_t result; - __ASM volatile ("rev16 %0, %1" : "=r" (result) : "r" (value) ); + __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); return(result); } @@ -396,10 +439,14 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t val */ __attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value) { +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + return (short)__builtin_bswap16(value); +#else uint32_t result; - __ASM volatile ("revsh %0, %1" : "=r" (result) : "r" (value) ); + __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); return(result); +#endif } @@ -413,12 +460,21 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value */ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) { - - __ASM volatile ("ror %0, %0, %1" : "+r" (op1) : "r" (op2) ); - return(op1); + return (op1 >> op2) | (op1 << (32 - op2)); } +/** \brief Breakpoint + + This function causes the processor to enter Debug state. + Debug tools can use this to investigate system state when the instruction at a particular address is reached. + + \param [in] value is ignored by the processor. + If required, a debugger can use it to store additional information about the breakpoint. + */ +#define __BKPT(value) __ASM volatile ("bkpt "#value) + + #if (__CORTEX_M >= 0x03) /** \brief Reverse bit order of value @@ -446,9 +502,16 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t valu */ __attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr) { - uint8_t result; + uint32_t result; - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) ); +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif return(result); } @@ -462,9 +525,16 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uin */ __attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr) { - uint16_t result; + uint32_t result; - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) ); +#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) + __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); +#else + /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not + accepted by assembler. So has to use following less efficient pattern. + */ + __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); +#endif return(result); } @@ -480,7 +550,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile ui { uint32_t result; - __ASM volatile ("ldrex %0, [%1]" : "=r" (result) : "r" (addr) ); + __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); return(result); } @@ -498,7 +568,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t val { uint32_t result; - __ASM volatile ("strexb %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); return(result); } @@ -516,7 +586,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t va { uint32_t result; - __ASM volatile ("strexh %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); return(result); } @@ -534,7 +604,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t va { uint32_t result; - __ASM volatile ("strex %0, %2, [%1]" : "=&r" (result) : "r" (addr), "r" (value) ); + __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); return(result); } @@ -546,7 +616,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t va */ __attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) { - __ASM volatile ("clrex"); + __ASM volatile ("clrex" ::: "memory"); } @@ -591,7 +661,7 @@ __attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void) */ __attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value) { - uint8_t result; + uint32_t result; __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) ); return(result); diff --git a/src/modules/mathlib/CMSIS/module.mk b/src/modules/mathlib/CMSIS/library.mk similarity index 69% rename from src/modules/mathlib/CMSIS/module.mk rename to src/modules/mathlib/CMSIS/library.mk index 5e1abe642f..0cc1b559d8 100644 --- a/src/modules/mathlib/CMSIS/module.mk +++ b/src/modules/mathlib/CMSIS/library.mk @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. +# Copyright (c) 2013 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -35,26 +35,12 @@ # ARM CMSIS DSP library # -# -# Find sources -# -DSPLIB_SRCDIR := $(dir $(lastword $(MAKEFILE_LIST))) -SRCLIST := $(wildcard $(DSPLIB_SRCDIR)DSP_Lib/Source/*/*.c) -SRCS := $(patsubst $(DSPLIB_SRCDIR)%,%,$(SRCLIST)) - -INCLUDE_DIRS += $(DSPLIB_SRCDIR)/Include \ - $(DSPLIB_SRCDIR)/Device/ARM/ARMCM4/Include \ - $(DSPLIB_SRCDIR)/Device/ARM/ARMCM3/Include - -# Suppress some warnings that ARM should fix, but haven't. -EXTRADEFINES += -Wno-unsuffixed-float-constants \ - -Wno-sign-compare \ - -Wno-shadow \ - -Wno-float-equal \ - -Wno-unused-variable - -# -# Override the default visibility for symbols, since the CMSIS DSPLib doesn't -# have anything we can use to mark exported symbols. -# -DEFAULT_VISIBILITY = YES +ifeq ($(CONFIG_ARCH),CORTEXM4F) +PREBUILT_LIB := libarm_cortexM4lf_math.a +else ifeq ($(CONFIG_ARCH),CORTEXM4) +PREBUILT_LIB := libarm_cortexM4l_math.a +else ifeq ($(CONFIG_ARCH),CORTEXM3) +PREBUILT_LIB := libarm_cortexM3l_math.a +else +$(error CONFIG_ARCH value '$(CONFIG_ARCH)' not supported by the DSP library) +endif diff --git a/src/modules/mathlib/CMSIS/license.txt b/src/modules/mathlib/CMSIS/license.txt new file mode 100644 index 0000000000..31afac1ec4 --- /dev/null +++ b/src/modules/mathlib/CMSIS/license.txt @@ -0,0 +1,27 @@ +All pre-built libraries are guided by the following license: + +Copyright (C) 2009-2012 ARM Limited. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + - Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + - Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + - Neither the name of ARM nor the names of its contributors may be used + to endorse or promote products derived from this software without + specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. From fdb897c3dd5561a1d9f22b35ec049e50d526d08b Mon Sep 17 00:00:00 2001 From: Duncan Greer Date: Mon, 20 May 2013 17:41:42 +1000 Subject: [PATCH 089/102] enable usb console --- nuttx/configs/px4fmu/nsh/defconfig | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig index 02e2243020..94d99112e2 100755 --- a/nuttx/configs/px4fmu/nsh/defconfig +++ b/nuttx/configs/px4fmu/nsh/defconfig @@ -248,7 +248,7 @@ CONFIG_SERIAL_TERMIOS=y CONFIG_SERIAL_CONSOLE_REINIT=y CONFIG_STANDARD_SERIAL=y -CONFIG_USART1_SERIAL_CONSOLE=y +CONFIG_USART1_SERIAL_CONSOLE=n CONFIG_USART2_SERIAL_CONSOLE=n CONFIG_USART3_SERIAL_CONSOLE=n CONFIG_UART4_SERIAL_CONSOLE=n @@ -561,7 +561,7 @@ CONFIG_START_MONTH=1 CONFIG_START_DAY=1 CONFIG_GREGORIAN_TIME=n CONFIG_JULIAN_TIME=n -CONFIG_DEV_CONSOLE=y +CONFIG_DEV_CONSOLE=n CONFIG_DEV_LOWCONSOLE=n CONFIG_MUTEX_TYPES=n CONFIG_PRIORITY_INHERITANCE=y @@ -925,7 +925,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=512 # Size of the serial receive/transmit buffers. Default 256. # CONFIG_CDCACM=y -CONFIG_CDCACM_CONSOLE=n +CONFIG_CDCACM_CONSOLE=y #CONFIG_CDCACM_EP0MAXPACKET CONFIG_CDCACM_EPINTIN=1 #CONFIG_CDCACM_EPINTIN_FSSIZE From fa403956ed6ef1a345ee06c25500c937a78dd7cd Mon Sep 17 00:00:00 2001 From: Duncan Greer Date: Mon, 20 May 2013 17:41:59 +1000 Subject: [PATCH 090/102] change default rc channel mapping --- src/modules/uORB/topics/rc_channels.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h index 9dd54df915..9df29ed34d 100644 --- a/src/modules/uORB/topics/rc_channels.h +++ b/src/modules/uORB/topics/rc_channels.h @@ -64,9 +64,9 @@ */ enum RC_CHANNELS_FUNCTION { - THROTTLE = 0, - ROLL = 1, - PITCH = 2, + THROTTLE = 2, + ROLL = 0, + PITCH = 1, YAW = 3, OVERRIDE = 4, AUTO_MODE = 5, From 05fe7779a98ef2d44693dac28bf73a899772a206 Mon Sep 17 00:00:00 2001 From: px4dev Date: Mon, 20 May 2013 20:33:18 +0200 Subject: [PATCH 091/102] Fix .gitignore to avoid ignoring prebuilt libraries. Also, generally clean-up the .gitignores and farm off separate versions for the NuttX/Apps directories to keep things tidy. --- .gitignore | 80 +++++------------- apps/.gitignore | 10 +++ nuttx/.gitignore | 28 ++++++ .../mathlib/CMSIS/libarm_cortexM3l_math.a | Bin 0 -> 3039508 bytes .../mathlib/CMSIS/libarm_cortexM4l_math.a | Bin 0 -> 3049684 bytes .../mathlib/CMSIS/libarm_cortexM4lf_math.a | Bin 0 -> 2989192 bytes src/modules/sensors/.context | 0 src/systemcmds/tests/.context | 0 8 files changed, 60 insertions(+), 58 deletions(-) create mode 100644 apps/.gitignore create mode 100644 nuttx/.gitignore create mode 100644 src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a create mode 100755 src/modules/mathlib/CMSIS/libarm_cortexM4l_math.a create mode 100755 src/modules/mathlib/CMSIS/libarm_cortexM4lf_math.a delete mode 100644 src/modules/sensors/.context delete mode 100644 src/systemcmds/tests/.context diff --git a/.gitignore b/.gitignore index de03b0a607..0918b89f13 100644 --- a/.gitignore +++ b/.gitignore @@ -1,62 +1,26 @@ -.built -.context -*.context -*.bdat -*.pdat -.depend -.updated -.config -.config-e -.version -.project -.cproject -apps/builtin/builtin_list.h -apps/builtin/builtin_proto.h -Make.dep -*.pyc -*.o -*.a *.d -*~ -*.dSYM -Images/*.bin -Images/*.px4 -nuttx/Make.defs -nuttx/setenv.sh -nuttx/arch/arm/include/board -nuttx/arch/arm/include/chip -nuttx/arch/arm/src/board -nuttx/arch/arm/src/chip -nuttx/include/apps -nuttx/include/arch -nuttx/include/math.h -nuttx/include/nuttx/config.h -nuttx/include/nuttx/version.h -nuttx/tools/mkconfig -nuttx/tools/mkconfig.exe -nuttx/tools/mkversion -nuttx/tools/mkversion.exe -nuttx/nuttx -nuttx/System.map -nuttx/nuttx.bin -nuttx/nuttx.hex -.configured -.settings -Firmware.sublime-workspace -.DS_Store -cscope.out -.configX-e -nuttx-export.zip -.~lock.* -dot.gdbinit -mavlink/include/mavlink/v0.9/ -.*.swp -.swp -core -.gdbinit -mkdeps -Archives -Build !ROMFS/*/*.d !ROMFS/*/*/*.d !ROMFS/*/*/*/*.d +*.dSYM +*.o +*.pyc +*~ +.*.swp +.context +.cproject +.DS_Store +.gdbinit +.project +.settings +.swp +.~lock.* +Archives/* +Build/* +core +cscope.out +dot.gdbinit +Firmware.sublime-workspace +Images/*.bin +Images/*.px4 +mavlink/include/mavlink/v0.9/ diff --git a/apps/.gitignore b/apps/.gitignore new file mode 100644 index 0000000000..9eb5181a48 --- /dev/null +++ b/apps/.gitignore @@ -0,0 +1,10 @@ +*.a +*.bdat +*.pdat +.built +.config +.depend +.updated +builtin/builtin_list.h +builtin/builtin_proto.h +Make.dep diff --git a/nuttx/.gitignore b/nuttx/.gitignore new file mode 100644 index 0000000000..0d763ab2a9 --- /dev/null +++ b/nuttx/.gitignore @@ -0,0 +1,28 @@ +*.a +.config +.config-e +.configX-e +.depend +.version +arch/arm/include/board +arch/arm/include/chip +arch/arm/src/board +arch/arm/src/chip +include/apps +include/arch +include/math.h +include/nuttx/config.h +include/nuttx/version.h +Make.defs +Make.dep +mkdeps +nuttx +nuttx-export.zip +nuttx.bin +nuttx.hex +setenv.sh +System.map +tools/mkconfig +tools/mkconfig.exe +tools/mkversion +tools/mkversion.exe diff --git a/src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a b/src/modules/mathlib/CMSIS/libarm_cortexM3l_math.a new file mode 100644 index 0000000000000000000000000000000000000000..6898bc27d0f736c2c77bb036a208b34ffebe6811 GIT binary patch literal 3039508 zcmc$`cYGXI)joc$I+A61th(x}VrkWExy!aRcU`mY>lVvha+SL*$@aQxUr53d5?DwG zA_SsPf`CAjP$Cj*?xv9q@tZ6qM1&Lt0w^JX2m$n_z;BOqp4FcLfQX!K6OoG&MC4XoL>|o+kv9jwe{H#l ze7s9U{_Hjp`P&o``8SJ*60eA;Bq5>-Y$9sbS`oD@*tYYkh;n&F)MvXz)VJOgQGUOO z`hzB-KD3GG)NTK0wU(g+eA#@fQWgeRm2P&5V7%Y5u0(_ z$lsD`5sSaJL7{zNt%#e^A>vmIi1>X~BY$_bi+KF~G+V^~C0k5R?hsQdg-E=iUg-7r z2>qsNp+A2-^f#^0E%29A*&&ivToXyV-xEpa21fqg=@&`-mt1sQg#P~E6)BNXA|=ly zQlx$4?_8@$!QZtyk@E9vBY*EbAX4MKA~nBCq%O!7sW-kSQrqT=)Gs_GQoDAE)Sm_0 z`{#O^rt=)mgq)dN$(Jr(pQ9KQKzu%dq7xP?i7}rE(yz>1H$s?abbDOBQgr=MaCRW zWGw3v8C#Z%j0?ekAKM}_KKM{%8k)%5U=f-1%SGntdqn2Px`MC`hRg1#90C1^ZG& zf&V>G7-tuSOD~DS+nYq;`*osdo>LTk?5Zewwnj{keNRl^&?KfmR41mtyGs;TUlqlx z5=61fDvG}r{QO+MD1N0&6#qH+_ffAXDY1%@jYXoQrAm}M5+zFfHKODXw+Wl(61MzK zVOtUbAeWJ|$by0TDouceoyC{3BLX>?}C(6@z ziSjueqI^TWC_kDY%5NDI<@a3`Us& z*G0uQmy3$08b!q$4pH%sH$~-?ABf6gT~sdjiOL;rQF(TYsJwrzsC=qhRQ3k9|2s;| z$gdMK*7vubJ96N_@q^1w9XzzR`Ou-(y>qJ;&KKiaXIIUw9^X2vYWCdmt@CEh9^W{7 z-ULUTHG6`C&Y$3rb7qT%<`YYgv~D_hcGbxP2VGkl_8mVsG}H;&hXy-A`_OPFXr}>B z&`d*~pqU0eL341}6SPh|@L59#-gI#Pk*1*w**Iqwbq;HoH81=YZXEM9xO?~$8u!S? zJ*{yMYV0!_`*_AanK2I~cv;~C7`~q2$1`+6bTxZV&zZHi_0-ZC3r6ic{0%1>`Zluf(5LX-M;f@tNW<{y4jnmuoQ6L% zu;DM*b7)K0UWbOC@ZSBWn$Cy141eJ+!(WEG41GqIvklFm9z&nG1AWFmEv*Ma`wV^N zedsgxX+F^s+Gpr9??a!lPt&P$2S?7v-*`X%Hax=NFX(pS$jQ*5hdy(cq0hq|=woR2 zgAHN(4}C$0p)cHnK8LzAxJJ%EpV5In^Zvn)*u5oqw*99@t{302z3Iq-z0C((4z`94 z8rFjA4eb-&>&VF?qdN^Zg!LI}K$n)LN09@BP|%+P|Kl)me#$YLASIv96mTaVA|`%!RGL<^n#9b!ePQL5>3N9@uUwQ zFm^bwzjbct@`u0hr3`%;btz#j*Oy?5W4*4Bf~hmM~Q&5NN8bHg@- z9suLPmhDUU$+xx<+#&?j>h93b+ifEMqPgR&Z8daxDBJOKm2O0 zy8#2k4&jGH+tAg_zTQm>-+-gx28|qTcIZZqKN?^ExDBDBjk`g?qfO9uotrj$cyeF2 z$8|6Bx*ISs>=1sL}xo_m*1f9ripgL4G-TB z7kr|jb#H5P!^x3o7}mnKaij%DryiB)ak}=xL%KmPKmZd!C|yCHH1gx@FqTFc++rF z5Y{qkRO8ymA7Oa^i4QZuu)>=#P3bIn4TnCD9Bu49rOlzXu)&~h+~`MdxL%L&QK3h8 z+mVyO6|(76aMQ@+rJ;;!4?B2x`?w*E-}v8pUT+wq+rwVe;c-#JsKZjj$bB6eRQMrA z#SJ>dsE{$#z|n#}9|#s(!Pk5A%@}D6J8`IS+-(@M<+^>sM;YofZn$H%Oms9HX#c6^ z=7XaiWmpS$3~L#_X(J7%nnrHznAWkojvD32zN2pKnC6L(J~H%^XG3ev{!{cNG+_FI z0R%q>qd@DC;L?bfY-sOLV|cGn;{?4&4=3!fLmMXOFy@lOdW^a1v0JWtrcu{EZm+T9 z7=Qlp=N)PpcO;x=-;vX28V>B;-_WwZ;lRPY2M*2NGLrXGW?n3vS}a zFu|r#ugi6}|3CWwmr;$nPZJz})Lolsdno0?-3s2RS;0iiHGl2|mmIcn)RpZ&(RAE3 zoXRvG44f;_;6hcXY1Hp+d|J64`HN%yN)yrcMpBXS;I5*@a%l(^KhT=B)wtZNI^98 zna?xynRgHFLPr-f$5Mr(iNkT<=FXZkcet@Wo&xLsQzuTGI=Q!%(CC&Kr)CZ{2CsAo zZJaf4Ov@0=7-|dQonu-??=^yDVz&{na?Y&rZ6hZg*>3@M16mdw;n=3&?Lbo)Vm7j0 zSmVekMjFR-N5l+2Q&O>cseMgY2upx#uj`SXB9NT?p9hmUILtDaj4}+gZE;Ouh zb9yvmI z^Vl=5WMg%-}|C8hxVhO%n}r{PzDx|NkY`N~4MqO1HfHCUA!rQ~I zExbK!v|-KT&O3J7#NEbUXIQ`SmpXRie>>~g3!Z4-p|;T@n{Y%Ej%28D%u&ao4YNmx zS3LcR_6Zy8xXnW_%yl~tAu<1D>)6+8g2RuE4%ge|zYlWkjho;oV{hX`yNo0-6KoAZ zH2>v-hxZwK*^EW?c7BF+T1XBU{EED70nV(SYoXJ~6X<=ML>)6VpT@@9LJn zocipdcmC5RpP9O9@k7CXAAjzy#p{Fresb!wi=X;;o2=UW!Q$lLzuTWnt6BI_n~eDL z%$kKCwn=Z|s+wsZv`JC5ujcXpYm;j>UaVO?*e0tN-dgj(KilMwp1rH)5AU_f>>XdL z8GN@*9(nu0n%@ny$uC{FTJz1nw8^gcXKR+d(x7y^zvftK3|FKP0KKhrM z@;BS$k5_$AQ~E~mJnux-ir3oY%(?Nk55C+cyD#ds3tnoI6;Gzsw*R6{dg60xfA&I~ zytc8h_P5Wq$$z$&)?Rz2O~&@kto_WBZSuq7`L$)LO}==druHk3w#m=_U}^2!KMWr4 z14r%DhuY+WOE%O_d7w=udbZa7?*2Bp_W7N)pS`b5Hm2;WwcOJt_w8t`b=?)bu8xzn z4|&_ZJb+7nmWWc+VFUaPs<-nplCi)@oG zBzDx^zMxIsR`s>oFV76#|4sMTexjsJKHBoF+EsaNvi$Q8)V`V4Cfz@Ju(mF-O+NP0 z!?jAh53k5qGk#qA%-^rbCl_6<{qoya@9bUVW~%?a?dpk&m9QJ<@eW`g49>TY3K#`QzFbYoGnn75T~C zy|uNUy&@M}{!Q(tZn+|#y63gphb~@`Gp@c-+tqYMp8d_6wVs1leb~f8+`S&GR z9hGZD{`Hc)_}M(;`0JPCH*)ih@4awI{^&ae#N^4WW;jNg}D zlE1XgHZE8$$)|oW$9OB|l5DrnGiLqcqI6!HZ*2bEMfuLQYGd8cF3RJ-TWDC-Mft+X z#m4_Wa8ahdUt?^(`=T^%HjIZqaZ#?)?Z(@!7v+L4Eipc9xF}T^HovCT%pf-*Z8J@>83P$3JmFPDJ&{tiMU+=0j zUY&D6eqrGbR@rNsh{+cM(m?!rPKLIqv+nV za&X$MM%GPd<*mQC)p)1ztc?Bqr;IPGJ1bA#c$<+m`>gb(-)>w;J1alzz1{f!`)6dq z-Jdpo^4b|Wd*^42?>})yR%CmPi}#KdZ#?@-tNgk3E@Pi+mEw)Nj2G`~mFf3=!6>+? zRi-tx8>k-kbCdqiIXC{C(gX#(Q&` zWzuKvH#Q|V%jxUBY25biX_+^<)42C%r{%x>oyMoTPRplm`IfQmGpFUL<=-|wIB{A| ziujIkVeM&oPJPGtW!Y)@%S#U!THI-wy6C$``X8HQ&A+~DL_FOjSN-67#!tT5Bp022 z&^Y97lKPA;$8bc=&|;(@UmNdHV@@>T}At@9+uv;#!~a?vfKSH}-KOC;NnSJpQ;* z^v~mR>%}LG*uZhQeBP7B)89HSQ~&y;vFGE*rN8qjlEi9~_kxzkAO3{4b8mPkrf{aq&Ax-@c=_4|3$Ip$=9y}r)(|%#ht~nwP`+s44 zFX@Op(Dq9s_N_*_Wd4grjcSx1z4M~6_VbPMi(mVdvG7=%%WFo}9f#z%Y_A)q4BWcShR^jGo~eiAUsk?h z?D^e6dGv!f4E>RV@~H=ZYjoUtP`e=W^`N6;bYGfAelQ(~BzVd28)R(Wd&avl4f3HEg8%-iUe0s>!+7ETdU;3HKaEeGt(VXB{nN-_ zSubDl{>!*4wO;z|gT`BL?v)P| z!S_Be{^zfIWXbLijc9X^j7s>(IDFe4`Pic$8TaqlBUc~!xACNHk9;`&KZg0w-SY2G z|Ht^kQ@dr%A|cm(Znyl8SI9T^?v`)5m&HxnWbK#Zxw_0?Nt^&h6l50bXZmlr0=S-;sL58j?AZ}{34`J28( zx%k)?xp?kWId#q!dDADR$|v97EW2NxDz`qdS-x1Q%V$2hS-#@drDfx0`MYvys%Nmnq?YfQ9`Dn6SoxD-*O-PXoe(jWXds1ZNy-vBXD@8tdz$v35Qsv?@r+j2{ zs_gvh2D#-Msq(!aY>>bHXR6G*utDD7NR#DqgS_{PX)--(gM9t%H2J1~y^O6%m)_gg zOUv!)GJDf{neI~a^8K_`GU;lr{C=-P{ysiWuD{zM@7H`m`FfBuG59?ri({@=`eS@zqNGUiIYeEzE| z^I`BA=fwyWpU98`K>P( z%76TBx%|u9h4LF;TP`!Ji{yg+%VovQMe;iZ%jNW+7fJEkWil#nx~#r$nSAcpbh)v9 znLO7$U9QbrCgY=vW$9~6txwzKl89(r3wo zuU56|6gHdV{h1GD6^glhTi>e+JZPZr2$+_U9s_X7E>f3_@Kv_L+n z&ylbHeZIU5dgjUx z*36TCj~f1?&(ucSXdl{_`cPjw1|5rzNynyh(7EWGbZ#00jfKWUW1}(BSZT~OcDe?- z7P=<7Ho8W-R=Q@ocDe_2FX*1oy`g(V_loWr-8;I6bT8?i(!Hg7O!u1ZIo*4D2J|fG znb5PLXGG76o*6wmdWQ5Y>6y~ArDsgfnw~j5dzu3@7idn<+@Lu^bA{#%&7Gk+6r4*m zr)X}`9HY5LbB^X7%|V)rG$(0p(j29^N^_RxF3n+@%QUBHZqpp6xlVJQ=03dx^e)gl zLGK2=BlND&J45ddy+iaa(K|)&7QJKiuF*S3?;gE_^e)mnN$)1Tqx7!QJ4^2_y~Fe_ z(>qP?HofEYuG2eD?>@xQ7# zQz^DmjHOshF_&U5#bAoX6q6}7Q;eoqO);BdH^p#@|6noVmrt>Ltm)0$3eJFW4w*3+6#Yd_@xlnYQ!K)C_s2$U;O&Oo^X zrl=^ zxew()lnYT#M7a^=NR%s4&P2Hr9p!kG>ru`}xgX_#lnYW$NVy^9h?FZ*&Pcf<<&cz1Qcg*^CFPiu zYf{chxhLhIl#5bMO1UZJsFbTx&Pur}<*<~?Qcg>`E#r&23xi96wlnYZ%Ot~@T z$doHn&P=&8<Qu8+?M^j3)$&x+Q*BQ*KGphE^Hc3l7yw}bgb5HfKo|jG z1%w$8c0d>cVF`pO5Vk-V17Qt>IS}?h7zAMvgh>!KK^O&L6@*z3c0m{hVHt#J5Vk=W z2VotAc@XwN7zkk@gozL~LKq2QC4`v}c0w2mVJU>E5Vk@X3t=sUxe)e37z|-Cgvk&# zLl_NVHH6s^c0(8rVL6295Vk`Y4`Dro`4IL)7!YAWgb5KgL>LiaMT8j%LMHm%fRfJg)c10K#VOfM}5w=Ab7hzq5c@g$S7#Lw; zgozP0Mi?1kW!*u{jIcAp(DH&<8ewXLtr5mXSQ}w(guM|4M_3$Ta)iwhMn_m3VRnSw z5r#)t9$|Wf?GeUDSRY}2g#8f)NLV0Yf`kncMo3s8VTObq5{5`vB4LVzEfU5^SR-MM zggp`lNmwLdl7vkXMoCyDVU~nl5{5}wCSjU{Z4$;wSSMkggnbeQN?0giqJ)hSMoL&I zVWxzg5{61xDq*UGtrEscSSw+!guN05OIR#nvV_eNMoU;NVYYljvM?hQwaR$U45Qjiq0&xn&EfB{*Tmx|q#61uPL0klJ62wgqM?qW#aTdf~5Qjlr z25}n1Z4k#nTnBL;#C;G4LR<)OBE*dlM?zc)aVEr_5Qjos3UMmLtq{jTTnlk7#Jvy) zLtG4TGQ`agM?+ik4wU#MxTz z8Rl?_%Oy^ixLx9SiR&fKm$+ZzfQbtxPMEl1;)u)CFlS8MF>%P(f?P6j%ET=b$4p!^ zan8g&69-LPG;z|zO%q2=Ts3jl#9b4IOcp)R$4*>3aqh&u69>QWL+0dz+&ppg#MKjLPux9m_{8NCr%&8I zas0&f6X!34TapNXzdy>`ALIQWuE{;NEmt31A|Jl?B3{;PaF zSNZy`^7UTj>%YqP<0{{ut9-w%^8LHY_p^uZZx7$^9=`uQ{5*R2`SkGf>fz_t!_Tva zpKlL8?;d{sJv<+Jcz*QoeCgr&)5G(rhv!!h&$k|)e?2@Odw72K@O z56|}=p8q}kKJ@VW(Zlac55GS>{66*Y`_;qmTMxf~J^ViQ@cY@r?`sdgzdigu_wf7O z!|!_!zyCcP4|+I0^l-fB;rP+R@uY|2OAp7J9*#df#Qg{3Q4hzb9*$Q%9KU)vp7n5i z>*09U!||_&<6#fSN0Z~F$??Z&Os=m?uD49Czf7*j zOs>yNuGdVi-%PIOOs?-tuJ=r?|4gn2O|B13t`|+NA5E?&O|CCZt~X7tKTWPjO|DN( zu2)U2UrnxOO|EZEu6IqYe@(83O|Fkku9r=&pG~f(O|Gv^uD4CDzfG>kO|H*PuGdYj z-%YOPO|I`vuJ=u@|4qgNOvVRH#tTfw4@|}rOvV>X#v4q=A56w0OvWcn#w$$5FHFWW zOvX1%#yd>LKTO6$OvXn{#!F1bPfW&BOvYDC##>CrUrfehOvYzS#%oN*Z%oE>OvZOi z#(PZ0e@w=MOvZ;y#*0kGk4(msOvaZ?#+yvWpG?N1Ova~7#;Z)muS~|XOvblN#=A_$ zzf8u%OvcAd#>-5`&rHVCOvcwt#@kHB-%Q5iOvdL-#_LSR?@Y$?Ovd+2#`{dh|4haM zO~waJ#tTj2{)70T$#|m4_@c>pqsjQA$#|s6_@v2rrOEiE$#|y8_@>Etr^)!I$#|&A z_^8Qvsmb`M$#|;C_^M*ORWbgm7>`wq&nm`i72~&x@m$6Du424bG5)I<4_1s1E5?fz zjyjwB;tr!nijE^hE%N672it%*C z__|`eT`~Ty7>`$s&nw337324c@qESjzGA#zG5)WZ4^YexDCP?k^9PFg1jYPfWXDH@36!RU5`47c>h+=+3F<+vXKT*u5DCSob^DT<`7sY&x zVtz(3U!$16QOxHk=64kHJ&O4s#e9%ren>H2q?kWa%qJ=4mlX3&iuotSe3W8-N-lYXDQ~l6!Tq*`7gzMm|}iRF<+*bKU2)7DdyJ{^KFXxH^qFMVt!6BU#FPAQ_SZn z=JyoyeTw-%#eAS*eo!%AsF*)g%qJ@57Zvl3iup&ye57K2QZZktn7>raXDa4574w~n z`A@}ssA7IpF<+{fKUK`9D&|)e^R0^cSH*m+Vt!T;_aEeI74x@>`CP^Pu42AdG5@QW z4_3?%E9Q$8^T&$$WX1flV!l~1|E!pgR?JT;=BpL+*NXXU#r(EnzFRT>t(Xs2%#SPP z%N6tIiurWK{JLVkT`~Wzn2%S?&nxEZ74!Fs`FzFvzGA*#G5@bv51?2dpja=USU;dx zPoP*|pjdC9Sbv~ckDyqepjfY=6l43oRVttchy^~`7lVUxTVttfiy_918lwv)VVttijy_I79m0~@XVttlk zy_RDAmSR1ZVttoly_aJBmtsAbVttrmy_jPCm|{JdVttuny_sVDnPNSfVttxoy_#bE znqobhVtt!py_;hFn_@kjVtt%qy_{nGoMJtlVtt)ry`5tHonk$nVtt-sy`EzIo?<

A6hS1Q(9D%M{r)?+HxXDZffD%Ni*)^jS>cPiF< zD%O80)`Ke6hbq>KD%OuG){`pMmnznqD%PJW)}t!crz+N~D%P(m*0UA9iS1ZE7t!j_5&#P2PpOnDB}Ku7=mIyfntAw zV!wf6|AAsZf?|JyV!wi7|AJyagJOS!V!wl8|AS&bgkpb$V!wo9|Ab;cg<^k&V!wrA z|Ak^dMlf$5@@FXaYbf?_DE4zG_ID`udnopQDE5OW_J=6;izxPwDE5;m_LnI3n<)05 zDE6Z$_NOTJt0?xbDE6}`_O~eZyD0X*DE7lB_Q$C1VZV%G|BPZkjbeX|V!w@I|BYfl zj$(g~V!w`J|Bhlmk79q1V!w}K|BqrnkYaz3V!x1L|Bzxokz#+5V!x4M|B+%pl45_7 zV!x7N|B_-qlOpavh;b_RJ1O=*DdPTvn5bfZlp^jwh?y$(Pbv0ODfU+>_FF0TUn%xu zDfVY6_G>BjZz=Y3DfV|M_IoMze<}8ZDfWjc_KPX@k16((DfX8s;{Jn}vts|5Vn3Q9 z?mvi8EB31?_OB`SvnlqsDfYW5_P;6i!zuR1DfY`L_RlHy(<%1XDfZhb_TMS?<0$jK=7XDaq< zD)w(G_H!!scPjRKD)xUW_Jb<+hbs1qD)x^m_LD01mn!y~D)yf$_M{uws9(BJMxP87lS_E#(RTPyZoEB0e6_Gc^hYb*9|EB13M_IE4x zdn@ApgB-A8Ke%FlxMIJ!V*j{eKe=LmxnjS$V*j~fKe}Rnx?;b&V*k2gKf7XoyJEk) zV*k5hKfGdpykft+V*k7%?mx(>EB4nb_S-As{(~I6Vn4oOf4*YBzGDBrVn4rPf4^eC zzZ(7l0C&ju55GTr{(St9uOEJX`1pDJA>Tgy`ta$)pATO?{P^(U^ZgI`?%}tG&mR7I ze(pnB5aQI~qlbSUzIpiN;gg3y9=>?^;o*aa{~f+}_}$@ihrb=ZcKF%hV~2kozIFK3 z;Zuh{9lmt<(cwdf{~W$^_{}+vh5Y64mBUZYaWdo|hi@EyarngH59hc&q~#(`7(Q_L zzv26a-y1$}_`BijhMyZgZuqz1+lF78*TIlK8@_D#vEjpp{~Eq)UavzwYxt|-tA?K% zK5F=x+=D7k*y&c;VlLZx?=D_;lgVg)bL=T&}Z1{#*EN;kSj)7XDiJYT>7aj~4z} z_-5gkg-;g#SomV$hvhmqMypRrpllPlYcPepL8S z;Xj4%6n<0qOyMtuuM~b#_(MvoQTRmR4}~ujeo**8;s1p16Mj$lJmK$zuM>Vw z_&DL;gl`jmP53n7&t%*z_`4*oaz-r#qG z&kg=I=G{VmHu%`!UxRNAel_^i;7@}u4SqEE(BMCV?+ku3_{`uhgRcyJGWf{gAA@fU zelhsO;17c@41O^9z~KLa?+bn}_`Klng0BmHF8H|M--2%oel7U4;Ln0D3w|v4u;9Of z?+Sh^_^jZsg0BjGD%J^v{8R8v!7l}$6#P*kUljYH;Ddty3BD)zo#1nVzX`r3_?h5i zf`19VCHR%#Q-VJUz9jgO;6sA{2)-lujo>qazX-k}_=(^nf`16UA^3&h6M{boz99I4 z-~)pH2fiQpecc_z zzXQGw_&MO?fPVwN4fr+S(||t%z6|&=;KP9b0=^6QE#R|&zXHAr_$lC{fPVtM3HT*g zhaB=pz!w2O1bh(iKfw0@zXN;@@HfEM06znK4Dc_&w*bEadW06zhI1n>{QHvqo?d;%eV0Q&;q2Y?R%`hV#Dq4$T*ANqdi`l08CjvxAc z==P!4hfW{*eCYC_$A=Cd`g`c^p|^+59{PId>Y=BHjvo4X=;oo9hfW^)ccEhfW>(bm-EdM~4m_`g7>cp*M%l9QtzT%AqHR zjvV@N=*FQJhfW;&aOlFJ2Zs(E`fupIq4$Q)8~SeOx}oQWjvM-I=(eHPhE5y$Z0NF~ z$A%6Y`fKQ}p|^(48v1JJs-dTbjvD%D=%%5UhE5v#Xy~G$hlUOs`e*2#p?8MP8Tw}E znxSWgjv4x8=$4^ZhE5s!WayHiM}`g=`eW#hp*M!k82V!9ilHZlju`r3=!T&ehE5pz zVCaIO2Zjz9`d{dNq4$N(7y4f4dZFiqju-k}=ysvkg-#dxT)p?8JO75Y}_TA^o!jurY<=vJXu zg-#XvROnKnM}-a*`cvpmp*Mxj6#7!=N}(r(juiS)=tiLzg-#UuQ0PLT2Zat4`cLRS zq4$K&6Z%f*I-%!;juZM#=r*C(giaIsOz1M9$Ak_O`b+38p|^z268cK$Dxs%@juQGw z=q90;giaFrNa!M=hlCCi`bX#p=`1fQ& zIz;FXp*w`$5IRHX3!y87o)9`h=m()2gkBIjLFfaa3xpmJIzZ_Ep!~{S`=INC zo)0=c==Y%8gI*6hJ?QhG%Yz;dIy~s_pu2!7QHo(?)X=;xrDgI*3gIq2h{ zi-R5xIymUxpnHSf4LUdI+n{TMo((!S=+~fIgI*0fHR#izOM@N_IyC6dpgV)!3_3ID z%b+WRo(wuN=*OTNgI)|eG3djf3xggEIxy(Jp!gTVuX{{`<0z85?%_+9Y2 z;B&#_;`fum+k&qJPYZq)ye#-w@UZy(VeqctTfwt}Uj?rUJ{3GF_*3wv;7h@if*%Dh z3O*D(DELqCp5QydbAsOluL(XAzbgy=61*k&O7N86C&5dCj|2}1{t>(*_(t%I;1|Iw zf=>jG2>uYfA^1Y@gy09k3xW>>4+#DbydU^J@O zj{^?}{tdhv_%{4*B=|M(YT(nrqk%sIZw9^$JQ?`05HH5Rmk1sV{11CIv|5BwdtJMebk?7-K7s{>C5jt=}BxH<50;N-x^fr|qV z2M!MW8@M;{Zs6R&w}EQ|&jyYS{2I75@M_@Hz^8#r1CIs{4g49nGw^2M%)pm{D+5mk zjtu-5xH0fz;Kaa(feQl<1`Z7T7q~C*Uf{gIcY*5y&jpSP{1&(^@LJ%sz-NKW0*?g_ z3;Y$hEAUp}tiV@+s{&62jtcw~xGC^b;H1Dufr|nU1r7@Q6SybvPT-utH-T#c&jgMM z{1Uh&@Jis6z$bxA0*?d^3H%YbBk)GxjKCLxD*{i1uNn9ua6{mQzzKm50v7}x2pkaj zA8fKLIJ0v-h%3iuOn zC*V!MnSd_=R|1{{90~Xla3kPFz=?nl!AAx>2sjY%AK*T~dw}x*-vO=zJO?-q@EhPZ zz-xfh0G|Oa13U&e4Dc7=F2GxWvjATKt^zy-I12C+;3mLJfRg|p0WJbO1ULxr58xia zJAiWl-vF)wJOele@C)D;z$<`L0G|LZ0lx-t2;dLE9e_6gX8^tcTmg6ja0K87zzu*G z04D%G09*ig0B``*|ET*>@1xE~eUG{x^*ri$)bFUe^K|M-bI~@`WAI9>RHsWs9#aHqFzOv ziux3FDe6(wp{PGmccR`zor(GqbtURa)RCwkQ8%JqM4gEG5OpEyLDYe$|4{d#-b0;- z`VMs+>N(VLsNYbxpbDl?h4gg{JZX`uTWQ^oW#LOp~!2=x!@9@IOib5P%)u0cJ6ItKL%>K4>1s8dj%pe{i@f;t5C2kH*g8>ll- zU!bl)J%Ks`^#ke#)C;H+P#>T!Ks|su0Qo=ie&qYe^O4^puSY(QJRbQw@^<9w$kUOZ zBQHljjyxRsH}Y=e+sLz#Un8$ZK8-vY`7`onb-l$WxJ@A}>WgiaZqgC-P3@o5(YfUm~wWK8ZXM`6Kd1qT zK7~9A`4jRcB249^^a7bCBO4uR%V8JO=p-@)qPP$WxG?ATL2a zf;2eXRFb=dr$HUB`Nk zbsXzA)@`iUSf{Z*V_n92jCC06FVnGMtte03Pu|8s5#CnKz z5bGb-J*;j%~itQS}(us&d2z9`PM<9q}A-9Pt}*8}S-(8u1x%8Sxl#81WZz z7x5Nx7V#Bv74Z~t6!8;r6Y&yp67dmn5%Cal5b+Oj5AhCh4)G0f4e<&+&fa zy~g{D_ZaUl-dnt{cu(Z+Oq}e&M~s`-Jxh?+@M^yf1i9@P6RE z!25vr0P{aI?}vX6zX$Ui^BeOT^BMCP^B40L^A+ zpG$~lw-8YtAyT|T6txR6w?l~KokDEs65>F&5UoBTV*Em+1%xQ>6=Hs$5G(tIxN$&; zLxVz`6_bRfO%fJ;lCW7OiE8U4;jm2-bybr@WA!BAvQHB6j!7cZIZ2e&O%jXhCyCXK zlf;guN#dw$lDOcWBoaK6M7DR5sA!)gYC0x~wVjj1uC7Vqc=sf6$u~(P`X`Cpz$7uF zcakvrCW-a^lf<5ZN#f+-BymNHu|tP z6mOKfs6EO(wWgy6_@mrufhc!zZ^$;E_<{)-VyE2bVj?&>Z09?>Z9GO z8>8JjnxfrDUD56f?r3*{C)%CujdoYGN4sk}qTOpdqusl@qTR>4qurN$(e6Zlv^zHt z?Viya?Kb+N-Rt|K-FpV2-6sd5-B+|2pRULFtdKI>>BgU8H zjPVuJ#rS5|$M}{u#`rch#rXEQVtmb>7+;Dv##huH+F)>xmz7VE34iuE;C z$NF6MSYNy&)|csw^_A7d`WDs4`c^l_`gSzM`i{C{eHYxZz64LKFWVdIt7wn))pW%A z)^^7Fc6G)2j(5lUF8N}8iT+q$ZXnh-qc_%P^u_wt_s9D748;0Q4#xVfXquR&Ya-vG ziCI=nEU{@~W0fWvsx@)ip^0RtCJO5`F{fS=%NjMYxk(fIU7Bd|Xd>0CiRtZ{nAf3+ z6`h*c+NFtu-I_S#*F<_i6D7TxSkR}58~Qb|Z9o%;2Q_g{ixU}ooG7)#iG|iUvC0-F zwpYc8Bh_)@ygg1#cEpJ+XPhXnixZ3M1*coX88riJ84|LiWXp4gGOq??9Y5H5ez_w0Qe8J>H&g ziMP+P#@mczd!l-d3$KRg(3Kc`K$ zXXumdrIyL|h1SXTRkq3Y?NyWQN2({=&pRgDvz(Ld<#m(oi|Z%b*ECMH?`)cEKjxZj zzv!N9pW>Np&+$&SSGG^K*LF;{uj`y_-`zFYexiG_{jzVeeX4)5JufiXKC^eSUG`13 zZ|I+F-#akberj;Cy-iDSPtz0J`IZFtENg;$i7mmsu`0pcP@UjD?MQGZI}_Z6bqVe{ z^$G4}jS23}O$qM(t^{|BC&8WSO>j?dPjJucNN}&{OmJ`QN^l?SPH>;`C%DrC3GR~K z1owiz1osX73GQtJ3GTy#3GQ>+6nBO`#a(Kd;$CQ-;$CH&;@)00#eJlDiu=4{iaX0W z#a&)E#l5(GihE7t6!*@iDehygDejA&DefHa6nAC&6nAaM6!*H$Dem1}Q`{%Ir?@Zs zrnsm2r?~S1Q`|Fqr?_R`6!(VyDek=kQ{1Npr?}g+MBg+$(U)&Y^v$v+`j*%deH*J1 zeGS!#zSE9GU$QgNS6G+mn^T|YTh^H9+uW4s+wV&BwRjSJsoq52^!7yGypBZQiq1se z)~-a~!R|!g8GoWLJ&@=t=}q)4=u7n7(4XkrHjwB$JecS^r%m-`=u>^AmZ`pl)~UW# zwyD1DRa1ROs;BzSJEr=woKt<}byIzd>!zwM_-8I#BqI;_EvVW>CFEG_Nvv;ab_D%I|=%4D_J22IEYH+HrP1iN6Mc1mV zx@NcOnzKsR>Z^6F$)RgWPF*Xg)3w?4y0)}Y*ETij+CG=AHG6a|#j9&Y?YcI%L)Vsf z>e`krT|3aNYps4=OAF{)aj&k;@6)xF{knGJfUX@H)U~tPG|i$<(`=S$TD5hW=CDoE z>Z+z`jn&gMmt&fi>71sO)lJhD)lbt_H%`-bG)>cvx~6FtJkzvn?=-EVeVSI&F-=?B zIZfNuHBCF-Jx#mhpQhyorfD;Jr)fstG;MwVG;PnoH0|WzH0_F>Z_9+P0l1oL0yt#c72j#X=9ROQ&W;-pDW4H>`8K@c#|AO?MaTg9Z8Pmok@-@ zT}h4u-ARsCf083DkmM-tO>)fdOLDC2PjcKikmNWtnB+LCB|9v7vcqOcc2rxF9S&Qv zqpm91(O8}Aa5<74na*TKSzWSYQGK#wbz`z)M^m!ns4LlV!ISLB_9iZz+r z^)yzedR&fFPo^`~Q&yMiSyZ3uS>2fG+0m5hIqFLFT=1lNvc0LEiuP1bO-HI{ZD*=y zS68a%cz3Gjl0Vgx8%Xuc=uPz)eW{-H{i&Wk1F4>qgQ=b?dYa#AN%L1()BJW@n%`NK z=C7|#^EWxu`~`Js{@L|u{-up+{!LA3{(Y`Af3r8uU(}xFpWBhjZEmt?`&|~T#cR=~w_CJ%9Tsgxr$yV^Wzi0HTeLF)i&oNW(H8Vs zv>W;@+O`3Uc6iXDozpY4QcH%m(3+vGvSn!7t1`4B)fw7(M~0T=%+Si~GPK3@8QPl0 z3~gsqhIY)Ap6m5BbS$xDIyP2iIvT1o9jBd{j>5W3$DI01$Fjyu$L6L? z$9`9)qs5!)nBJc0nAef%Skam3*xHrpIM|)(I1|Wpl=Nmg7W8F0Zs^Z+Y#YdQ93ISc zoYS)$rIswmLTi>|l`YG$y(-Ibq&mxS-kIenugh{QuFrC;Y0Pr$Y|3&Rb7eU$da@ij z-YiFDdzPcNBg?U_Gt05NE6Z`BJIis|pXJC4WI1N`W;tYEmSaPImSgWgmgCf5mZMG2 z_T*c#J+rLYo+Y+y&&H~3PeXOK=d?51Q&^YnnNy$bS=N~C+1!-v+3(8sw0N^U)7!H> z^E$FUD>}11Tf4G72fMR9X9C%tlHP33g1&6e4gJ}kZ3Ee!!-LtLb9#=a)RN;_XwC7g zvgLTTSLJw)ROfikJ99kcbvd5J^*Nq3jX9p3O*x)pt{l%rZ;q$3J;zhqk>gp{nd8~r zmE$?lo#VOe&++61ay&D8b3C#y$Fre7$Fp}J$8%~h$J3_g`tvQh{#n*s{}NlSe`8gy zzo9zUf7+SrFRaV;&#BM#FKf*8Z*I!Fv4xc^$d_6`i^MtzEhPgWb9Q zGl5)xNpG%yL0_)_hW=dtwt-y#;lW)0IX%x`YRU62wC4F&+4B6`tMdFus`LEkoq7K9 zx;+2l`aJ)d#ytPdrab>KSDyc(H_u<$p69Ra$n&r3%=7Q=%JZM-&huXm@= z)tkLmy{O%)&+V}4%R8<5mM*J)pxdgq2CRBuCocVfLUB14kK3`wmn6K|>%GZy&^7RYee7&MQU$5!N*VlID z>$|%0_2b?7`lUd=KBG5ZH~RAR_5Jz!o`HP*l0_TD50%vQWz**c|;GExA z;9S{X;Jk65zRcc8>$tgg_xsJ_s-y0Or? zqp8q&)K%!b;4O4kv==&SItra@I}4q=x(c1gy9=F{0)@^Qy@gJruh6-^ztFj7pwM}8 zu+VwMQsk|&7J2QqBCoTm$Xj1s^6qmLd7ImdymLE>yvsX_ zyj!}8ya&3Aysd#EZ*gytcYa@ycV&N(_r`%D@1emW?^%7i*JhdSt+r10I&9Oubyd^7 zjn&h=F6VS_S>1H+qWbCH)s54=JDR3@kGiINFLEUt zdnqv8JEM2H*XWz>UEe?5yJuj!_vGMo?-fgNpvqbtu-l3Q&Z^=-eRXl5sjfIMyS_NE zw6Qp_si`=y&s7{~ZZ8hZ?I;c`?<@{%=_(E!=q?Vl_7(@`_Z0_L_7?|k94HPP8Y~W+ z)k^|4OG%*GS`u*BN&0u}8g zftrqzz}n7|z^<;6!13;qz@=`HtoE$6(T(Q{nSyr3A#Aees zR@wB1YMXw#&Zf_)x9Q6oZTjXWo4(&=(_7kY`n(RCzM|8nZ|$<_2fJW|pwFh? z&~MYX4cPRT4QH^_@+n`Y~6j ze$iX1SGJexwH>AUy3SI4cUP%?qPtYT94OUi_Ll0huTWnbDp!5I~Q8ZovUo+&h1s@&Lh?3&hvHU&c*fR&NYqY z&Yex=&SS1}=S6S1v$DP1S=&+WT-RCd+}%~~Jkee5yc{TZ&g?CB%D!^vhW>Kr-hp!G zsljq*o29}#%Ua=GVyp0Otg7%fR9ARU*Hw7u)K_?yHCA{xH&uA|yDGdb?G@g69Tnac zofY1#T@~Jg-4)(5y%pXCeHGpt`YXKK1}eOV2P?eiES27c)=KXxTcvkFKqtI~V1z0zCTQR!XRS?S%~Rp~v^UFp3XsPxY4t@O&iO7DjL zO7Gr*O7E$`N^hHGMqrk8Mqr6;Mqp#rj6g&6jKJx-8G$+VGXl#RX9PAk%?Rvw%?Px# z&j`%xm=RdfIU}&OYewK;_l*CKiZ_qZ9O>`-_}qMM_H)*Avv2mzr~7%j`Sf#fZtk3% z-JKoo?CdP}m>tgU>@N41UGCYGEdexQA#|)H{KIh=8L){Y2pHQEm;(qQC;@{gF@*#H zjldCO%L?JViWw`C8C$ke@2kH&56CK#RmI_t^{s=SU$y(vJ9N+dL-$5-=spY&-DlCE z`wcj9C-{;33UTDVNglb+sU!DW?#P|;NA4}*$bCyZazB=i-0!s`cdj3~cZ?(VZS%UNbr?Mf>WOa*8>u~5t87;hy-7QA)xRfV2B~$$RQA@A&|HsIOm7p zrZ5DL#3A@d8iMb%A(-hyaN8Jy$L0{cu!i6VZwMCt5Zn!h;7K?HpGHIQ6MoFm#4*Q` z#~e=`b0UAtT^5eHSH)xQJ?WVHLObS0`Z0IaIObkAkGT)5W9}>Om^<~4x$D6(_eOZk zeHa~cUxO2l!cRDcIN><*gcGO}PU23ubN+<8DV%VR#1rl#>4f`EJK<*f33uB#;U1eO z+zac3`@uWm7XAr$H#p&*geTmm(FykxKGJAnq_N~kk@hthYZN}#7-Fn(e0lh z$C9TWPn~)qf9hQpPQ6#fQ|~?L)cZm|^{yJH-s|S6_knfledV8e*Mn2W;+(rro^$U~=iKM~Id?@k z=Ux-fx%Z`W?o0igyJnno56pA!sddi1^v}5)!8!LZJm;Q8@DFL=Q|=XF%DqWWx#!fB z`<9<_w}dJ8mN?};mZseI+LW8?Q|^v2<=!@@+$YwQ`_Y?nOMlAU3#QyV;gtIAiZIh&6KC4{(oFkOpJ~^OnfAb(X-}=0_R^neH-ee=Fq~=6 zqM7y$KG$9$=GvR&TzgKkc1xIRZ;5m5V`;8^ug|qR#$0>boNJ$0bL~fOt}Xq! zb}yJ~?}T&hvuLhe;0x~(vGDGb3-4WO;eF08yeq=Odre$;?@J5sOMT&8GZx+hbKyO; z7T!yL;oS%p-otR=J&P9JH~7+fg;;uTl1uM7we-H_m)AfW`y^p1(_r1RK?ifq& zZFA{;VlBNN{iSy=SbFb-OYgI2>0J;s&XP3FQ#3B}G=5p2@mEC}e@~+EFLWBeYS8%W zCXIh!(fC(Bjb9IF{Ed*tKa6PnYy1+<5SMU{yo3wXC0yb!;Wvd#_#^QW{*iPE|4zSz z-!?AckIhT?3+od8gMSIX8(hMlgqQG7qf7Wt#ATi(FY`QgnHPo2{Hx++{yph3|Al^; zziM3OUpFuFA6S?9ul&pW_24r9MtGV3FuKftjbGsz;tJ1^S9pQC!b|)W{-$t+e?{Rh_4<>Y{K}e^tDy zzb9SQzc8-qubWr(53H;DSN>J~dT>>LBfP4A7+uxB#;@rNaZTsQYq~&P(ZR48$*u18{u&(Jp_}BEi!8QF!cuoH_x~Bg`T=!Y>y3bSBeNnjX zzban$-;=KUUl`Z@*Ujtx2iA4}tKho-MtI%-FuLx4jorbuQ`pe+9{xH0)KZ|bb-w=27H_1EtbLx)%t#C(wOT43hEZxz+H}2?f zn|Jh2tULOT{vG{Za7TY9yrX{>-O(?IyZ(LhuKzA|*Z*9&>%S)6_1~B7`d=D%{Rie< z|EYD?e;M5MABK1RXVG2%8{(e-CV9_)PTljr74G?OiTC`ErF;JO#y$US^Pc~Sb;j6-j(W}DO#A^aaz9tCNYl0-aCOi^f6F!n&6TUNE z6CRtd2`{YIgdc*}geT!^!l%(|!cXMu22Z_ih~n$Ud(!L17v}562iEJxSHbJX8{zB5 zhtccC*Te&ZBOe$7^}vvX2gW1uf$@>_!1&I1U_3S-7%!{`#t*>*<4O3y_%wQ8{6xMH z@YEZDD83QAC%qATVZIT3V7(E16}}OC7`+jEO*{-Z@?juQ4+BYf7(5am1|LZegYS%o z!DI7b@WOf+{17}0o`esBPosyyPb5dYOL4^KB1gP0am1G5=fI`AB$bJrZ7qkA!E@BjFqJE#W!!mhi3kmhiFkmhiptmhiUumhg%7mhfZnmheva zmhf5hmT*BnHr}Nk8=s4hjrXO;#+T+}kHOoEm?*!k9?*t!9?*!kQ?*yM%?*u=F?*yMk?*tbVPl_T>z9;eI7bZ`BVDaQvAy0l7 z@#NR!yQDz9OG@IqM1Q6HG1^nv+>^?~_S_<{Lh z^nv*``P3Asr=}!6H9wM`n%|jE%@@{F^M~-M`Dygj{E7N76r~TtFRTy4uc8mbugPbj zKs^g3@mcth^ep_&d=|d2o`pYz&%#fmXW>tjKz=R>E}zKjI&8|pdvt@xb$Sb9!= zZ$2kKv7VDZhR?~*qUYoV^^y3w^pW_b^^y28`bhkS`dIu{`dIwl{8;?N`dIui{8;=f z`dGZ6UYMUtFU&8k7v{_8h4~HjiTSPciTSauOgB9n);lQq|d4Etk0<*qR*+HtS_XmqA#Sc zsV^l-`cnGN`cnEK`cnES`pWv6dTB}0OY1x9rS(Jf()x+|CX%FYqVKG4q93AfqMxL1 zsqd|CsUM?nsSE3S>Bs1M=_2~kx8b1gHo?Xb3{-2$C}pq-`R|u7x1yHi8r!1nIg6vhN|t%tw$?fFS)4 zK@KAXSs*baiNEoZ#%Mx|(Ucyeb4HAAn=yLViqYqGj4n7ay6eX1eJ@7O{1{ydVst-@ z(T7otULbJ_oQTU6GA^%Caru~z%Sk3K*Vwqc!NuhfAD7cYTyBVQ zc}t4Rr*d3ImADMlxJ+nqnbPBO&WOuxGcNC1arxYi%LOMccip(W@5SYrAD2r(T<(W) z`7nyh3nYOQ(1eX)2^$9qo5T}xfk@aDGGVV#3Hz8%*hwZ~*Vu%;!6obwpRm(H!fuEO zdrL~#r*gtZm4pq{giUA(o6-|@&Pdp8Ghy#q3H#hm*aatHcin`&?ZB#|MWL<&R_sgg-#ok}7nbP`E1NuETNLEQAEj5YkXh~$ECy~67L^@^?*|U4Aik|2xI&Y-tj+vtOtQ0-9Q*_Zu(LFasA9yKx?x*N-kfH}+iav@`^b$$a zD4Ld6u(Z4i((({b+bEHit7KYUr_%BXou;!)TCTHcd6P@aV?HfsgtXig)AF{Ime1t0 zoK@0tOHIo=T3VjyX*qAC<&K$__pG!$wbOFZNy|MqEgyJkdG4p>a*&n>VOlMOuV5K_6=duo4mmrKv8!apUZ*nl37w&fOvbLW8GDn<*ke9pXM~L16f^d=l(Em` zjGa|7c1z9JJ6gt`=ove2WbBTavG=TuJ+(7-(aG37H)9`o8GG($>~fH?2VurOiZb>R zK@ki^Q4H>IfTARh${2y76%s|)C=@-WA-88xw8o<728W^}9+g)F6m5tox+S6LsSNWf zC<;^*B{USJbQH}QDB3nrbk{=Ba~nkq4vKbN6y5hwbmpUIDL~PFh@yuPiY|~WQbV&0 zhGiKXWEm3A$~7X(RLCr|MrD~}I*ZhqEK_5%%m$ZbMtoMT3t6TiW|=K1%bdztw5DVk zpk^6D%QBRnWpYNAX`5MQ*UB>Ic9tnPS*Gh|nSC$I%=|1<3bIT;%rb{jmRTS<1fV$u z!*U7^atev(WI*JU3Yk;ZsGM?4=a3eYQ)+BZ+2C@@h|kF_A*VFNoU$e5lv6o}0wt#a zHK!0-PN8%dH*!kb%qhE8PC2)8O2Nq~T{oxfdpTw1=af>AQ~F^}IgE130?8v?H1A+o z-oZiMA@RK2CGt*%%sXpT-Z`f8NRP=oH8$^TaCv9M=jEP|cN${e*^=_kshmf?Yvi4_nRj-rymM~nor05hx^CXt_wvrn&pV|c@ASjGa~S2F1yZ0fw17g6 zk3x=*LXK}^L;P1$#v(piQxWZc7F9OfE2(Qb1d3 z0o~CG=tM6#m{CAGW&z!^3h2}>phc&E_S^z`;1$rhUqH)20Ud+|^e8HzOQcBG&?2*f z6`55~WQKUrt`SA1N*0-Qs>qzsMY_%unL1l!Hn}1*=8JY+C^Aj4$ZShR=1eX!HKoY3 z)FQK^6`6@%bZSPC>6k@k&nhxg8|HP2OwTPc2VRkx`$eW46q!L-WR9XDvqVZXKuZc_ z{0e0J%Fh`;AWBM=EGg?$NjafQbc-n|b+)8zawTQVm+Y2MQkr5(*_KMmnOtIkQc_xK zN!ig#%0w?Yz$hslv!v`C@gJCrm!!|e!8}XRDDqvVc#IP+1!%k)BKcHY3P%(_q zFpSbM1vfCPZDQE2g<H!X8E|>;kDE1X{re ztfE3+0TucR$OKVQD`Z7oqblk#T|su3idthU>IPR)M|?%z5h`j!tf*U3MLm@(D4|qT zpjK2utEiM-Q3#`=w#|yVYgN>9yMpdG6}9VD)P1j_&isn96I9fGSWyq7in>6m$Ua)d z_OYsqgQ`p7Re7JNs{3TsU8Ab*Fq(eNtYLdr4V&6EX4R=-J-3D(cr|S9*PPX$h7H0Rb`;gHB~qt1 z&^o&T@30E$>=3Wp8${jRAnWWpRcBA=I=#u%*`NP5xjH-M>-MHlXPaW3-InU?nOtW! zlsel|>+FtJXD52y*)ZyC$E>q^R-K*Nb!OA4vpu)Y9(Z+j?$@2opw14$I(rn=*(K7T z3ADiySVLU}4Rwe&Y=UUG1lds6sfKz&H|QOv!S1jPb(3qTW4>YU2o1FpYp`OVN zhEN)6OKqq-T0@=a4TmrqYR7D-dsai8+6`vMX{bH7p&ob*b?!HuouHu(!iIVjHPj{2 zr1#M#yN@;9RnT;Yc+=h|n(jW?bl0h-dqOwq1E$FyuuXT9Yr12;X&(qpw<$K=ZK>&= z$xUWoX}T@7>F#JvccMdI1*7S9%%;0%HQlM*WDcCB+jE=lf!B2Be$zP!n(iQMx<^sd zT_OM>QGk&c05|}E#DPo_KqW~4)+hjuX@CqFfDKsyHaGxAJdlS1P=_J_TM_`LGC)ZM z=2HP6Gyo_aD5L>E+XP_O0^r<+J`fH7T^E3T4}h5ulwklsKLp?~0$_o(kP+I#Mp%o( zL5m~tmOLU_>WFM{YgCInrd!CEX<=iw#cgmcZp63bvCvY-VvF07THLAJLPtsqjMNrK zXf2M?Tgu32ac#53?OHAF+-{*`r^R*M7Ps%UxS8Kl#zBkghb`_fYH);74dHsagzL};rMv8`=MZS7QUqmwc`<5 z$D{O)GBY~b%wQHJLuf$cwM*S?Ry<>=695N(DC|V$2*KV-U8{;B-&+3tP7xT z1c1H~Hc50{lI((YstZo&EZeAgZdU3VyU!M4-|XL6Szl`coBU9h8d z!9?#mq|xZWZ*n zA>Ok`M9&?OJ#L-qaVK<-9y2|5%=WlVuE&k}o;?2V{q$L(l6 zZld>`kx@*W>1X&lv|jZV>jkqo~I%kv>hKeU`%d8uY8s zpkIYe5q*~;``S9y*G}j@Jz@IngzamaTwfdWeS0GG-HF)OwxzyyCifXi>2s9Y*LJkN zHqrYIW%NDD>}z{gUz^%}X5#d@iQCr>yuLQ~`_3fjYlE<_9YuX@i45o&I$&qmz*_|a zZ-@`<88L8YeRVpZNDSNSz+ zl|QCeVV}Qhud=KB2Di$O_*Hg8ShaV=Renoac;@4PGSaS$*P2ZB%^iz2aCzUmYRM&JuThl3h4Uoo~ zLYZs&uC=D0+iN`OtU08+rtf=e`pjPg!(h#!!ZrOcTGJQEIx(0JTK5;|hP;7o;2U5A9}*k# zKDmJnsSW&u-hg)Bus7HZe3RS2$NUDiDQwvL;s(AgZQy6hhCEU?@EvUfpXeJ5X>7lE9x+?? zh}~jF+?GD(x7d-eXyEvZRrzzizAIKWoB;ad)AgdwYT_@ zv*nE3E&agT(&zpbHw?C%S-7PiMO*q3*+$0bwminR(J|Qehxj%&CbpFWavO}PZU2Pc zhV9w5J!ZF=F}LlH`E7PAY&!?yw!bZH`)BetK32AsvAXT=Xxsio-{wZfwlX)j{XJ{j zpW55}*x7c*?zVs6ZToY7n;Qq)&OF@qkD_gVi4t)5PRIlx2$CRFxKjv>HJHj!&L+>*?{64#5?{hoC zh~HuMg&lWC+;R4$9pO~ok@uAyb*SzT``V5`={v;8*ik3uj<9R(2JcaGq6xa($e2<}sJ%J+k9E#ctj_Eym#_aJk zcF&%1d%=j`V`jphFcbHjnY0(2%6lxO>}f-F&!x1zfYSFk%GlE;=AK7cd%?NA$IhHR zZ|Lp?``%tK^Y^$}u;)#}z2Gp~3l``;zK`w8`(U3K68mu80DWeted2`Phx3Mg{D9q; z54e3|%rb6=pWePU|wV+YQ@J977l18<+0 z`}^P^*mq~)K5-Q76HD{}Kfn&;18^V=i39b3JaC89fpEec@CWRHeZUtiE^lo z)I)Wm9U2q;5KN3iI37CGCf1=bwGXkmbLfrSLv`*Q8gu^;%!5O379JW$(V?+Kj_3(` z#80pzdjgJvA%4V6h$CS_9yt^0C^(^yV1InX&)Fk;&K(6~{)m|iN5Wh@a^})ea3&wI z6Xi%7tI&@}I|?TH5jQc8w7GfYO{}9}Y9Fz4=g1qo(0|7}3g-S1HxG_re+;+iC|ClL zBq@?Srb%STkmwMO%!V9Ej(8Fu3M4TUp|6falBWu(lNwBFkUC|O3T2VxxlPJLhxAF8 zREHi(&U{iC2Bc4gq%w&}a)AtC+c-o=*bp0mAsFF9d<1LFh#Zn5YA7DlLpatRqGNW5 zjk%#X;)nPczU8qvak2=$0!Ak6$(GbDB>87wT}Ts9h=AWF-bu zP~NdQ^N&R;I1Z@rSer!0<^nl^b?Zc)U?=DVoG26g1e*{i>V!N26Y4~p&?j)LcVbW2 z6K2Algd_fhod_pztarjqq?7PeKEWr-i9S(Jh>3O*Qu>KDGER(%d7{m%lknU=;U~_C zKXFfliFXpt{1a^)oCK5bM4Lw^;R1}Hokw6okD#4L(9R=h=Mg#PN6^kAXy*|aOC$13 z8R;W!L{5y6J~KxSWsS(GJ%Y9!`6G7(Z95|8{s`K3jIlm9$Ii?ei&JOpkG-)t561pH96R%9EH05#IR7}6XV@t^1EvI}=a2nRIHN$*1^CIn`(CDKXPd&53?W z&WuxIW}d?K>(rdur~J%0^=Iy>F!N5$xqm9og419Yo_dq$)LbHG$Q(VB=hzuK2WQG0 zKf~t4nK~!Wz??eM=JXlV+nGIQ&zL!P=FIssb}pR3@$VTom(Id7`3#>cXZl<{Bj(y! zIML6@xp8L9P3XsDorP2TjGsGa{@gti=H6L2_s`(-p9S;q4C?JHTvC)q(G;BHQRoED z0wx>ED2t-bZAzXvlrnKCb>dOf434}euy#=qMJ+?5q z%LzKeCfE#2zzm<@Gh#x_$O$>4Ce)0cAaiDd&e;hz=b&#BKf&k11h!ohaxP80nLLqa z%0!u|6LqFdv>6F3nBc}|}rQ|26-vgi1eJ13|7xjYrl)v0){Phsg(1*X$rIsDOvwd4l^4WRU650KK~2pC zJw=wx6kD=We92A8B|nvy!c<*~Q++8-&80j=7s?bY)G4vhrqn{8Dhp$(EzGI0u%_0+ zo}x=<3YPAaSbEcF=1-MnFx8gf)L2H-XhF?jy_`W?&Y&%4(3Uf3%Nexg4BB!AZ8_8C zum;YonYplM&}K7evl+D6jGFs1XtP-ef5tqTQA=vB&84|Fhc#wy&CMmO8FO?YFQU1$ z#9#;($^wTWv4GD9E|jITFqXfOBcrcrL+uT3LT~};17CY!DHxYzYJiA{yD#m1ITT0$ZHA6Ye~pyDadJQ$Y&YI zXIaQ)Iml&s$YTY_V@1eeCCFjrU+`NRQxQ6@A#_DY=%j(rH4~xJ7D6{{ghm~N1};M9 zJcMrh2weyex*H;NDMIKz5<}qnX~<7wava3u3LcY_L`<%cF*!}eHYVq| znB3-LazTj6T`?w?q?p{7f5C5UOpV!bEoN8rn4L6YcFm00X)9(o?3j%@F&nrsJLkph zwjZ+#LCo%kF}oDS>^|}fev7PNaU=oaNEMGGDI$*4$vBds;_ypb9LX|qq{YUOJQqhg zd>knXaik~4k+Kv=27k_P=@m6jC$u!?lbG0;6)zgsWrJ1^!W-?ZqY1(Nf>!g{Mn`ZJ}n(6pyrWmA|UYKUe zQJNVb85=`0%FkKu3dkr`JmX+QMyZn-B|~MDCY@2TOh#$3870qUln$R!ib6)|i5aCV zWt4%Ov4N6tR#eDywTx5MGms@^oVuBDGFHZE+8HP7WSo|paq?cq>G&C^7-XDYm~qNc z#u@w^kzx2UYzfczG&wN?R}RdZZcZSz^RAY|39m{m(sR_)7KI;Uh^OwH1HE$deF zU+`PE2KjB?%DN3Z%jTS{3*4-m^RjN+&$@*m>vqGeTZ*!7AI)JaAcs})9KAy1usWHu zSEwA;WO7)G&0%>ihjsWIRupnrPt0LuDTfV|9J`|CyXdpt-RZG@@~t^yB$C87K6Oo3-fL{ z%DV%kfK<=|z_0>R1qD#S3uuKXfEo$eEL8vvx`0)f0sw3Qt8xX<=3yG40J>rUl%xXa z%LSyZ6gW&RARVp1RrCVdHVRzLglyI-a1FbFwVeV7+yd6|3S8TVWdsGT8y2`yRN(rM z%T~~$hG9jz3W{0IT+=S8ZKuSw+>+YyN?gY;Y3-oI^}-TYj!N7BDccpa ztU)eoS3y~;;$^2ol(jku*(_DonsnK%FlDX9mfb2>);fIIs|aPSCziFcRMrM^*={Rk zZ$*V`wzaZXgFwc5gp-W6ArwzQ)6VUJf)RzO9C+*VuhEBXom#)@AvS2SR)_zimn zt2!$_fDE?kt@v$!1+;?|zZ{_n{)+f zF%`VUR_GR2!8<&R3l+R4R-B4d!3S~$X)6`9tybu^R^hAgf8I7KeBG?@ZL7jJ?F!Oy zDtybW&>gSBcYIhzP~m$aj7JrIfK)MnRsmeY%>q!>t9X?GL{+boRR>U2y-8QG7E{$* zY?Wa;=_)n6tJaX7R>OOG4ec86x>-YeR!wNwHLUB@1mHsU>eYm{UjyBsCUnCZ z=tVW5kJj-zR;TNr&chf1h&s_F>r9=h8x5vz0IqJd`8v@S>PAO5TE zP4~1q-_z?%*Qg6!v(EIadeDGgN?oTO0LWTxKgKk*odQm;-BMqdBHqb8C zpu3>Kbnyn>B^vO)4Zce?h$h`YdQ5|8u?@P%HHZ%1zpCUL+`2$ zxu-Ssp59QpM#Jcu4W(x_gr?n4yG}!BLDt&y8bZf!Xx*S8^umVLiyFcJX<}Wp3A$L5 z?SdxP#hU^knnIUs27qcBO}dHon5NNUn{1D38XdkVw1uY86PrO>Y8nH%X?K;T57&d+ zJ+0~YbhtL$Xa-%g>GZ5-(6pOw*J%bV7xGrG8Fc)n*A1FMFKl|fs2L0Z-~kC3KmoqX z0kSOsvMWMXDgm-D16YRv+ExM5(E#7l0j$G-fE*R?Sb*=@0BbuitqZV@2gJ4y^9Mle zhJb5FKdRfEuXORg+C>Ih7a!RElcNB5N;-&cF|K9` z!0amnt8WZ!cOUO0&Q(f}Rc127;5%zz(o192b?tbsDn2kO8c zXaj!$*I&ak0o?loZvbrt|7I2j=Yasu0dY9LBjDVRg!4WM&iNQP&tu^nkAw3&9?tCq zIIk1ooKAxCIR%m9Dk3K}L{967j2eiXGZDF9A#%w_$r3RnPsWfU6+_BQj83pII>p843?HMjLX6IfF}f(l=&}-%6KYIO zX)!sY$KFHfQOqu5aWo0yXc~{BC=o|< zWE?F}akRw7nIsoy(tMmjg*cNF<4i${GbJ^yB(=Db*5e9l#Fd;GR|-~KDYBXJ2 zA9v6o?&QL_Q;6bD2}__UkU%qd0?iT$G*2ebB9%bPY=TK~2`0lQn5>Xs@?wH1N(rW{ zCX|$xP%?T#$r=eIZzhzYl~BrV!by1vC*voaY>;sBVZtd!38xH_SQ<}aD3Qc+WD+Y- zNvy;r*)*SIQ6b6Z#3Wmgl59y!s%br`qDE59nMt)^CDoFbbkly)MT4Z93zKdkO1dSG z!ZLUY%MvLpPo}UUmBPwgip}sTHY=pqyqIE(Qi?5WDK(>~)U1(G^JYpdS}C>crQD34 zaJl=ez^24sm0$degRq%xq)XSl48;qqdJD@qxztY@^Wk@HtVa6*)8Lv#Bc#cHz0)^rw0p)Wd$`>S*FBzzwGf}-@p?WDm{alFpg$VUaL>AAJ zS-ePP@v@NR^J11SN?E>aWc9q6)r(eEF9%saA7=exl=aJGjwnz$q9o>of|L_VX3i*B zIinQjf!ln=^OfrR62v1AoYIBpJ0RFN!8 zMX_uZ&2m%>%m1eSXoP^8BcbLfs5u&u5eDjvg*xM)&UnN|1gI?$YDyg$uJ2l!zQ#Om(bEY{7xez)Qp($l2XD;%Lz2CzVZuvA2`_^t3Nt znoLt^F-@mo`Or5Wep|_KX*12Iv5b(0woHSJln&Fd#Z7BzGGnCmjG0#8_Y^T>r}2yf zkKHtp@zQ3-hu4F&kqOhV>~xr6GA#UVqQO0%;W8rJ+tByj%}ALL9{KQ_NSHA)X2ye| z1CIk3qQB_xXaqo=;ZR=$)E5bLML}KBP)`ih6AN|3K^^f>KLXSb)LRVdEg{3a3WCCZ z4@qbU6W3wfK$N(NIEaNfaT`IQ-cYDFCgveb!bcRSHwEg=iA9K$Kx43`$LJV{v2h$~ zi-@T|*IJBoe7bOPbD(oAz7#G)}K8=_bhZ;** zF)wbzvYZ%z8ewo{NQu25s-fh!`IuV>-089}{B+v~3WxVqxsxydMqg1A~z8J`}tU4gVhu!oqvH zaIeDq+OYj~5fRZ43GrYm8=ln>1D?|mA2DHQApyJs-#9!DVEFU$0W1ZBApuLlVMxIe zNqCNfr7^Hn0hYK76Bqbb)gLGS=kWVq`wyRdyYsKKZ;0pq%R3K7U)`Gi+86X+`!jKf zeEr#9{o_CR%ed%O5QM`1bqve(JvW z?(C2Fzw>{)@BGTc-+1zWP4&0`qxb*H<3G@pw;mb4^62+?<;^eus>*@tUw>%*UGt6n zJ?DY^U;h5<8^4=+{onp{?=|-Vq! zL%1^e|M;ENYghmFuU`EZg+IL_{f{rM{N3OGy~|ryA6)*;fABk({=2_%{nGkh`Yk&C zOEjIhsQx(o{>iu6H~!1fSHJefpNU_8_9vhGg%^#Ff8+UMq44atpZ@X(x8Lu+_eZ?@ z&Tl-?-~KC)mA8K7k@BX>{q=|D8_t8@e?9g3-fItD{fqa1ll|Gft$QEb{hN1wc6)UD zmu|T?*KbO%{4R6A{N)>ec>Vr$>)PtIU%mRLS6*ECy~__S|IVfBmwt<;=|8(bkUzUP zhTBuP{rhnH@8R|@;dU7N*B3n8{+-yry7=wbpI-d)*uT8kiT{g>x8ncb#jnPr3p@VL zFaBBlPcAkRe|+&q;{Uz)ONoDW@n0qWpNl_C{L_m;@((XwP5$iSmy`eG;y07QMUec1 zi%#nIFYcuN;l)MDzxdBn|KQ>urT({zM*8nxFzNsG;=Amd*p7>i+%zcLT{v84Z-kDw!D(qRgypviIKGIiGWmJ+hOC zG=!*(6qQnuBv~ay%BV;gDJ%8AuJ7;vxF6^7xChQTpU?HaUeDL-b=+;uCuFwf60Tb_ ziSt`iiT16D#M;(aLY#?AI50&K*-W8C3sWHRo5_a|VRk31nVpCDMYT}y_>|fhmEAQhmI7nXEml`&uq-lo{1P{p23)7Jg;N? zc%H^w;<*>o%~KV#fwv?^iuYWM6K`@%4lg;Tg*PbX7q4545TA971)o7o5}$fZ1D{;X z6rWhk?!A05dVASpqW99pRP9}f9@#q+&AM+iT4i5fwEw>6(USM*PQ+i1c4M$xAG)uZF~%SPAl7ml9Xzbl$cfGJv2U_B~KU^c2u z;8WB)fxajP!PY2w!Fy5eg5^>9f(2181k<9H1xZmN2mGQe4>&|69Wah+IG`T&^?*#& zP9ec4Z6VI62qF5Ya-pTj0iiFETZ9K96@=R(J%k%0&kNs(Y!fbsToO)+6c&k!G#BxT zOc1e&yepy`IVo~9l2cSH@}%hQ$Pm%3k=I05BKkz9A~uN)L`aLhh;S0S7m+1)J>rSj zxrjNj_=vp+Lm~_hI!BNX8b{nbs1`ANP$Gi)5MPASA?66LLu=s|4o!u>I5ZHxbm)1w zkocW&Gx00oapIZbb>igkF>#-8_QTfUYKOJM{SV897atY~e|4BWeC_bxFfoalFe{0{ zutbTru)7j>!X_myhwYF|4^x+n4hxX<2)iU{7S<`L9`;A_aG03Xo-iw^En$gLi=p*W zpF$_3IzzWhH-@T7Uk~+@&JHb-CWm%Ndxfq@n}-U^sE3-#h=<0?>~tqVCXTO86Nn;fzr8yd3jh(n0M5xtP;BXS`XNBBeD9bpRDEcZKDTJBS@ zy z#eqMMCI;?P3J5%L%CP}k zj(G>j9y1AWIHnYkc1$3k;TTiE#IXhcZ7M_l$|_I&Jya_Eb5%0^n^hwGXH@L{xm7j& zHB`m@{Z%>q3sl$qo~w@e&8xQi@v2q(X{(+03sEEaT~c%L>rm76`>iJB$A6sLPyhH| z--zQAzE_XG^nHE2+IQu6p0A*KjIW`(lW&x|wr{EWVc%|b4&OEP6(1puQ6FQC7N2O1 z8$Q=HGJJY8LVeaWtbK$|sQMV45cG*Y!RS+Z;)i$li9YYu6Aj*iCyTrdPtv?2Pr7+u zJ*ns2c~a7Q=_H3Yzvi-+p5};GsOA%|OPZx#?V8D6KQ;Zlc(qP@X=%xM1!(Q|D$rW@ zY|;AU`CY5klUuvOQ%yU~(@Q(RGe_IRvq@Xt^RxDDPd1%(4@I4i9!@$f9;rHI9(Qz7 zJVtbUJ?M3fJS23bJuG!OJ*c|N?l*LY-1~H!+}CtV+y(V$?)rKz?xA{G?!|hd?rnNZ z?z4K|-MCM6yQ!V3b@Mot>bRM?Gw!Q z*jJjZ*maw|v-@p!*KUt_uAQ2Bke#c!kzI=UVY}Pr%yw_gr)^ivU)b_ll-g=o#M-)B zINGLJsMyw6@Yue!SUIz5@$L+t<()GcmRV=qE&b1=S)MvmZ7F)@jV1k=Wy^6J9;;>> zHLD^U7po|nBr6M>Dl1u=ZmVrJi&o#QcUrewD_LK+wzsCiU-s~KO7L%XT7S1*gsIW1gz1}d$%jb{go)IF$>cY1fhncI zv|fg(ZHDRn08{+ORSG7WQC|_J+XALM6sA1~roI-YzZ*`$cehzM5p8fXis6KW!b#DG z6Cr?>)6b1R(cPjI@|JqzHZ2f&Hff|JjyvZGL!{!sdyF4P*qHNa%z$Y^6}xP8qPJZosx` zfvq(P+iS&V4K`UfY_w9?Y*Db`3}Mp=s^`JhtA_3O61Lz3Y{S34`mh=Kk4wRp)P-&7 z0$Y;=+w(kZ(Q4SH?XXqHV7spQ6~LzThmETNo0nVF9=316oZP?gPOboRT&3$SqA)W-}|$OqJj2C8%c)af>;R4b^}FsRl- z&;f-lpkjQWX0o7ax}a|MpmL$0cB!CxC7^zHK?OTN4L^Y@{tn(O#{??L4{9j~s;LL+ z=>RGk3Tm1Rs#*-{S_dlI25LJDsyi1l3JP2UN*oJ{YzE3KEMpET?FDL02G!06^}Y@& z-Uw>m399}H)O|5D5tQBv6kkm0FsQ#eP=FcGfCo@PG|)jhP{L)Pg*!kEZ9or$KoK)Q z6Mw_jfGl1CVH5*t_ycjM0eP?=_5lhZ1C3+?m0STjxdW8)9B5?#sAUT1Wi8wbNJa^W zhWU^L(2W{Ujxo@VGf+p(^KfR0`OB@F;AO#wBnL|g-c3IUQj2}H#y zdKBnN7bwdHXv+(zD+=f<1t_clXzT`1StHO{J5bsH(ApQEwx!5&Ah-x1Ic*@iokB7| zcj`cS#z1=xKz)8desJrHBhn}&~gw^Ga2YP87TT3&~yn;_st0Msr4^nMg5{shpx0Z_dq(7iKIzAw;zI8Z+o z=syKqKrXm}VsHgz;0|iQCEN$M&;qWZ6Wl{TxQLJ7CZ@nuEP%UMBZY(0I0=q}gNqZ~ z2Oqc)A#fuS;7a7dov4CK(FV6-1g^yr+=~Oa7!PnW0pMyPz}*nwauUJqq=W0p1NTz| zE~pgTP!+hMI&eq#!6iKbxAX#BQx~|WesEDE;HJjGRZWAtngf@$1a51cJOa+E5*%10 zI5917WSnd~;Li4gOA`jSCJwGm2HcwhxHuJXa~k04bimyifXg!hw`U2i&lcRD6SzQk zaDzVJ3Io9%hJs6s0=Gy8*BA@#F%ev3D!9o^aFw~>F7v@O*j?kHNh@1sB^2ZuSMZ+758HufgT^fZOc@*V_;7cMx3gdvL=e z;EF$jJ01ge1b!%SX45t{>h1>wo`LmnP<@aX;f zk0|;3m+*s!^51oW@$Vnv-TE3)y1q&Tudfhl>&pb|`Vukx=QnZV&o3hU&mwX1&jPXI z&ph#IZI-yT_MM1Xn;~@9riqWF%TI~LrN_k6rH4f3QX^rvR8JgQswGx`-y&Z8 zt|ZR=E+d?OUnQh|mk|GcT_iexOXCXZ9grE4+|zl)q(*LwV*?2FK7^43o69KyaG`>FGEn~ zVV>rN37+}=#J4#fqH&IkNSxb7n9Xe^1R%qjpIs+Eo?RlJot-0}nVlw!&5o0oe~gfy z|L7;@{^%k*{dhr^`tgMP@B4jn=l42t;rA-C*Y{Gg!uKLF{r5cb+nIFo)tN+c;0!@l zorxf`&IFK$zj=@=zd4X2zgd#Cz8R6ZzG;&urd7#x)AD5Mv;^63T8PXy%}1V@;v_$q zVkRd~Z6aGvt&xPL7D&IoPLW!^ek5go?I$^Y?IcNjZ6W>ra-Y=srG`}arHthDr5G}| zToS{V6jJ|ZDyj5yI4StEFG>BgGl~7PCF$d&0qOSS2@+}YDCyLs1ZmIY0n+ruZc^g} z8!2gmj$|>h8Y46@8?!h*5%X+(FeZEab&TWq(-_I|dolmUs$#mvN@9w~&c*nSCC4a_ zkz<&~f?|d~xy4j`vW|)PWDukMNj--9lU&T_k76L__z|iFgg?c zbaXU2YqT%garAk#T^}w*7k|i(_WKYYee6R-G|LCC=;0CD=&BK;=$H}p zXuT2H=shFC(bL1bqVEqgMW+m}M_CQeMu`r8iduQ!7uEj0HR{6qdr=POjN_5U{ul|XO!h2eU!-HQsnZ$m&g|b1CjXy z?U9}Xjgg82HzFAa3L*#Jr9|F%7Zn-x&MQ*)olWGPce;_^`j19F=ogDj>)#!DrhjXs zc>hYo`rE09*KY?Rir>D7@PB(RLiO$Sh;47rMSOY_A5rrrB!c$FIl|w}tKLz7zJn>vGtmuJo|XuIMnwE{`yo zF0-)BUFu=|uMdZnz1|ZR`Fcy3-s{Csp4Xp3e{^<+Hg`6LW_Ml>b?(d#J<>@IW$5$@ z9eiaTTKP&nl=MnG)bQ1=Q2tkRp+7t3LRve9L(X?V0?<(xqTEp&!rGA>^6_P8NbO69 zkocE+Ar>#?LPTHkhx}=03VGfBJNR<@r{LiBj$qC9yTLo#OM<_>NDY4UA~ZPjg?+H| z3*BJ37qY>OFZhDrw`~c&)wU2sZ5s|UZEFn@Zo3_{`usvr=W|+6$#b8e;OAyRn$J~( zc0Csf`rgVO)ZDrnnA18Q=+^ow@Mvp&AWLg;;K!E4z&kAgfr%}afi^A20}r=|1#WEF z9@zhEHK5|zcmU~HM}YCOx&Xmvg#pV?V*_42^$sX`Y7!9gR4G9FsXzeFQ>K8qCky^9 zPlo*SpFH*Vc~ar8_9WAv<4J`7RI|N*Q?sUjR zdBEr+`QV2){ewR5;rk8VHTR3W6YtZ!ZST8z%iP!VX1p)yJ=)0OUEjFumD)Js<=FVd zOTMwxi={EyYrMhFtFhswP_X>Ww_g>!m%2dQK1X`ek?V z`XP6^`X=|`J0I7LZn8U_zd7$1aI?oz z_hz-D;LS|O^(ueIcU1$1UU8`msRI551c2(VQ_*t3k&{^r>P*$nsK&=#V zI8#aIAXhnIzpe7A{kI#J?OSh9>`QLg*+<<_wl}-6$6oTrirv;5@9ZWk?%Fk1O0m{=&AYywvtWd8}NT9sA8wInO&Yc5u5 z*VL?dukl!|UR}0)clC|sovYQBSyv$exaw|s>Z*pN=v6*ThO4U<6Ib3^JiSt5ap_8$ z1?h^rh0PTW3xz9u7F<_W%oi`eG4H*6+r0X6ih25FS971sYUa9^_n3=b{%yu^x!Y{A zq|&UVB*E-TiGvxXM9Iv)gwsr=WX_bQDeNU)31woPTwl} zWt?8rW$af}ZfsCQH9lNqW6WA4Yy9IPi}CA=pN(!`d~B3)G2h7lVxW=HMO`DwivmXM z7uO8u3*Q*_7Tz?hD~vbHEwnQXEtEGjD`Yd2EBtD}UD#}}Qjl*jR1j$Jpg_mqVgbJa zxnM=#zMw~6t)N1Ge*sm0bAgrqL-ok{`g#uef_fVHYq~=DeY#unZ|HtIPt|>W-cq;vyo7Gf zd3xQj^CLP|=kMq!pHJ1+`t+t(WHlv~Hc#(#k%^s}+9kr>4!hc1_iDmox>=g=%g&r>8lS%dgp; zyL7TXxASB{?$wjz+{ly8xrQgTa|KU|=dPaEp4)w5DW~+ra8C4zCpktZuIC7yNX=Q( z2+ZlxFweQJp_~(~!JlKS!H^@QF_XQf-kaU6-jH3YUYs4J9+z#X?v*X5Zj`-pTrT_d zah~j}$2Vq29G}Y4Ki-wafBbINZ?%hA9cr;zm()D7Lez}1wAJLZ;Dcsa^Qv@N&sAqK z3sn0u{Z;R0YN%e$qq6A*M|snIkJ6{B9i2V9`tb-!?tc;@j zS$aj|vx5psXR8zh&k_o(XHP3EryWojOIwnEmG)BpZd#H2<+K3#)HFx{(m3TE(!R>+ zrrno2l6F>ZZ<@W_)--9kU#XkrMpNG%d6`;qq&_wJNJ*-}k<`?EN5WGVWSvr5Wc5?e z%POXN$_l0`$!<$!kzGp}mHCoVBh!}>EAuGDOy)+4uuNXciZm^yL)tH;NZLBZPg*NQ zOpyY$|a2`T23da32)M5)PSE2-XOF{ww%es~#1s;p#6%LM#kdnUi7_PhiT+NwCi*!cM6^HQr0DYmPSLvw zlOm-FcSZ6N5=0Ub%tgWyghkvEmW0g{+JviIxmEz?E z#p4+S_r|{yV2>{o*c2Zo@GDMJ;7c5rz+l|u{#SAJ`ya){?XQkA-G4PsaDQIhPyVF1 zXZ+D|+5CQSPW+B>Qv9ZI8~C;2y7wK8yR=U{&VL_&oXS3qIQZCC+{oUw*s8s=vC(_S zV)gd+$L`+yGIomZQEUTWZEO9Gf&gn^O?rA=RIw5cMt8(?&q}F z-4AKTyK8Cixmnumt|Ho_T{*O~yOL=(y9k=tt}xolP9Iv^PA6L4PAi)0PD7f^PEFdz zoyxQxZW-DoZZVo4_dc33H#d!mo0T@iMMo>=TBn9{EmBW%eWP-4jZw!qhp082Jye3T zovP3Igv!I&K%M5OrZ#evQxiE#sAe4bR6&kR>cWmB>XRK*YQ~O8s_l*->cJge)Ya|I z)EC=rsCnB>sjl1gsWRI&sT;PdQoGm{sKxA3R3COR>QQz9>K1lhYX3Ga>a}g#sKMJ9 zsmHf%qCx^d8DaZPsbrg@M6yj&wAdynoNON`6Rd-jTGl=ag|(An!1{v1!}^pm&C*0^ zV7W(0V5y~;vfQNXXDO%5F<+%TVlJknF<+oqGv`u7m@_E9nNle&ObL{1CK|O*ne>Oqm&>O$GD)q&E*XiF(#w4!)3no$%OPgCd_4JdE6=uxh0 z(V_%wIYCj`a-6~pzcM+sdow9c`8|C{ZR?34-%#`F! zOce7?TPcE@7%2-Iw@{ilGEmNLq^H8u!+*LVIw6Q9u6BeP!7Xm?Y|9_ z_W%B)oQH=iJfz|AA3R?F`;Srx56^!aDDv>2gGcY*jg%62`2F2PQU1G`!uXet@@}1; zQo7DS30~hqQCnxEu&!^V4F6%G-1q~34B;PE%E>=$lpTNADWBGMP;RYpP-51&D7tGq zDLdD8Qzln=D0QoR6zb|eis7mNg?IG;WqL)J(y$^%Nmvo5n65}r_OD1&W|xmpnwAwP zsmn?ft7R36@bYoW;?fDq(iqUQckpgR3f zrAqzKr2hM^Pwo6}N-g|uL-qRZOjY>qMWz29M14CGNxeElr3TI z%5UY=$ZyqDt#1ufu5VAM6VvU~y6GM&b$WiZ6Y>YN5>-Gn{wo+o_k?@xHp|2ZM8|98TfeuhNxe(uEew<3wJ z-zp>)ztu_fe`}qn`qn#f+uP{GPjAu^Yu*$k(%#%oGi4m5?^m_(rnN5q~@N6q^zEoNlrZ@NwPh& zNpw9Mll!|llFPbDeGJ~^{1KiRRXGFhhUQS#=l-sJw* zlgVYTmy;u3GpFdi-kZYnS|;U3r&daHr*%qpr(cS5CoSbjXI=_J=Z%!XSC3LEU-hMs zUVTY1e6^Os|7u(6&kn)V)(*wg^BwxBo*ho9${pdUtR1PTA77TF*1oJyjeq$v)#Bx7 zs_4sKsejtHroC?8n|8VVNLp~aZklGhL)y;v&@@N@(jL9IoR<0GZkqFpS7~xD#?lyH zET_G1V?BGTP4FzWP3f#@oAFuUHutlu&&g*ypXZ(}d0u%o`1zBwn$HK$?s`6Z_IoRR zdUGppdQPisx?8JW`q5UWbe7i0^p7o>>33Sn(-T`Br`xpjryp+lk-o8oKBNB`Z$`zl zBN?P;`WeR0Tr&ipkusK_p38Xk^kzoM)7FfTrz08KPk&|bJY~(Cdm@zC@mwI@lL98WH1PBq`pY-;Yy%xa#=bZe%|I@-*a#nvpJHU8KrtKqR{R@&p(EXT(e zvyMEzo3-_ESJvpGsjRw38?%!h@nqXRlFOEUWR%VD$SZreDK5LFsW>~KsUh2@sW)4) zX(pSli6Lj`A%D*8hsrte56yF|9|q<~JWS1@dw4x(=)sem>IcI)@eh`AY#waSm3$zc zOaDMSclf?@Zq0piZsPrdT-*Egxia^=a~bc?COIal8(a4xk`^_*j)%{lqT@N+DU z+2_U^Zk=mvczG_f;qy7ShD~|O4SVx;G$`dw-LuGRz88|0cP}%~_ukDsjeG5RyYGF@ zo4>p1eB0f9=Zo(upAWrjb^g@du=4_UbIz~USD){xe|^5Z{@Zz?eoMZ2y->b*y+%G= zy+i)+9ddr%os0RYcN+7Z?!3!ayz?uc{mzaHQ+1LTn(GWM~MJL96q?b{cR-+p~@ z_w64Sf8Js(dUfk?QRyv%BI1@`k>#!QBB@)qikNP_E}FPGThw%ut@!*+iQ<5pM#Z`} z1BwN2W)-hj)fT_2>MgFR`dOS>#c|2C>c}P4D)URbs=_b*tjxdES=o50ta9iQwQ}v! znM$4#xk{CiZI$*V-)>M!T5nt_DY?;75_My;#OwycWyu?&m$%-~y*ydrbGf-9{c>SN z_2saN-pj@nijzFhR`SlOwo zO=bR9Apy7=Qg-L6QQ5nzhssv3ZYkrvHgR3;TJv@1YZtF4T#L9~an1Dlt80?i=dLkd z-%COz!(F`v zcQ+mGvLD=S1Gwvl;qJ2*{k-)9rr|YA#ci05444vsm=+_L8cCQQ_KSyLl1yNtqG7VG zz=XBKq|H~G!PLpY^l=w@z$9kCMBanR9Id$sQ%Z(uwTG!ygX!H5Q@pvL3nqH0whgAc z0;W6_rrj5&-TCO63+!+r6yanz!3jx)lTrsKX84W+oE{B0MM7|zw&W9VvdZCv z^}tD6tUDYk&qtOTceFP!d8 zd2VphGvUNH!pR?R$c8Nt4%@&6wt^~b2Lad;Th5I(&cN2_hV4-gTciNC2^qGEGi(=a z*fQd-i2*>5w>P5Y)?MXm&89(;8JR5}mTng*)v2kLDNDy{`;E(5B*7u20OB@&dr3>3fr zbuXy@BcOmvpn-g#f_R{VAfN<$poLRF4T?Yy!axxmKoc92>3}R`fiRqaG_rs=nt?oK zdvbw7Xh0(YKqYoSC#Qf?jsmTS0JU%fz0f7)0m-xi(Jc1$0NpeL<=h6^DFW(A1Nw;u z3i1XTvIZ*B0Xk9uN)iED;s$DBNIU}sl?EjB0Ep^a|8tlt z22^MXbf^QAs06eq4%E08=#d>La#Q?$Aj;|CFF==rK$)+AHXi|XRs(%r1q#gr8chN! zjRrdP14?xSS~Ue~)dG4w3KT02G|LZE%K>!D5N8Uc8xO==59Is#V?R*vOQ7LLK*hB{ z$Jc?93xJl>ftqPR&*4DP-ayk1K-H!|*E&GiDnQ%PK;6PX-#kF!>_Fr6u}MJYjX>zr z6Q64xl%E5%pA6Jb0R4x73-AFq-~_I~3fzGqxCBjb z3(DXcWWYU$fs5D&Zh{+J1uM7jx7;Fc7? zHA#Vc5(5_{0B(vGToo6%t8L)27{P6Aq6&cXG6M&e2u`dK9ND+I32Tk8YY z)(P(I1-Q7U;O3gZ)!hSkR|_uhCb+$FaD7+7{S|`?yZ~-67hGWmxWiO%i3#8qY2X@3 z;2tBvMTUZ#3;AYh@S^KZ{;$NaBPke(b&tGEGko^Yhq;+B+Z}x_qkAH~2_AMLO4*Vg`U-`Y^ zwb>dmHX*XHCuo&;CuFm6XUqx_;Bj{2mB3}9{_R6E$t8=)BuL5l8+b=s?kkQTZCW8G{j` z!f%{z*RLTW^%^IAdg1^PGpI#>3O}wC%b}GxDN)9dXZDmRwi#r&AqSsPNMPEsb@M}_toqoNhNcEW zYtVm7opU`=@ZXg!e}2^v7lhtyITvz^II2g_7&Cfbb>_dVO|Q=rOxN*9D>(7IU z1f9p)R*qg8aXVU^Db0mUTsmvdWIY~9bQNVWQ4B(fBUR6s{+0$19Sy&j-b{HD$2|vl9b9Oh>+p3o<<-&^z#XN~QWsoc2`d8A~^{w2pnWH3%uQGRrTR-W;pf5L7 z6n@J?{Sr6J;4{+0vTknK(EFrAj2m|@uUC_%++=oI1(%Vgn_YHVzbzt(aOds(Ballf z^laOyW}iY*Zdl$al1L$K-XylGzA%h5tz)xm>Y@+nOIq5l=P6F4pB+uR^j$4U3=Ffo zh(iXXJu3Tl+kMm^i3A$&o}nm`gi2_;53)*-SUT!DUyS0&rWqV z(yX-B9ueARlB9mbp1E5qF-M#$_5{E95%W7_Xix3y@fa@}6VI(D12Ji-$~>NzJ7Y{T zeR(E*pT;y~7V`)S-;1eB>*5jVtc*Dp_aE=PeMyXdxD;>fXl~4is}t`Bz2ull!yI0^ zQc{fFkrv*S>A)COu3x+l;kQj_3kUd&j#y)@^$r(+PqQk2NIpspUH>D|D$SyV3O znd}tbk2TSl=#^c2>mKmNcr@znHSu7Np@u~7?cG2Z^H{8EuVm74^q%42y#Z_AqR%F= z?8~(ojb?%WwO?_0Z}hodzkQiwt~c`rq~ib?S& zGi67Y)H(9+{TvrvFQ3g{eltA!;@zkG!cJb%hLS(|i#ORuw_X$2&zfx*y}ZM8e-w*) z^hZ+M{>f0;=#a5H`wcsUqHiCc-2aeeS9DS#r@*0OOwr4;Ck3uqtw$}Xgb4^Z&qfhR z*9C4_eTqta)h}@JSYOl@CI-P7me#0M4SB(99e1NF!`%h_!^)$$OV0}$u@*$hbhZg< z=cGnmnOzdJp(91vF^e2Xaq)|?7qC1qP;DPoB%5?VYuYGkyIRA6fo@sgRno_K;(Fv zys+P;7mL)#ND=Tzk+(qe^t)x)@%9qj? zUV4TybSz7sYBCFbHYOzVrRaEQ;ex4*kB@k0(ke~nqsXq%xYcTzlYN^*6BjeGm&d$FNNql)!_NZH1NZ1Vz*|-p_Z6Q+>C-J9i_IerH>luOB7 zefBX}>9Dd2j1U#N-4zKGLWGpLWyq6@jy|&Ql-5)qJcYe zdX!q3w+D9qU03=OvKpZ7D5m_pV=N%xzPYjpdq;rL)>!2OC+h-+jBYD8yB7v9roUJI z7ZDrK|AgV#c!YO=;*89(KzI1#K96KMf z;LjqxP30EzkiVyZvPyi;6aPa@9xD8d75+w3IVy3!nf{$kk5%fL!~HKNeN(C3Xz$;k z!>t-Cqv^kEgNEuM6LJ5BTYjq5jvW4(rwdfK+pqcM&$Oyq=#BZkjG0%B6>9h6-^8nS zVeYnHE}^YfRFUV$yAZ6FV@&e9Ykf(L`0DIu+4xe;%}>{FjRk&_U|iC#(31bSq!zcI z#D!DGc?#BjYr4XZvk#B^?*4P-I0ws1Ust}@$3?}feUs%@j+-jy`BF~^s^=e#@ja<+ zsJ<%f2fA7j$c=riS=v%CBiubX)ldv>!NOOQ-5XHZnTlAPT=f z(HV8(t}>%fj%w)%C)FR`YGqv~yrlZPjW(~I=-J-j-DEC!vT*#OH>KF%Wam|?ch38W zlint7-g7KhPev~2dS@KzJh?`Z@b*5vbn@5V9o{4teoY^rWv@rxdYUfn!(JjDp_*fy zPrU9}UDBK~F7-O2)~-n+C424W`Kfs=-`DHQ43C!MRb#J*wVGOuMMu1Hd;_$q6L)#J z^A>37I<9+4Jbk8>Cicnmv(0y{sPPuhglR7AU1{Z>Tm00teFW1yT|awjM^yQHo;S(S zRu?q!yios8`*o_ErxWvM?S13BJbzfQ=^PVV_mIn1&=Ga~=pobTs56!L%wzO-iVn5- zx`zzs9i89TlHq?pKcb^o=;P5OL9d%YHT3v=P(ruTLfWI4$5QtZFQ>g5SJ9o+bk$|AyJtp`~v#wKm&4DiNYW|^m18th_nVX9B zHnNJk%cVWnJ8^=^U7T@N@3Pl-H@_(EQ~Ri0Zi}O;r=BI&xZP9qIF&`tajQwpJeB4e z>Ne8eaO#1wg`4bupHA)HtmsxP#;D)=V7Hr|j+B0d^B>p0Hdgw5Ya^~LPE>uZxW}$} zwiWtJ>m{y!r+W1FyU|=VC06vaA3M8p)AJkHGoExE>DD&L&=7LX$Otev;K$%9s-ABk zl>F7D^y_1T{M>ezHQE;gBJ+le5IdXU$Cy-?eK~T5kF9)M#<$oR?ibc~@eGPLWSJCq zsqCsUOvqt%xwh|(VW#w~v%c$^q14kZ=gUR=jeOOsoiDWO80pq!I!jCi7`@^Mbhi6* z-e|?m*m>`!$3|}|q?~=%CyiW2*qznBF&kHHSa8aHC1YI2)$8PR+1faor`D;|lWNSo zBiqUBK)JE!YM_(fo7cwqy~a+{VZV%v3Z?u_4PG8Am!*!@JrM5{&Iv3}mb`hdHrAlY2HD4vMl*OpF3XP? zOwGZ}n^3mDc{AQDWNf#+CQGGRkKBsg4f}4hl$dvRz1M!3U8$?LYaHHfzIQms&XPgR zoc?#9-3>ukbK4C@b``QI=AwVa?TqAaoBPc$*>%UZuPYFVk4)suQ>n)+{BzS=5!CXMxtWi3DbnF@tv zOLwtx8&)$Ot2x1Dn|fz8D^vC&n|v1+tGwArn_7z`tER{1HtWh&R3d&2jI?-AcCzGr;zcn$Dc z;5ET(gVzYJ6<#yEc6bf(TH-auYm3(yuQgtCy!Lnx@Lu3O!Fz-E2=5i%GrV_r5Aj~& zJ;i&A_ZaUr-gCV7I0HBfI1@MB3U?LmEZkkV!*G}3PQ%@XI}Udp z?mXOmxC3z);!ecfh&vK@CGJezow!4Bm*P&v-HJOFcP;K*+`YJiaTnuG#@&oN8h17B zY~0eq;b-0b~MX z17rkb1!M+f2V@9j31kXn3uFvr4P*{v4`dKz5o8i%6J!)*6=W7<7i1V@8Dtt{8)O`0 z9b_J4A7mh8A!H(CBV;6GC1fUKCuAsODP$^SD`YHWEo3faFJv%eF=R4iGh{SmHDoqq zH)J?uIb=FyJ7hd$J!C#)KV(2;L1aQ?Lu5o`MPx=~M`TE3Nn}c7OJq!BO=M1FPh?PJ zQDjnNQ)EZDej_Z)9*}ab$92b7XX6b!2vAcVu{Ed1QKIdt`iMePn)QfAj$81<(_qH$abo zUI9G=dI$6n=q1ooptnGefnEbW2YL_mAm~NVlb|<2kAhwWJqvml^f2gU(9@u|L63u8 z2R#pZAM`-zh0qhBH$snuUI{%DdMETy=%vt8p|?VhglcG08kBVLuJu7-w^swk<(bJ;0MURVK7d|=%vw9qqjznjb0l)H+paM;ONEClcP6BkB(j)Jv(}L^zi8A(bJ>1M~{zQA3Z;M zf6M?d3&2bOvjNNqFe|{!0J8(k5HL%?OaZe6%os3hz{~-&2h1Qai@;0*vkA;7Fss1K z0<#OuFfhx&OarqG%s4RXz{~@)56nO?3&BhTvk}ZlFe|~#1hW&&P%uluOa-$Q%vdmM z!OR7-7tCNVi@{6=vl+~2Fss4L2D2N?a4^fkOb4?a%y=;C!ORDD#mpD8U(A3p3&u^SB zXUw26i^fbEvuVtzF{{SR8nbK6urbTVOdGRp%(yY@#>^YDZ_L0k3&%_xvvJJGF)PQ+ z9J6!G&@oHLOdYdz%-At&$IKnGcg)~1i^ohJvw6(uF{{VS9=>|Xz|H}?2kaoQi@;6-y9w+l zn4zn{&H}p&>@cv)z)l0Z4N>Sgu`1UH!OjG`6YNm1OTkVB zyA|wMuxr821-lpQV6cn9P6oRf>}as7!OjM|8|-kf%fU_uyB+L!uGV<(N>G$T?AWzq=Z@VwcJSE6V<(T@Ja+Wh)njLm-92{r*yUrV zkKI0Y{Mhwl=a1b#eg=T)Vdp>mXWodyfB4^3Wj+7l*GJ6B{lo9?uG;($f1aUd?_d1+ z>jz5y;`4nR^Zkp@zp+H=FTNg6TgJcm`uO&|TgTTcI(TgzUw`KLpmlsdXUx^s@%`m; zvaaL%J^uFnAAJ8_=PLf-_24oO|AW`ZfcxYhyk5HpxBtQGM=AWchSxLM?$#P!-(&k@ z*6?~?{j9Tw*Z*lH_Zr@hYk`xicz+BP>Q?c7b^N2O;{D@)VX%t#(;|y!74L7T&GZW1 z?>M1`6}p$_lUpW-=6VHF4 zu=-Ej2PuNve&T+J6!@@!`@&DKY6160pm5Xz?vs>5+6%Z}nq{~aaNqD8o0!M_Q>tA% zkNe2UoHCF5>5QAfJnpN42%dS|UxH_+=Ww5GxYjU-`%SSaVGj4*+X2%#+MH`F7lfz~(F zr%&~q-%zij_DxKqewnA&PNSYh{i95yzWoR`oJPHS@QrsG_3x|O%oOS&Y4ZLQ>Lb-X zc?$J%ZN_2>^>Z;)XbSZ-c;m0HsIQdlXJ1io_X}lzMg4Vba`=jRe8N)VE9&!`-|Jsc zuemS0`hxn+r3#iGrr-8E0)3+jD~7Q+|R|381;enuYPx_j+2^1-g);Lpel zEVAmKksnr;w|z#Qn0zuiiF`4TerpnWW5}K~iTv?X_S7Wuh#2dhN#v8nZ&MSpWYeeNOj55)a1gXkx6o9_*xzsP)* zIEa2D>Vw4~`VX7m!h`5X6gid$(4X)sycj^g!t9hkfc}Lo+hYLzjQ9(M0rWS1n;8et z?+j=TzC-^LoKf)({gBp&$ame&kYf(Z_(e0?BDhl{T^q> z$2aKz%A;!DpdXx)q`g6ZIQsqc8}y4=H3DzYKhno6_MxBD(r@iUe`$RnuMhpE=4SUk z^qgLuPz35*rK9BB2Kdabvsu%t3*azNT^t;8se)ORK z4c*b)gMQdgA*%=dai+`vW9crywJOuLk1JvqcDG|Ib^v?bwu0S?je&uUiqzh8NrMWa zV56d9Be2(vi3oOgx1%FEzK*E#UcWW#JC6ArhuF`v;=Zr*{QuW_JH09|e|G&YugcFC zzSiry?ch^h$foqn(<|Tc>t&eti zNq=y4=k;IGC;Ykbk1y&M+I*H@)Hm#P@8}ox4}bSK>qULU=wo+#Q9tpYU6+1QU(v9^ zy9@Le=d5_|0)0leC3`K{|O^ZKCyk2F88 zFPeGgsOPKxXsxrJ*C)O5=5EjHm-3`#p4T@W+2#GY`lliL-#=F$b@@N~%+*h=vhuNW z^;H)wzU5r~)$l+6^PE2Gn#EpxPQSIsic_A`cfGXf70>Cv_TT5g=k#H>p100(`mrCQ zIMkQz@LGOWe|Ev@W1rQh-F^DG&+6BHet55E^=<7}S@Bu@+l;F}c}5?1;MWg7qo4cF z>4Top*S-B|$7l3+-*nmG8GYU^i??`2zgOP;=F|GVQ3u@pwEl1Uzk5Ed58UE`BcIj} z{@-PrKdmp^ruh9S{o&lz7Cfa-d}HC{r}T>_zJJA2`o@kg9`uy{@zdwmdrBYq%Zoof zsh_<5gQuU=SHAJ<^-tdrr+&Js~ zX8rK2$EP>zi+3ysH0zJQe5qrzKKZk6TQ}>Mw_AD1W_|Pg;=S4W=V!V-Fk2tJQFH&< z`svS>?>Jjuz1lggXX~$LKHqY-KKsMn-#Y`^GE?7v*$X?*)W46vZ<(3;_fs`3g_y``20R^BMa8{SSL$1|D$H zn2|H^feD|TGXpPpwV~Y%{9xVNSDk?;bYJ7!$MJ>VN9V`!h8x$p?s5F#{Apbt$0Is- z*za+C;^tr0c^t1;b?Uz!!!KUwJohm?(8GAqg8y##Fn)C8o4-ATCq4SuOAp~oEpET_A-t*GO}!t&pDwud z_=oVQF%R$X5I!~Ym8BlStG@luM-Spxo3(!YK|JfSOGiG4Z@t~z`9Zwv;f-VddEI^Z z)FS)x)+b#Zq9f2;Ipgl_3S-(?S^^sJ^1Z0M|Zym&z-sO*n9BZ6SSc=j?YE;SY3UU~GVcj4XBHf_EO z|NipH8}7ox=Um+NE_{5yt&hA5FYo&Ews+y@C(K>?EL+@%kS(S>aCnzV*4^+=1sGH{+Q*@cnbwzU2oD_k!Cw0Q>EI_w5{j3tA1lodYoK z$4<9%09w7DZs!0@cys;RIRJ-$^q<=}0K5MCt=l*NN3Q$GZ5)89hmF3C1F+A?i*Mrq zZ2a*dw{ZXtY1sNU4#4wwFLfIS;Kt3rxRnDi@4hE*EfqP;Q%~8 zxnT+i;EF@npTYt7dg(=zIRM+d_U>d3z&`iRn9Kp#Y3%irIRO71a@AxG!1R&FP38c! zzkS!q9DrBmt~Qwi(Eg8wH*)}5Hux~?M zK9?MKBM0ET3wOVf1MuEeYu(5Jcz^Wo6FC5v&3<Am9w4#4T-SDnBCm_6&)8#n-e|NPbs9DuF%eBuTUz}_Qn zynzGI{?}eNZ~)q0aK;TBfc^fp?+qM)hJpXMfdkNXyJc?R0POqOch_?Oj+^@8^&Eii zy{BK#0eJN6vDb3|mOJ^X>p1|8XP$ID2Vkvk?XKqlynXXV*K+`#ezV2(9Dq;O|LQsp zz|LLgUB>|^-=B6J2Vn3qqpsrsjC=oz>o@>kUva{99DsrAx4n)7(Dls?uj2qbc5{pC zH~>d>`)WJ~;Gj+~jOPGMKIQ)L9Dq|gj~UMa=-2nE@f?7)?(aCB1F+$D#dr?Dq}?|g z&jA=WcIojPfaMqeVH^iw$;Ma4aR3Ib_~eF4!}9^f{L2jGhr zE*;AOcy_1b$8rG9ySwdJ4#2BBZ8DYv&~pA#V>tjzUirfq4#2yuUmL>#=)36gF&u!U z-nnTE2jIMC`;FlMOndtLF&u!mUprz92jGW=yN%%h{IuEnV>kd`oYP_q2jG<%-;Cw} zJhuMJqd5Q*M?X561JGx!NuxOc7v0}?GzZ|U0qDH)k)t^Pz24n@GzZ}BM>ZJE z0r+uB%h4QwBX9nG6bImqX|Ijq0Q6e$#3&BH;eSmT#Q``h-eSc8=sD(+Q5=Aee>;8@ z2cSonViX79=wJRZiUV-|uoXvf0G`?P-y=By=l=A;NDja;vz{5r0T_A1w2>Tu4F-)H z$pKh=P|uMZfW2=xdn5N(Q9Dr-b-8F&(aKpZ%MsNT&ZE?*A4!{ntpE-g9kRR5n6aa{$uxHt}lJd-r_j>dl990Jc18rQsZa9ozkWEeGJYc*_c>1**fYz&bxRwKO;^bYgwB$z@QE89l`+^ z`sejSH~=sIv;PndK*ygi8^QtDVd>L{Z~zW%edrJlz!T^1HG~6j^w4`V4!{pRdJN(KY;xTN zgE#;`J$2F`4#0^m+7IFYoObM4#43%t~H1Q&@gkUK^%bBkN<5T2VnK3 zz8c5@Xz~1;133VbCp|lm1Mp+NM+b5M7WTShAO~RD(D4H~02|*kU?2zJh!3tD$N^}# z$+-hL0N-~zejo?nl+OD z0XXH(76Ui{Z#?yDe-6O@3%}~m0eEoNcl&by)*Cv%KL=po!sh-QfQ1)L@6Q3~^yjVp zIRNk8G`>Fv;KZW`_vZk7x=xS&9Du8Ty{JD2VBOEo=+6Oo`LkpCa{$Kwc3^)Fz@;0s z>CXY^bi(%iIRIU5-?%>qU{uT1`*Q$Zxq9jT9Dp7E{-YlU;J)jB?8gB(Z2!;taR63r z`Bpy;z@Kl;>&F3Dskyly2cZ395BB2#On>T*ejI@PKbz2x1F-ZOBl>Xw7Io~~j{~sj zBUkm~0QB1U!hRfpm8YEEj|1?|&d2uS0DSPy!TmS@>y2sX#{szhw4M8L0FExU?8gB( ze5dvMaR7$zu}VJc;_ir`Mvs9Dr|{|J9cRu+J)A_2mG3dG-5!IRJ0|{7PRA z!0L_9_2mHEy3y>u9DqKrKiHQ8@bJXD`f>o;TzOMp4!~MxjqS?;IOOaheK`Q{bZhL( z0hlx8%Dx#J(JWWm+83mjke1=mC8>0KaU}t}h3m@vWWv zasV!yuytP!z=BIQ?#lrfb<$dWIRNGHEA{07oY;BEz8ruvhW*)x1Mv1!zx3e%lq-JU zhXb%?m(Tie06zWj-98+EP0o6?4+r3_MbG!)04zRrP9F}y9i3^-;-2jK4Kn)+}6+H87F9}d9bqc7{j0r)E3 zKF0xQc~7T49Du3EoZN>4@J6d+`)~jTe|l&i4#3=J59q@I7}Z?#;Q)N~{2qNc0Q0`y zu@48J&AQw4;Q+KbW3xUSfES)vzYhoChb`9Z!vUCb*UEi30N=D-whss3na^AF;Q;J5 z`Ol{6dDn}7YvKUBf8@WKH~_02^j#AN;IkvYXyO1Idhth19Dt)HzthA4SoryCO&oyM z?Otr+04z6kZW9Nf|CUcRaR6?bIlGAiaQvB%H*o+SSnr`G4#2(NPHW--w4Z-h69-_} zoLieX0GG|Xsfh!y=*t_LH~`zNIj)HV(4ynWCJsQ;gF~A*0C%oGu!#fE^~OF;9DpCT z@72TsSn-W+O&oxChj(q_033PprA-`wuI;)saRBz)>AWTmz?{9#ZsGuZf7}^O9DrvA zoYKSrICS2LO&oy!8z0xi0l0A3QB53xmdhR9!~r;LQimoEz`^?-)WiY!ZP9-5=Ngtd ze%{_q9Dob%X=vgA>@>Me69-`0U3)Zf06u(r*Cr0YQ@`xg!~r;UkJe2bfcr*l*TeyM zYZyKU%hl12AgZGEE$S(?%@a!~yuG-%?E+fY!s~t$X1B?0iqlCJw;Q?=8{9 z0k~+RC7L(@cV6A1i34!s=kb4}HXMM%&sw~R1JL~2Voe-??`~SGi39M)iHkLH0J?9v zSQ7`}<7F3X;sC_|Yx4j3cMgDG=K%Qq8~}fw1K{uD0Qmbk0Dc|^z|ZFZ_&gi{pN|9J z^Kt-uehz@|!vXO9H~_vc2f+8|05~2T0LO;|;COKW96t^~bv(lXaC|ucjyDIu@#g?I z9~=PZhXdezaR8h@4uJE?0dRgf0M0iD!1?C@xE?qFt`81?>xBd0`r!b$o;U!mFAjj~ zjRWBN;{doGIRLIt4uI>G1K|4Q0Jxqx0IqKifa{$D;QHqPxF0wG?hg)t`-KDG{^0<) zpEv;SFAjkFjRWBR;{doHIRNfY4uJcW1K|GU0Jxub3kSgc%>i(~a{%1`902P92f+Hk z0kB?h0IVMz0P6_{!1}@gu-k$XQ`osaSUU2}dUmO7I83(}n#sRS2aRA!I z`o{sV9&!Mzj~oE&B?rLz$pNsQasaHa902Pr2f+Hv0k9r(0Ibg(0P8ge!1~Pru%2@O ztnVBE>pcg+`p*HdA8-Kd4;%pd1qZ~9K5ZA94Wfj~oE|B?rL%$pNsRasceF9Dr)S4F|yf%K@+- za{%nm902<@2f+T#0kEHQ0POD^0Q)@$!2ZtxFb{A5%m*9*^8yFJ{J;S)PjCRt7aRcd z1_!|W!2vLjZ~)9F902nQ2f+No0Wi;S0L(WW0P_w9!2H7jFb{D6%tssm^AZQZ{KNq; zPjLXuR}Y5+VBX>Yn7=px<}nU{`HTZ#UgH3m-#7r~ISzpNjssxc;{cfdH~{8B4uJWP z17Kd{0GJ;+0Om;!fccUGVBX{am_IoH=1~rS`IG}-UgZFoUpWBgSq^~tmIGkky`J4k_UgrRq-#Gy0c@BX2 zo&#Xs=Kz@hZw&`P9^e4T2OI!-fde2vZ~){94uE{Y0gyL10P+V1Kpx=$$R`{Cd4&TY zziSXu7Y9Hd;{eEK z8~}NZ10cU~0OUCifPBXRkoPzM@*f949^?SXha3QTkpmz4uE{g0gyL20P-gX zKpy1)$fq0td6feozj6TNSq^}F%K?ygIRNr62S6U?0LaH20C|}MAU|^ef?@;e7Wp639__Z$Fup93KOa{%-K902_Q2S8uI0ni_C z0Q3nQ0Q~|7K;OUt&_8eh^bs5Y{R9U&;UvL2Q85{up1_waj!2!^JZ~*in902_Y z2S8uK0nndt0Q4yw0R0LFK;Oav(7$j1^f4R&{R{^{U&8^=-*5o*IUE4}4hKNr!vWC$ zZ~*i{902_g2S8uM0ni_D0Q5;c!U51PaRBs9902_j2S6Xi0nkrz0Q6NH0R0sQK%d0{ z&~I@7^j#bP{TBy7AI1UDk8uF>WgGzg83#b0#sSc;aRBsf902_r2S6Xk0npEJ0Q7Yn z0R0^YK%d6}(C={o^nDxv{T~NFAIJgF4{`wXg&Y9=AqPO8$N|tVasc#=902_z2S6Xm z0nkr!0Q8j{0R1HgK%dD0&~I`8^qm|4{U--NAIbsHk8%L?r5phLDF;BG$^p=?asc$L z902_*2S6Xo0npEK0Q9vS0R1foK%dJ2(C=~p^t~Ja{VxYVAIt&J4|4$Y#T)?rF$X}O z%mL6Za{%F70C*P%0RQ3u;9(p9e2fEtmvI2_GY$Zr#sR?BH~@GX2LONL0N`;P z0DO)EfY)&V@H-9wp2q>e_c#D}9|r*c;{f1+8~}Wf1ArHD0PsT&0G`MJz!y0Hcq0b@ zf8+q*ksJVgk^_KOascp44gj9X0l+so0C*<{0RQ9w;GrA^S;N2Vm{F?)ShjRe% zaSi}p&H=#BIRJP%2LNB^0O0K$0Q{W;fX8zH@OcgZUe5u*?>PW?J_i8b=K$dS902^k z`cM3K|C?X)d;DI1#-H_f_`Cd_{%$|R&+;?DqLSx>jAY zu3gu#YuPpJ+IEe*)?M?iefNNS!9C&LaF4iG+%xVS_mF$ZJ>}kVkGa>}bM8I&pnK6h z>E3jYx>wz^?p^n=d)Ynh-gb|>*WL5(eQSWVz?xufutr!btQpo0YlyYPnqqCS##n2t zIo2L)khRE~WNorWS*xsB)-G$9wal7kZL`K%>#TX!K5L-0(3)s%v_@Jht(n$NYpAu< znrdye##(Ewxz=85u(jBlY;CqiTdS?v)^2OKwcMI+ZMVi->#h0LetUquz@A`lut(S{ z>>2hBdx*Wno?>sY$5eYw>^b%xdyu`zo@8&bN7<|FS@te_n7z!NW^c2{+3W0i_C9-{ zz0jU$Z?s3+EA5%~PJ5`m)ShZ@wa40P?YZ_|d$7IOo@{TnN879I+4gRGxV_w-Zg028 z+w1N5_I@*fS-?zSHZUWY70e7~2Q!3O!c1YdFk_fC%p7J9Gl*HlOky@Mqwp2YEM^xo zj9JD^W41Bln03rNW*;+C{Z(oAW#G-H}I&75XW zGpJeAOlmeYqncICtY%j;tXbAfYqmAxnsv>*W?wU~S=dZ$HZ~)hmCej%XEU@}+DvV> zHe;K$&D>^hGq_pYOl~$eqnp*u>}Gc}yjk8%Z?-q%oAu57W`7w#7LW;K0~tY9kQrnL z8A6tjDP#*7L)MTvWDglc7LiG06B(uQl_RsrE;5WPBh$z>GLEbx^T<9jkSrt<$wo4g ztRyqZPBN4%B~!^(GM20*bID#Zm@Fof$!0Q|tR}O`ZZe!KC)3GxGM=m_^T~cPpe!g8 z%7!wctSB?ejxwYyDO1XpGN!C4bIP7Fs4Oaz%BC`^tSYn0t}?7FE7QuhGOnyE^UA(5 zuq-SS%f>RYtSmFj&N8$tEmOIt*Qg zPD8h$8x~DIxJn5PD{6?FjiOIy_yTPEWU|so4Rq8BtmpV*crcP70spHgj>O6IyI#6AxPE;!7)#_|@w>n&1u1;6CtK-%6>U?#- zI$&L}PFOdrBi0q`jCIF4WL>gOS+}fX)-~&#be~p>%4W}I&fXMPFy#xBiEJd%ys8FbX~emUAL}d*R|{1b?-WOUA#_SH?O1D)$8na z_d0xCzD{4aujAMC>-=^97yuT4319;l0akz+U3m5~|fH`0f7=-5$F$rt} zqrfUK3+w{Jz%nomYy;!KIxr9H0|UWAFcEA7Bf&~A6YK;-!BQ|4Yz1S%S}+&v1%tt2 zFd1wHqrqx08|((d!E!JiYzO1PdN3dC2Lr-_Fd=LRBf^R>BkTx6!jdp0Yzbq+nlLBq z34^LwR4^%Q3ZufRFe~f|!@{yKEo=+p!n!ao>5k><~s5F^A2D+j>y!@&@- zL`)G|#2B$g%n^IUAhAeH5}U**u}aJmyTmZDOiUBo#5l1|%oF>>K(SCv6dT1zu~N(w zJH=43R7@3H#aOXc%oTgZV6j+C7MsOrv0BU)yTx#^Tuc|+#dxt^%oqE`fU#gq7#qfj zv0}^^JI0W)WK0=b#+b2Y%o%&eps{F78k@$bJ+F>gW7ilqmW^p++ZZ?2jd^3=7&sP= ziDTm!IaZFDW9Jw;mX4`o>li!Mj=5v+7(5n_$z$^vJyws|WA_+7mXGOU`xrmgkNF4w zPx${2@yP!hE6;25VEl9L%I(`89{&tqpzSk%H>M#g&uhC{{4;!lwtM~6m`<9%X1l%q zY)mcw*}B~-iyG6YmD;y^@;{Afu^l_L>+pMHI^?Jx?WX#x?!8#nEu>i_lBEi#s+^;yN2%` zZA_yd*|%Zk2jlNsba2Cp(;CwQ`yA2m`JIhvrNPHFjJ~BY9s1JA4Qo$oOy{lMsiE6- zjj2<|^BNu;72j*h#SKplZA{;O*|p)`{*9^Ywmljy>fM;S%xG#@rdwlL?)`oZJuYiZ zxNMR6{M@;zOLcd1LOD2 zpU`k@YE1w6VN%2JJsQ)?D@|#*sdZzzcE{Tq25lL~|L8j#+HcgDW?pf3!xw8drftVh zYdCSG#?xL%}kAJT7eZyw^#s9wNj}52o5x?(*pBpaUws)Fy<*yB=ZPYt$H}3x$ zHeaoGy5gZf8lGCJcN+7`Uk!Wy(JLKr^{;fEE90eyR=Vcl0M zx_0fA9$%(a(Qt0BwBWi`ijPj{m0s9%+7k;~LamC*~(??gWUo7!c&$MUD4T~-x_e?!TZ&cj>a?f6g&O9 zN4jC}-HKyA?~#sNuzPXXt3A>WC+t~loO`4$pYK(?IITx|`Qo<4F%x^FHU4NYjdH z{HWr|LEY1kVMiA&uIQc?U*p(f{nNUq6K_7QXw|-Z8oA{O#fQ6ePq$A$vFN{H_jLVU z9gCLBc25^Pb#igqFW01X4>`3M{oyrf>g%T!H_g2!t#-;8MZX8HNvC{qX0hLm*Q9=3 z&MH3We@z)FNO7hjXk?Rjo7@q}yArY+Aa=Inh zDLO3bmhRo;;^M8(yQPPwUQ)DO&@GK?eOb}tk#6az$1X3%PU@DvY1g$F*uPuq`1F;< z(OtTwJKJAf{C-TgwBY4##no-QrTNEoFJ9fWTe|)I9!1OLx~1dK>{Yb-`RerPSG|k> zd;99N>F!O%m6jeqtXOa7tJ1~CUt4rv^Qtswt>MMPe_WaV zd}ny^+(%cYO(%{h9)9Y|wDZX$iyn7gnYLShRI&chD^sfvM-|s!bY=SRrqRVekGwLC zJ8ev{!LC=P-8LFqY`NBzDSte+SpJW$X{RaUig_P&O~cO^Uv$b{(`y@FSG;*k*R7Ew|~KUixH0@!|4a)4(Yci;MqxMcVR= z8;f^ex*|QW(WGLd=~twUKb};i(O0ByH{Vq3b@>%(#;G?KD;;x1`gr}xMY+or>Bsjc z7YD6=Mf!5$lw#Vim#3#rx~2I3jmy)ZwQnt2K6-iD|{;?kJ94?eeth$UBQ`7habBaoAnOr5(e~0b|GVi$=d~|Q7vA+? zamBwcNk5(SP|@+VOVWuOKU}Q$z$NL94<0UN47((~b;BdYj^|yHemM5gqTl|Pq_0{% zR!raclJxX~$BLPMUYz<5e!RH(or}{p`_Cv&edOZw(0^wXzmL2)Z8+?U9*cf-@Ygf>(pF~edwapVS}>Re)vV{`?t&D zmd+QYOUC44;XW6oHxHdtY_R@CX~U(TEH?iwtneqFES7$yOFFK{Q^m7)cS-y2_H=Pt zzbIHgN^e(E#D=DT-Er*wL@ICAAK>9zHqD^C38!nF09&lPQ-yfAedF}GMW z;lkAOpy!M6mtUB!UTj{m!XX!?W1g5-oVMA8snz8#6xS}gAl<*s{9^p;7o_bzpI`L2 z_kuL+#sx*Yeix({j(M?ox8nuryX9Xhj@~)``SeT0UCYM*-s9!s?N826Lw9+l_~P;N z(>C9~QY;v8e!Az@SBuf-oS&BM_*$`ZyYth*tGr&^zv}s^^YgD4OMiP_I=k_WqFp{O z?X&xv#i8TROMm_FX0g|W=cNg^y;Ur+&v|LJj&B!J*E}y>*y^2Pn;$x-+n#%;81!W4 z^hD2hizlz^obKECz2cnn(b{uC-$zwyiBqjN_|M|)>77#3Xa6i(_3f0d z8TVtc#W9`Ip$Gm{th;%qwCMkSD!%*m%rxNce-$@8duIBs7T>s3e>6d5!TO2m#)U;Ha#nPvzpPK$VYOxefclzS%#nNqmoRS_b7EiCvJtbW+ ze)06-xKq;lKP;Z+o_R`oaNibb#15yVohP(NyDmC8P5!Axnlbm}^!ouzq;N4Qn;JhjAss$>*>u*O zC!}S6T{dlT=?Uq+gO^Kl_c|dp+_YRec!?9z<3BH#?pknsTK~Z1)0g9qPZv&HKD9Xg z_;kmQ%csA$JU-3acZKxszm7|9U$;UU`^0hSmG4$a+x0yzJzT7qZtrkh>N94=v}o1i z(w<+fn09*q*!13BE2V>OJ2ss&e5KU(!ei6>pRANt-sRZTcGs2D(|;V3`VU$;9rx5R zX~ugir@2FpNpEi7Dy@CgG3kS*R;m5k$D|iuZ-k7OSN8cOIQCyk?cO_C-gh zbr!6Wp4;WgVUGGZIoU( z`QSA9q>a*+8yuYWnYvLr=c9wt{NFZ8{U;xk+8(fR8gRxzY3$gIQ|C<%O0RvoaoXmy z1Ji$6Z<1cR^}w`L?@iLNXC0Up&EF)=+U&se_BxxUCB8TyP3XL7+Wz(f(teL_n)W*T zfb@Ec&C(W|ACL|?aIC)ZKe$yo<~2L`@Az%g#S0r!p0aKF&;1Rl!}r^! z&KEYMCwAK|&DgRbt=zO-`r-3-sr?Jvr6s1cOXsh?efsm{cIlGSwomV_)h?Yhb^CO~ z>uuB43%5^gN48BLwcQ~-*`aOfHeiRe^-^uq|Gl(By7I|3>EyLrr`vnBNq3ytIz7He zoAmlUt<$uHd!?^_X`Ke#w^#b8-HvJB^Y%)!2JDzV-E^ov#6UW9ea;zLP$IdZyEFDwF)-iUh9dpOtIdCqV6X(V`a;}^+ z=gv8FE}c{7);V^ropa~jHQ-usO}I8(Bd!(KjBCd=R9#DPO}VyQW3DyVoNLcD=vs75 zx;9;-u2t8pYu7dGT6Rslwq4_{b=SOW-#y@7a8I~5+#~K4_l$eTJ>*_;Pr0|;W9~Kg zoO{nb=w5VBx;NdU?p61!d)GbeUUpBrx839Jb@#k`-x^>ouqId=tP$1=1Y%R7XTbr%X)@p0Ewc8qQEw`py+pY1|dTYM5-yUEu zuqW6X>=E_~dxpKk9%3)Cr`TKUG4>jJj=jeoWG}KO*_-T9_9}apy~`eEFSDoF+w5`n zI(weI&mL$mv?tmd?UD9Md#1h99%?VOr`lWXvG!VfuD#bDY%jJa+nept_G){!z1tpc zFSn=L+wJl8dV9XT-wa?DFcX*!%m`)$GlSW|3}KcqQGn3iL3}u!wQ<<&ISY|CVm)Xk< zW)?G(na#{-W;HXL+06`RmNV0t?aX*)Ju{!#&kSf5G!vQ)&4^}2Go#tj3~81$Q<^Q! zm}X5gr`gjCY8Ewqt*+0_hdmNnCwZOyo5T{ExQ*9>eHHWQnT&B$hDGqc&* z3~iP+Q=6^L*k)}rx7phaZWcF_o6XJWW_2@rHM_?QZfi*3fV%&kTqlu*+T}AMPw4$L`IQSWER;)hLL4t8req1k#%Gq*+&MF zg=8YxNJf&CWG2~3hLWXZD%ncLlC@+m*-HkK#bh$sOh%K{WH#ANhLh!FI@wOfll5di z*-r+P1!Y3nP)3v$Wk%UihLj~`O4(Azlr?2e*;59UMP*XiR7RCmWmef$hLvSyTG>{{ zm33ua*;fXZg{w>)*;q!Fm1SnxS%#LSWop@4#+J2ZZrNJ~m&Ijr*<41K)n#_sU51zC zWqR3O#+UVFe%W6KpbO9m=mvBIx&obn?m&m2OVBCk7IX}{2AzZMK?k9W&`IbfbQHP@ zorUf~hoQ^RY3Md|9J&sjhweiMq6^W9=tguTx)PmF9QJJh~p8kM2hYqzlps>4tPfx+0yC?nsBEOVTOnmUK+I zCY_V+Ne88i(n;y2bX2-3ot5rNho#HXY3a6fT)Hlum+ngkrVG=F>Be+qGomZgnd#1S zXu7nGqEpkY>DY8_Iyc>$4o(-Rlhe)V=yY{DJKdcQPnW0D)9vZ_bbUHM-JcFn7pN1| z4eAJWg*rpsp$<`(s8iG}>KJv6I!E234pJAXlhjS>D0P)OOWmaoQR5HHI#=DR4ptYdlhw`YXmzzZTivY=SC^~P z)$Qtdb-g-Y-LDQ<7pxQ34eN+?#X4i%u?|_6tW(x4>zH-TI%nOp4q6wjlh#e^sCCsk zYu&XDTbHfV)@|#!b=^8|-M0>07p@c6jqAvD)3VeI(OZ>4qg|p zlh@7b=ymlvd)>VbUze}b*X`^0b^SVj-9H9^1z-Z$07ifnU4W~hJj^Z8rTNLfpuUW*arrJgyhJ+_+G*cS$dg<)dY7)FMbowmpS z*x6>m(6F?Msr~VF#n`Ym%nf_P;IKGM4x7X1usX~RyTkCXJWLPU!}zei#$bNf9|nj8 zVuIKpMu-(+hS(v7h$Ui**doS=HDZp~BL;~@Vv^V-Mu}Ap3TBC2VwhMaripE0oLDF3 ziG5=Z-AQZZF*6=TI(F<0yrgT-PoS!@=g#cI0+v&C-Lp7cMK zi|Jy!7%$d~`C`8qFcypnW5XCRR=iFAA3Mg7vE&88l(A)u8EeLzv1be#i^im}X^a}H z#;mbx3>(YFw6SfB8|%irv2P3<3&+H{0y)UkDp9c#zjv3Cp}i{I>k6%@-cmEALGaRF@Nlz0}%f{)4#{B&+_Z>`)B$6@#kmx^YQo1^7jS% zpUnY?pEujji=RK+&yUYD+vkbTH{0in&pX@ajn6;Z=a26*+xLm@H{17%?>pP~jqg9( z_mAT-+wq9wGu!cr<2BpyisLui@r&cx?0ClUZFYR)csD!Var~Pd|2QAb&PSY|X6Gl) zSF`gK?7!Lhi}Ts+e8%~0c7Ef0H#^^P{+pfuxE`8a4{?1oyFP;bH@jZq`e}Ck#P!td zdW!3-+4U9ITeIseuD@p2UtEvPuE)4On_ZuAy*5|Z>&8QyUB7WXH@lvL{WrV5<9cs) zy~p+6?D~)Uq1pWq_eZn)Bkq@G_eX7_8{zs>I7;V0*2_jBCe&F=5G-<#dytJRk{$ASOW4|x$_p$$%_Wzg%O7lR>2c`KS z=7rL{5c5N6eu#OZG*85QQJODe-YCr*F@KcikC;bF^GM7mrTHZ0mD0Qt^Gj)diFu|p z&%}IFnr~v>Da|`E|CHvRn1@R9P|QcA`6%Y4(!3P&Q)zyRd8#x|#e7wouVUUR&08^l zmFBOQ$4c{9%x9(fEatV+ycY9YX?}}&t~AfZd{>(9V%{swdoll&=D(N+OY>mNho$*2 z=Ec&y81rLkevEmtG*8BSS(-0n-Ylzmvsd5J{2B9TX&#OFv^1Z_yjq%9V}32ouQAV- z=GmBUOY?2ayQO(I=HJr%8}o2!9*+6AG#|&jT$-0-elE?=F;AD~>6oue^L5PIrFlE% z@6!Ao^LS|50NKIc_Q*fDPKh1DCLdFAEo>ed8Cv_BA=A;N_i&o zO)1|*-YMms$Umk06M3kVhaw-9@=@faQeKMuRLW10r%HJ$@>MBcMcyjqt;k=c{1thu zl*b~UmGW8SwNhS-{8q|uk>^TzF7jO|-$mXl<-N#%rTiCpu#^WQAC~fAw?a1Gy{2h6`l*c2Vm-2b! z^-^As{9elMk>^W!KJtAj-$&jr<^9P2rTia#K&cOiexTG3L|;(q3!*l=_6| z7fSs?^bMuHA^L|>{}6pdsgH<$qSQ}BUs38SqQ5Bh7tv>w`ix-zW#s@o{Zgs#i2kG0 ze?%Wr>O-O*DfJ`Kmz4UF=ub-hN%SeDJ|+5tL(vzN`l9HMO8rsvNu@q1 z`lV986n#^vZ;Jk@)IUWZRqCUnpDOiJ(N~rFs_3su{Z;f?r9LbAtx~@geOIaPivFwA ze?=cw>cgTREA?a1mzDam=+8?1S@db8J}vsSQoj~`Td8l0{;kx%MITq{fkJ zmHN8q?@Ik$^m(N|FZ#VwzZZR9sqc&auhjoVA6V)GqaQ5wgV7h3`oicBOAbKviKRX< z`o;J^C{gu|rM@xx$5Q_oePpSRjDE7zPexx^>MNtaEcKVsXO{ZR=r>FKX7rtyM*P&idr& zm$QC3`sS=}j{Z68pQDe?`snDVvwk}I>a4Gh{yOWgqtDLz?C7_%emnZ^tnZHgJL|ur z56}AW=*P2uJo@siFOU8_>(8T4&-(P}*Ry^-`u41EkN!RD-=mMu`uOPQvwlAM`mC>y z{yyvPqtDO!{OI?yen0yDtnZKhKkNU42V^`T_&~-7f)`}GAoxMX4}vFTJR$f(#utJ& z_)zeoj28tz%J@<6q>Lv8U&{DW@TQD61%Jx;Q}C#a zM+KkC_*C$!j8_G}%J^0Atc+&`-^%z_@UDz^1^>$USMacmhXo(Y_*n3=jF$yJ%lKLF zw2Y?(U(5Jf@V1P%1%J!(V zU+}<;2L>O^_+aqDj28w!%=lsO#Ed5fU(EPo@WzZc27k=>WAMm~M+TqF_+;?Pj8_J~ z%=l&S%#3FS-^}=C@Xm~P2LH_XXYkOBhXx2X)QqPFU(NVx@YamC z27k@?Yw*~N#|EFx_-ydn%mD~~oAKM=xf#z5zMJvg;Jq2|4gQ<)-{8R+4-P(@@!{ab z87~fgoblt}$r(=$zMS#p;LRCt4*s0+=it#9j}AVa@#)~z8Ltk0o$>47*%{9czMb*y z;N2PT4*s3-@8IDX4-Y<`@$um087~ihp7HbG=^0NCzMk>*;O!Z25B{F<_u%mvj}Jbd z@%iBO8Ltn1pYi+P`5Dg-zMt{^;Qblz5B{Gy0P){52Oxeea{%J^W)497*~|fmzbkV9 z;_uEJfcRON0}wwua{%JAWDY=lw#)&D&zd;^@!2y6AihiH0K|989Dw+)nFA2tJ#zr! zSY!@B9GlDmh+~yG0CDUx2Oy4R<^aU8%^ZL@)|mqk$3Ala;#_17K%AS*0f=*zIRJ6) zG6x{eW#$0Hxy>AaIM7ma{%IA%N&5X_c8|{?#0Xjh?T7 zt;`&NSUWQZAlA~%0f@CVa{ywk%^ZMOdou?h*5b?oh_yL$0Aj7q9DrE6GY25n^2`B< zwLNnHVy({{fLQx82O#!>%mIkKA#(s?ugDyL*gG-@Aoh~X0f@aNa{ywm$sB;#dol+g z_M*%Ih`lLu0AjDo9DvxnG6x{`vdjU9y)AP9Vz0{_fY|#o2O##s%mIkKF>?T7ugn~P z*gG=^AokMC0f@ada{ywm&6RJr_A!|Q5PNav0L0#$IRLR&XAVH@-I)UrdwJ#n#NM7c z0I}C+4nXYvnFA2BK;{6%Y>+tsF)L&aK+F!A0}!)B<^aTOkvRY{Yh(^U%pREo5VJ_; z0K{yPIRG)MWDY>gE|~)mvrOgy#B7r}05R)i4nWL4nFA2BQ04%{Y?L_wF)L*bK+H~= z0}!)R<^aTOl`Frp`J~JNh}kQ10Ad!)9Dtb3G6x`LwafvC*)4MbVwTGsfSBzv2Ows> z%mIkmFLMB57R(%gm<=-rAZEqP0f^Z#a{ywN%p8E2Ei(roX3fk2h}ko90Ad!+9DtZj zGY24M)yx5i*)_)ui~VN~K+Lw80}!)r<^aU(n>he63ug{M%*L4m5VLaT0L1K^IRG(B zXAVHj)|mqkvv%eH#O$3p05OYa4nWN2nFA2BdafLRrOwP8fSBbo2Owtq%mIj5KXU+L z_Rk!E$O4%I5ZNGe03s`74nSmw%mIijkvRa7EiwlnvPR|rME1xWfXE`50}$CHa{wZ% zWDY=Nm&^f(ER#6^k!>;uAhJ&807Ul59Dv9|nFA2nD02WJD`gHqWT(slh%A*k0FkXS z2OzRm<^V+Y${c{mVwnRF*(`GaBCBN%KxDTZ84ml;9DvAnnFA16FLMAQ`(+M5WWme< zh-{cS0Ff0l2OzRz<^V*N%p8EomYD+(Su=A0B70^IKxEO(0f=mxIRKGWGY25DYvuq% zmdzZ1$hMgS5Lq{K03!Ql4nSn#%mIjOocZyQl`{t*vUBDDM3&ARfXLRF0}xp|a{wZH zXAVGQ@yr2;Y@Rs)k<~K?AhLVr07RD09DvC7nFA16KXU*g`)3Y7bOD(I5ZyrL07O@i zIRMceWDY=d37G>B-9qL7MAwix0MR{U4nTAfnFA2rMCJfQSCKgY(OqN?Ky(?I0}$Ot z<^V+3kvRa-ePj+mbRn4o5Zy@T07O@kIRMd}WDY=dDVYNh-Ad*FMAwoz0MWf<4nTA< znFA2rOw8>S`_CMJ=x#CxAiA8)0f=rVa{!|2$sB;_eliCjx}eMfh;Arz0HQ0(9DwMK zG6x{Kq|5<`ZYgsBqHD?=fasnw2Ozqr%mIjQDsup$tI8aJ=&mvcAiAu~0f=rZa{!|2 z${c{`zA^_Oy0FXvh;A%%0HQ0)(V1cYnFFxV^eZw4AiA~80f??Ga{!`y%N&5{;xY#y zy1C2&h^{Vk0HV9g9DwNZG6x{Kz03iKt}k-{qWjAnfan4<2Ozq^%mIk5FmnK+JIow_ z=n^vrAiBlO0f??Ka{!`y%+>Qpe_WY40MSim4nTC3nFA2rW##}xmzg;L(QRf9Ky;m% z0}$P3<^V(&nmGW`jb;u&bfuXC5Z!6!07RFXIRMeEW)47ft(gN5-D~CmL>HSm0MX56 z4nTCZnFA2rZRP+(mzy~N(d}jqKyHYo0MSin4nTC(nFA2rb>;v>mz_BP(QRiAKy=-i0}$PJ z<^V(&o;d)~jb{!(bmf@?5Z!s^07RFbIRMeEXAVGg?U@4*-FxN$L>Heq0MX574nTDE znFA2redYi}m!CNR(d}mrKy>|?0}$PR<^Ti>$Q*!R1DOL5tRQm$f*oWIK(K_&0SLB` zIRL>LG6x{oL*@Vki^v>+U=x`G5Ue6|0D@g)4nVMs%mE0tkvRatIx+_!*hl671PjR= zfM6q;0}!kva{z*!WDY>El*|DLwvssj!CEp0AlOUh00fK49DramIT#K0pE&@*ZZZcT zSWe~u1l!3RfM7kD0}$*da{z(`Wez~Fq09jYR+Kpa!HzNqAXrl700djg9Dra=nFA2) zDRTgVMP&{^u&K-e2v(Ij0Ku*@2OwBh<^TlS${c`TU6}(A>??Bsf`w%cK(Mh~Js-PA z@5})Rc9uOq8!Rnz0QT${|NP@?>_2k=g1u!9K(M&X0SGpiIRL@xG6x{oUFHA;%gY>q zV0)PZ&^WVq<^Tly%N&4UftdpkY%p^Gf)(aqh7G|EGY248V&(t@Tg)7QV2zmr5bQB? z0D?tk4nVNU%mEm*Wn<<51iQ=}fMA)K0}yO8a{z*MW)48G&&&Y`7MeK#!A7&^ql1-Z z4nVNe%mE0NnmGW$Rx<}6SZn401bfXKfMBti0}yOBa{z+XW)48G+spw7mYY4#9c(vq z09KsVm^lE!elrIkSa9Y51RKsAfMCU$0}$*udwx7va^?VhHoq}*0D?7V4nVNy%mD}% zojCx(rZWd1Sas$A1iQ{0fMD5~0}yOGa{z*MXAVHH@5})R7M?i(!NxNOAXs_k00cYF z9DrcynFG+__r}Zt2-coC0Kwif2OwB{t{i~B8nfr~gVkpaK(PDF0SK0#IRL@-GY248 zf93!L`_Bx3`rl{PzmEO;{j=&nkNx}mW(E8A_hbKl9`^6&WB)!6_V4py|2{AF@AG5- zz7O{A`(gjSFZS>IWB-l^_V4&$|Be^-@A%EGk0!NWB<+v_V4^)|IQco z@BCr^&L{To{9^ykH}>!RWB;xP?BDf){kvYUf7cK8?|Q=iU0>M0>ka#N{bB#EN9^DA ziT%4?v47Vu_V0Se{$1bLzv~_Qcl~4k?g#AO{ek_vUz+Rt2m5zFVgK$g?BD%{{k#9L zfA=Hy@BYO8-LK8{{fqs(pRs@UH}>y-$Nt^_*uV7v`?o$||JDoa-}-_5TTifm>kIa8 zy}|yiKiI$ZsJULBuz%|n_HX^d{;g-&zx56Kx87m@)<5jude~gAkJ!KU68pD)V*l1t z?BDu|{abIbf9r2qugBQG^%?uOUSt2(Z|vWCj{RHTv4875_HX?!>-_-xw?AP2_6zLa z{(=45Ps)0K!T#+x*uVV;`?nvJ_5OtY+pn;H`xo|aKg0g*Z`i;64*R$NVgL3+?BD)~ z{o60GfBPr)Z$HKU?XTFs{TBPT|6>34W9;AljQ!iMv48tF_HRGO{_XGBzx^KjxBp}R z<^k;Ae1QF%7qEZx1NLv8!2Zn_*uQxL`!|1J|K<_w-+Y4on^&-Z^9%NGp27ajH`u>< z2m3ewVE^VJ?B9HZ{hODtfAbUeZ=S;bGY6oax3GWn7xr%+!~V@@*uQxV`!~N~|K>UD z-+YJtoAo65huFV)5&JhkV*lnz?B9He{hK$jfAc5yZyv?|&8OJEc@_IN zzheL9S?u3@i~XB-v48V#S-#m}~oA0rI^FH=({>T310qkEs!2ab0>|cJs{^bemU%tTp|cJt{^c3$U%tWq|cJu{^cp`U%tZr|cJv{^dFBU%tcs|cJw{^d#RU%tft z1*}QS4tn#s1}0>|cJx{^eQhU%tiu<=wK*zu3P#T-Ny*`|bAi{p$~~ ze|-Y>uV29a^$pm+{sH^fM_~W@iL&l1uz&pp_OH*t{`DK!zrF+e*MDID`Vj12KZ5=1 zOR#_a3HGl~!T$9t*uTC7``5o<|N0p0Uq6HW>ua!o{SEf7&%yrnJJ`Rz2m9CmVE_6c z>|Z~G{p*XcfBg~muTR4M^-I{lz6tx+KVkp+DC}Q9h5hTRuz&p(_OH*v{`FgB-FIRC z`Y-HXABO$w$FP5W8TPL~!~XSY*uQ=a``5Q&|N1xVUmu74>*uh4eI53%zr+6ZdDy>x z5Bt~mVgLF+>|Y;<{p$y@e|;hLuRp~8^@-TOei8fEH)8+#N9DfX{F#s2lFW!ld*sOGWM@;#{Tus*uOp+ z``1rn|N3g|Uw@7L>$9Yc>|cM5{p-`QfBic4uW!fx z_3ydv``7Pd|N4IHU;mH&;{n(|K7jq>1=v4+fc@hM*gw92 z{o@VTKmL$w9)bPi6WBjqf&Jqb*gu|u{o@Ki-4=<3HFx9)$hlL)brFg#F`3 z*gu|x{o_m6Ki-7><4@Q>9)=js4@-*gu|){o~u% zf93$x{2Tkn!?AyS9Q()1v48v=`^VFbv=lzN_zC`w!Kza7=1HqB>TNS?y0$$I>ya{fg>XJLa{2QJo9tr1mqabLE`X{zi2! zozvRysLr)>Ui%-_wcwhl{gCQfan02J$p5aTxTb2qq`KBzbG3g`U5l>C+E1yjRo86o zuT+9Rcog;)LLpyt^KNMt+nRX{#CUW zTa#-)t6HnA*|on_t>xDA+V85?dTV~|e^q;dJ)!o)s=dOVVehbq)IM3Yx7cH9->lku z>_N4UR_#spsM=Sn_AYx^?Xy*Tn?0`f-KxFM9$5Qu)!t~2tbMs^@3e>3K3%o9+GA_q zuG)L;!L^T9?alV++SjZ0ZhLs`^HqDhJ-+t+s=eO~Q2T(@Y+y#HeZgvWFhkTnVKrNr zF>2qinmx=QwU1cMCT0|~ikYSM7pqyuOjG-f)vROYsr|=l7BUmneq=Q(nVD*TvYMsL zRJC7O&01!z+P|!3F*8~1XI8VCnXUFWt69!WSNomStY_w{{m*I^G!xc-Xf-RE8Eb#E znkCJYwO?Aznr6=0KgIs5nY8v(t69~|YIZfl);?=B+nRA}-?f^3&A_z}Tg}F19n?Sog@ zP)4kM@hUsYkhM=9v=C1wwDvQhHwVz*Qb(y{P_p2-~)7O4~mGx!*+W)V* z0G&Ynd_dI|=nQlRI)wUpf~s54G1Si+RNaFPqJAEs>Lzp)_45igPwQE=i|UKVMRHO**Ig`ID-P(n;0Nr&L{) z&Z>TXrRuVDTJ`fSRoA8S(tYW`>gQpqZcIm}E7O_P&(Bm{nog~LzNYHhbZ+(YH&qv> zldGT4sk%CyUH$w{)#d5*>gRi^u21JzKmSv8fjYtZ`Jk#R)EU;#4^>^FPO*NzsOlPZ zj`j0LRTrs~te;P+x=Nj8{rpnZW$H9_n>x<=d8exT)Pd?kb)xn2QB_x}Gp(PWs=8F2 zYW;jw)wSweb+0*vX;Zdu2yYt}i}&!1ucRVS^R)=}5bt5w~#4!eGyt?IUQ-1YNrRrjp}ub+pj zx^W$O{k&Y&o$Ju+=jp0$UB_NOZ&!8iI{5l|ysDem(bv!GRo%S~zkZ&t>h^W~_49sJ z_m2V8&jVI$03)cM7p&L;hEP9GSg{3+p?==5VhNoDj1}9! zIO^veEB1kb)Xzg!Yy=~zpO>uI35HTXPl^4P7)$-UWyM}F7%T>p>G8kkGb>hu+0@T( zRxAh8sh{t}{wwBFKmS>=AWW!!KD1&*m{I-wXvLB+rTY0&?7w18_4B6{i^8Pp=Tj?I zg;~|luU0Gz)2g3utymZ4RX_h)u`o=mem=HhWv2x*tDm2(SX#x@{`Y)s#o92p`uW?6 z#bI*w^SKqP!|dwkcPo~M>DABoR;;fvm|y+;Z^Z&J!TR~&iWOpp_4C6OOT-lG=Zh=W zh&k5JA6G0AldPXlu2>~zSwFvAu}n;}e!jV4otS6+{By-ZG12<@=!%tMrr0TlT0c)+ zu~m$*u{I_KN}6&x2QN7$dHq7q8ec zhKwa+%JuW*6>G+v>*voa7QII>>H7I}?BDb16}!f;>*v`kwvBPu&%0Ob8w0POhp*T; zMqWQJU$Jux9ZSd5>*wn$*8XHLckCU5ub;>NADa(GUq7#p{Z|aXex4uu_k2J0?|Fah zzlj4-zYm~t1N=HyfCEs!KcI36H~`hV|KsnkT!U}`xCefI{XT-qP3RB~Kz!cHS*YJ% zP`L~ofcpIgmFvI(2=-q&5L^fjK>dD%%9Y>%)bCHITnfjNTfqUS-?vb?7aV~4eGHYG z@mV+kalR^NgS+AUaXB~u_4^$v*MkGV{c!%dARK`D{ScKa!U3q?A5pm^9Dw@$5|wMh z0jS?UQMo7_0B(xwldHl3sNY{vxh$?{ZVLyXe&0pqzHk8Q_hD3S3ZVv~be&0vs{%`>5_kmPy5C@=s zUr6N+aRBP~iBxV82Y_p2z2P2l0P6RVRBqCq9slPlS+BTD9Dw?LCY9U70jS@1Qn^nY zfckwXl^ewYsNa`TxldE2%2ne4 z)bFpUTs95>x6S^>b>jfk@4u;BI1WJlew@mc;{ep}EG4nX~WoyxW20Mzf_sa!k` z05{M6%+=!naQE!rTs{s!{eGXy_2U54@BgV>Kn_6texS+~C_wPGS9ip~^Mn z0Mzdvs$4`4K>dEA%2nh5)bB4c&s0uh{eGj$b>skWAI(2pNDe^#ekAi! z4gj~(d{w`1sd6tl09;J-Sp9yc%GKlm)bDSqTuu%^{eGv)_2dB5?|-UXP!2%-eyGY7 zC zSPlR;)_h#QFROBAIRN$hv?{lj1HiR4Z*y-s0QLL0DmRw{P`|IMa(6iZ_4~Zc_m$&Y zzwfJZe>nj4`@kwUm;+G1FRXHhIRN$h#45L#15m$jta6Vz0QLLG0QXt`;X=zp+-MF!{l2uyo#p`4?^BbnD#yBh-&*Bfa{z+qFU_50*1x10k|zi&?d ztQ_?EeRP$Z&HxSUnrS0jS>> zs6VKlA*kOcSUp?70jS?MSUr2d0jS?cSUsD-0jS?ssK2P5VW{6{SUuZNIRO8A-(mIa zgZ{&_5FCK|{fO1G5*z@}PUufOOThuC->;}|sh+v0-@jNri@^b?-_Q8}2JU1fFe zJHOUinn1p;F7G92zO5lv3nSt`}3v4aj37mm_!l#`=$Uubsq-r`)!lJD;rm&Uena z=9(YxJ3jv7KSn%P0}g=dH+n7y8~}^`dyWUW9&i9u|Iu?n-~gyTr00sj0U&n-{D@o< zH~@w(d5($UO`db2`jeiE0tZ0#DLq#O4uI-cdM*nb0M)njTo*V1s(SuZ`4IBW~*YsQ)H~^}@2_EM;IjYYIUgtSGs^96kJa7OE-}4+F)%*0^A2bXO308~%ZbBo{rsNSgO9)UlSiv$Ni^+`Qf2@ZhjmwGM}901if^;{=7 z0IGlLxlnKbR3FuIrQiUNI|Y7fv485RdTtdQ0M%Rd+$%T$s>cdG>p5Dg*Xp@jZ~(~V z0?#G43l4zly?X8!901jW_1rKx0IC=3xnpnuR8Q7(%isX0-mK@I!2wV`TF*^`1E6}f zp1TGIK=o`rw+#+}>fL(o8yo=D!v!Dr968m?_1rl)0EVY~PMzxOg139lo$Bv;E*=~J z)#vqGJvacW-|M-2Z~#=_*K_^g0I2@2=K{h3P<>#}6@&wz`oY8#Jf~3gg+1304uI+p zdoCgz0M#e#Bi0Fb*${6_VhiSKxhr|LZu|Eb{ss2;TEhQa|*y=c!J zg#(~^(w&mFKLgel_td&uLYCYtMCs13>O8@h@^= z;Q){uOMHx6SvUZypY6G{Z~!d6<~g>Y00PGaLZbJNMjYH~^}LPJGmJq*X7S_^IbmtDZXXRnM_jy>-vMh6A8_?4Fwq z2SD}OJGtA&0Z=`6&+Uc-pnC6~`wa&`_27vQdycs3#e42J901jm_uO(g0IE0dx#w^I zRFB?s)8PQ9UcKk8!vRn|d(Ul$1E6~M#J@cU-s0h&6R-OC#LGQrUiI@mmmUs)>g#*1 zJsbel-zOgLIr-$~6Q3tn9}a-(_j@is901k#_gsHC0IL5FAHZt@P#XY#0JQ?(08l#s z{s6TE-~iaUy~Y5w2H*ftdjS3cwFuwi`Y_ zwGZF`PzwP*1ho<108lFdz67-s-~dod0X_w_72p6+YXQCmwHM$3P>TURhP|5_4uHk} zYxo+}Zh!+oEeH4<)OLUaK&=P(9@Kt-13)bZ_#iemYB&HE`>)}PP&>jo0B`&M0pPVI z-~d?czlLvOW3Pq-KrIURDAcBa13;|`_$t({fCE4+3-~P5wtxdbtqb@r)V_cNKrIaT zFx19?17NZL8oms*GvEMFO9MU)wKd=XP-_Fe4YfDm08onqJ`S}x-~iZMt>FMry953X zwLIVeP}>8354Aqv08sk_{tvZ4-~dn?1b&doiW&|8wL{){uP^$zE0JTftFHy?`4uHwF8h#VCPT&BT?5p8FQ40kQ0JTxzM^P&U z4gj@N;7?IY1r7kURp0=atgYc&ne46M08onsK9c1`YtVV&IFJ?x^7aP)i050JUY{mr-j54gj@h;Ga>81`YtV zY2c?(s|F4LwQJz7QOgDn0JUx4w^8c`4gj@p;J;A|2Mz$Wap1>MD+dk$wR7OlQA-C7 z0JU}C*HLQ+4gj@x;NO`puHgVsn+JX#wR+$HP`d~I9<_Yn08rZpejl}d-~dqj2mT+m zfZza78wh?NwSwRPP&)|zAhm?x09fq5hF@s5hSwaT_7MC-Y7xN!pf(ZwL~0em0ibpf z8~|z=!Dpnl5gY(&9l>{`_7NNaY9Yagq&5;90BR+{mo(d{h67-+{~A6ewUwM-`K?aP zC2B9h0iYHWd`xOH!2zIF6MRi-H^Bj*mJ@tVYCFLJpw<(7PijBG0iYHXd{Amb!2vK^ zv4$^7?I<_^7W?;_Qq-1$13;}Q_@>mJf&)M;DmVbtrh)@twrUMu)oj-q4gj^R-~d?c zzlPsRtt&VH7W=Q^znU#v!vUZ+7W`PVm1{Tv)XsuGYqoR^2f$+gHT+s?ZNULB+q;H; zOD!%q0MzD!13;}Vui0g_yWjv&%L_g)wY}f~Q0oi6FSWnm08k4IKCs39Yd8SZ3WEbc z?J)Sm)DnXOKy5Mj#nc*u13>LD_{Y>Dg9AWqGWf~VDuV++?K1ew=F8M@0L-_k;Wtz3 z3=ROb&)`2(3k?ncwb9^5Q!5P)0JYQLPg6?`4gj^);8#;?4GsXc*Wh1U?7xNsKy5ZS z0Mu%O17N;e4S$kqy^wg2D%Pz#WJ0BQrm0iaeO`2vO=)NlZ(B?t$=u!WlZ0%{Gy z0igCE`3KY@gabfrLh=&~tEk}sP`i-)1!@_>0id=a900>QyyhXb58(h%3z2*XY9qn{ zpjIOJ64XwF13)cB@+qjT2nT>#i{x8Sdl3!*wHV3AFl?rV13;}t@-?X42nT>#j^uMt z+Yt@`wI0d$p!Opi0BS*!4?=B7H~`d&BwvKuk#GR0B}qOBwI$&IP-~KW6KYSw0iYHo z`6$$;gabgWO7c~xT?q$(T9)LqP}>p?fMH!V`7VZi)o=i)g$W0M+L(rs5&N$VGb4Yd zh67+&n%C5%wk8|^YHgBlL+wpC0Mz0nABWnUZ~&;)NxlxXJK+FO%aeQ_!}e-80Mz;< z--p_tZ~&+UNL{%i8vsC5emz_9O{{5NXh!U3Q*F8OiP%7p_!?OgKbsHF=BfZDp` z*HLR14gj@x$-ko(FB|}B^OB!OtzI|))b1sJ&#?R&4gj@%$?v1qFB|}i{nzCGQ41Ij z0JVY152RKw8~}?Q)D}bVTEcJuEVfXSUr4QCH~`chCjXFH#BczpO-z0wwTj^YP`jA? zMQRzt0id=q`Hj>%h66zDWAY!Vg$xJ4Vk0&AkL$@+YaK3 zh67-+|C)SJYDdEXuvk(}J}I@O;Q&x;8V&%pr{Mrt?7t=-mD<#B0H{?>zN*EpYB&JY zvL>IE+SYIYsC7-gtHr)*H~<#=ugQnC*jVlPu}5}lW?Ss6h67-+wE8B?r=4<6r^Yt5 zw#m1p_BI>?=}4` zw(m9msr3&BfZG4$|7-ivI{s*C{1fZf`Kdd=?@rbAP^Ws` z1fCCd6L@aK;(4CbS>QPnd*}HdqxV9+2HqES9C(k^ci{aJQ|G-OqwzotopD0_2*wX} zB^X!7XuKVxaY%g%#wT?v7`Ml0JQD+FocsTMLH!HO3+iPsU#O$OJR-Ku{5nSSj#xJH zkvbjBQ|fmxf7Ab4ulY`l8aY6H5aa`OLy#N9qLC;4k~7pFLHS)qIZyo;VyM^&{jwj3nPOK^ZwPy% zUv>zwQS1}y7Gbwg&j@>_Uv>`lkFbBJi-cW7y(H|Ve%Vp|vag6~Vs{bC#2zDtiJeC5 z68nvqC3YS4p0M|bQDO&D9}4@Bm?U;1^`x*TsWXM0*)RK(x>VSu)T_c?rH&PLEU`uG z+kV--)WgCarcM@iGWD~tpZjH3Q*R4t+B;r+7Di3wu26AQ$iCkBX}PyH|K|9<%e z#QN|T`sGJZUkv|(x?}hq#PaY*s8fcYLj5xQ7wVef*AT12-=Pi~eo(*sqkj2K)KkNs zA_j+_)i3|6Uw#>}HvBbWZ1{21cf-Hym)}P{IQ&8C#Nj7WKMwzqm>GU0_2%$5sY8b! zN_{%~(|-A_)U(5%B?g9{OZ_|iUt(VP#p(aMmLE-hJ^X9x?%{V+j}L#GI(_)*)bGQ8 zr>-AM;(LfmyCnTfuLM zS%B*js{rpMMga~?eOT~e>c-a8jTN3uomp_^TKF?D2XJZX)q+=3#}*u$`nKTP)V&4w zrXDVMcrBcq*a7%Cb#=kjskaN>P90uw_*(cpF#&LU>iL4_`~UGvEI{}_n7?mRyugp; zJBly(xj3id5&m2Jrs5Z1_I^!V8`sFSa?M;j_rSeyPuv^#s5lGQyFUY-1<%B5?HcCJ zv*MZY?0ANX`}niv87ofY&z^U{yWpKrE0=e~yW*Yk?s$iaTlu@?9V^b|@18NBxR{R( z#)#r*K6V&Gio5yPVvH$H=VOmCsJNbwO~$C=fIfB^!;EFdG_`0Mhx*=xlU1I-HuI=ydUUzyMw6 zqx-P|#0zrU02@I(BCtKTA;dd!+X5RyJSDe1utBgzut~5@uu-VdiOnK@l-n}cG}t!S zIM_PaJchlw4TLR(O@wWPjU*nI+fLX};(fVog^eYinA=|1VAx{VWa68-t%l7;ZA@%9 zYGPv3VcTKjVe4V@Vf$eNiWld$AvPkmA~vJ=bzoXpAp{?ACj7e_>|N# z#K*+f#OK8K#0M3x8?2(^qw4=D6hGX3S$taY$-yAp=f(HM2No~gePeuNd}VxQd}n-U z@!r7_+{YGA-hFR;aPjKF3fxD>SI1{JY`}eZ@%F(2+{cgq2N2&M3?TmBKjjNJh5!Zt zwg3j8yaUG~zyQD~zyQqmr-q+n8ejlm9bf>;gK%tw>sQ`{V=3Gp7z-Ex*bDa$CIbcl zRs#kAhQsp$+W`Xr^KlG7|DPTh5g35-M;ue)eJJ0=F(}@b@>3kM;(aQg#W5~00Oh|p zCdPPBzKmmNj2EyqFo5`f?ZD!|0FcL0{~NHK7zG^0f50WU%_U<0KjaS z&tSP=0ARe#cd%bD05D&gb0Vto;V@&8f<)3;?3Vled3jL@&R*!9g0Vwa) zV`1o5<;i;N4E;+?4Ge%-8~T|T92fwxIWPcXc3=R+^3d^|LZY9FaTnOU;xS^ z_Sho!gYu3&76}GGj1qf;*d_J{F-`0dVx3?B#6YoEh>d~)5Hke>AeIUSVD^s3T8X`a z0T7b~10Yt5eMAfw41m}!_7gE*FaTn~*jL1e!2pOIV}B7-1_L10jD1E78VrEgH1-=Y zYcK#}+1Pi)xWNFF|BgNAv2o?gdkh_Wk=Q!+BQbX{0Algjm&EA70EpdVe-hIN12Fs4 zWB#fG;M@T0S2zP;0IDb890M=_)gN$90`{=#6*z|hds+1job!M^t$GN~k-*+o{RHfB z=T@lRf^#si*WqTs(SWl71^|}>3;>P?_CDMXFaS6q_ycf7zyRQo;4i=}fnx&a1b+f9 z3K#$!6)*s}D_{U{TEGC{x_|+|fx%ya8v_PlzQ1#4;L?BrsLlrdk8^NTm&3U__(!Va z;oKhlCpbS~0C0iuuiyxQ0l*!?|AJEl1_0Lx{|pWi7=Y@NIA;kAK=n-U_nhkl_X+48V?UgBMWS2MoZ@)do+XmJb+!{Z<>iLG_F9{hiwg z*AWcBuC)yY05=j0!0x3D1^|~53?Tj=9@SsM_jhh){C_)eIKcqS_jitG{J%P?2jv`5 zFaWrt;4k(r+F$^1O~C-{UA4gg;HH8BP!k6Xz}{^ee1{r1U;y^+odc`7Sn2<}fkO)h z0Jj$W$i`9|48X=#8+-|lE*OA~y*Bt0HEX~CY;3l{r{DmC0od4WgI}5N-v$G)vF)5< zIL2TAsz2tOWbiP!%3uK0m;o=NwhS16&80SY8ntA=0H`4Y20-l?FaT=CfB{e|1`L22 zF^&Or>a&68wZZeK1p@|PbG;4TN9`9d0Fwo6@IY$4fB~4SXoCT$zFhi$UErdF0mT2~ z0(Tw!(PU8@3;?b>7=Xzt=fbN#9=^YG=i$Tnz+`tD{MKZ-=Psz8q31Y&0g(Fu z{%g9R4F+Jkp$$GvjT0~c(;aQ_V``d!0hn%SJHFhh(+K|D27jhz2^fIsrZ)IAHA=t$ zOn0@xuc=7_24K3a4Zckc5-z8zJD7GfZQK20M!NcTp{8E6xfSMj)0A^dXi7$|&1O{NXN1ONqIZa>yW}CFZ0LXy?15ka`^#5|0ZPNw=Fk7b$ z2B7+@`2L=oMXnYY06AP>0OWQNKT+M+^#5s)BL)UwwpW|@i`imrFaXt?^&B+fHRPs& z0hlf4xohOIfdQDU*9HS1_YDldY(dYBBUg_2klBiDFaUDvzyQd(0|Ouz4-9}DJum=j zSAYRnJgN-_K&~J0DYI4EU;xynAbv$n3gTI2+j>qRH7LLU%=T>)|Dxsu7=YQvp0lVr z#_9i;Am^Znak0OtF&!2rm~1p^>g7Yx9Br8e8w|jFQP1sGy?4(6Cthv7tLKQD zFWV-bZN6@KaDIG$eh=TD-%oY>b$t)%df`WK{qQEZANUm9U#i2e`^Wd^dEoo=d{Ui# zJwJSZa_ixPwBdv3dBY#!`NJ#WeSAyr2ObLVE7ix>`}~&PFFcnvJQuxxcrlCz_%e)- zROepf2i^_i3E!XbmFn1Q{H40}=KGVgj_=Y+>C z!+%8nZfImq{*Ja z_s71$_s8DB_s9Oh_s1T>_s2fM_s3qs_s4$1_s5>X_s71%_s8DC_s9Oi_iuv%$UejO z$6mwt$9}{2$DYIY$G*e&$KFfzucPjD)Vr3wi0_a6i0_X*iSLhniSLiSiSLj7iSLg+ zitmqon(9=W@82drK=y2^M=g7o`~&P?@)EFzQ@v@~%c;J!>}m2Lu&>FJz}`;vqoZ!L z?DJG7TJ}4>KlVJnKlVMoKlVPpKlVSqKmGu|KmGx}KmJ0h?<{`;-yi=1-yeSi-yi=2 z-yeSj-yi=3-yeSk-yi=4-yeSl-yi>mJexKcfc&4f{Gqn|Bl39gmr{LY`BV7*_*eM; z_*?k?_+R+`_+$9~_-FY3_-m;?vi!MJ4_W>mzCZpSzCZpTzCZpUzCZpV`BnIjK8}dV)>`|{%tS-`LFo?__L`VvHV@~&&WZ<_iuv%$Ui2J4S$*ZHvDJu z-tebWJz@FV`2KA$0Quwi{`lwk{`l+o{`l|s{`m8$9h=ns@N4Cogae8=B4?_Bs#TX;}A>fMs##+VU)lQlaEElr0^+xfAA`Ne;>obv+(_Wj0^8-3;*)Dz?=|1=5vKPBmB(g5_3xUn$I=n zobWfFi_A&kbNK$?b>wIJ92TDEbDKFXywB%8GC+8s%LZhG@WNEzm7Ffa6Y>4MCcW@R ze1Dfg$RcEt@JW1sa<#~hcNrFSS%q)9tV8Ar|HSuiBNK&>wuP6v>_mnNPj%Ufj1}JM zvKJXFJl171GFo`8%Wh*Q74q#ATWTa3o3jc-`{n<@c*{r0d5;$BPd?rwgWbV;t6hBU}GrWfbZ`%h~g1$ zn_#0TUeP8u2OB2paw@*zwhlH=)ZdJ{n~IO%`;%*f@9#DgIW^c+QBPCx7Pq~y!LY@! z$rPV)TMe5{@f&>q&DeB`@8J8p&8PSezCZCGe1EqQ6)$qz5gRh7 z9Ev~U`xB4E_jeyf@k;ky@L?3sbl(OaNAXVgeei)455@N)m(9hbJchpFZjVMjb$c|6l;(12{GS1|YtGV+VX+ zd;-T7I6qhe7=Zo0V-VsaI5xrciLc<;1=kOj0R{lJ!TpKv;MfNkfcOxOjer4wm4KOu zKY{Px!Bjf@3ddT&0Ki_r0K~^|Yz7QKd=1BLz;MLp;QczrBfbakAO449L5v5mAus^2 zA}}NIM;uE60}#K&u_iDl@lPC!0+SLyh4Jc`mG~=;Wr1ml-{M#o7=ZXMj)j2%h#%uv z85n^0GmfQ!0f=AYSR3;V>yn=y8{CN%VR!+?STP+^)cVU{=fjh z0+9z`gJ1yS3psWO1^||bJONt-0|0A8-he%V0f0p!kH99u0Kh7dS8)HS&n7;TW1C-RhW_gZ0}vn1v2ic}xc}4{6MxRJbT9z%>l|wb0|0vm0|1K$0|1*xKZDhS z0f@hcK6gwXY#;qDzMo_NU;yF+;`@^W;IRTQ0PzR0Cp@Mgexb)2zyOFnV1E#c00R&| z(PI^00OButECUQc{6>#;fB}gA=&=wm0AeH9M`ka1%!Jqp_7kxbFaTmJ*jL0_zyOH7 zV1J2^>9H9w0Ae*@0K{&v--zXa0TA24z9ZHH20-kG7?Aj&sos_Nq8>ZKek7Iz20&~H z`;u4_7yz*+>`!7*U;xCXuusKT#eVe|miVk5+aks#zN^Q+zyQRD_1G9OGVx`xpW)AX zEDd{_*cups__iK z+=(TcKS68}3_yHik3E6`h>z^CNiYCnmG~>fF2MkZW#Z2e+XMq3)``C({&T9kB!0BV zO2Gh#of1P8pW0)qU;yG@jii<2_c6zf9~L3_yH(kF6797vCQL+hg#=;=usK&-Yk87=ZZu9?J&<5WnAJ{a^r5 z{|7Dr7(mqffhzz80CxcV04@O-0Neub1-J%a0B{e$AC!-f>h-`?0Iz`i4+dcOQiEqG zzX80X2JeXaJN7J`6A|@x;QoUF*s~)CAl21TenqOIqx=hef9GVt{Rabps{vjE_a6)Z zE(drH+zv1RxE|m=a6iBRqV7%9yMZeL1_1XT48VN<8axSZ2^aue6YwUuCtv_@QNW|% zrhoy!RRIHly8;FP_a6)ZZVMQI@?F5cYA^t}|KMS8W557xuGHXVaA&{(Y%bN{X>e=6 z0N~nyx52#u1AvPI9tSrE3;?c>FisLukI2@F8_P2in1cqiO{FaWqvU;xUG za;_8@0Ng3?)2ORrvb6?Zg=+-{V6wLce}#($24J$e2A_qi1qNWUy9U37%jI=ZR1YQU zpeX;#xnN)brW|G@y@#(|HUuB^cT;LgFJgG&bn0Jjc&9j+Z1fa%^E z{M~eM4F&)=4-5eAKNtYqJum>%<<9AY+Xn`qd_VAi=Kv}n(7A!c2b3@9+(F_8a0$Tx z%(keBFTgbf1Au!71_1XT3;=E-@d>#9U;uCz!2qHz2i!(50Jx6CJCy&J>TW1MGS%5o z{$#4F5%o0ST7m(X?Nt+hFVg*jy3Tk<&zR$a*ionQ{qi77y#U6;+y8{)L;N`pNW6M{Rabp8w~~k zR~igJ`P0s&CZ4MN>QqMo?ll;I^0A$pO?=jTwHgcn?lu?zTy8J`^X;7DZN6Sjych02 z7=ZG@i4QwR+~UQ~8CU)|@#LC#GTeVK0J!GFo8kV00hljJ4gkJ?4F(W(3e5L+4m(_S zFaYyyo#PJIop?9gcQ62p|2rq%eB&Anzgz$4K4Q(nKW z2Opm6^xOrzes~SsSIXDdbHF#}`5dF?mh$l<4`0t8pPToR^6d@7sqwY-evi?6_goNs zYK;@m9l?jzxJvo*kteV5iBHV9#TTyei8apgeHs7wyvz&uGRzlzT;>tJE%OVXmU)LS z>p3}^r|@@}zwmmP*Z8WQ^CLOXFZtj(L-2+qPf{Mb$b z{5A9!K3k3NCVhvGh91N>LqEcsLvP}Xp-=I_(6jhnaIjO}we&SU7J3}t3jK~xh2HO% zJ&^LKWk006Y1tc|gNUyr`y}N>%buxa=hU));6-8=rF>`EQSd9Vui#x`cj3!mkKw~$ zr`3_aEV~Y01$z%3D0U$HQ0zl^qu7o3BG{8D4_Wpnyj1K`&sBx5Dmymi7t8L24~spV z@`xjUSavnO0`_*w6PA4rZx_40mOWob9&qIU$}hmy_haNoVB6zgc+N3-z4Av=9F^3rto&STUmpYVi{Z+ zXBFF3{=Sb@#;ouGAIpqsxTuWr$U_zW;B$dFA-uxp3UfyIhR-GDl<*LrYs@*}Cq5UM zlfqkkt}8$mtn%qu*KkHl4s*G5AG#0P`Dhnmdi+FCAJpaN@OUUN@OZrN@Ogu7MY9e zMFyMA1a~s!OA3c{*^LYrZt1ce884jEWj{JVxTxy}bcAqJY#Z>^I`SHY$6~{{&Jli# z&Eh&qcrSTio~Ic3iNcMsMO?=TXU6vM{KLpQjC?~lhUiS;+t?JIR~Y$(=vs6xx)&Ql zxH`6i=L^CS#8wbKk4@k@-E0BR2aG&GbU!vg?WcH<+lbfz z*pAqc*p%1+*qYd!ibJ_=%KO7+#RgD3%WYh20L8!DCdLL(yv%KAYyidA+~&pxhD+c_{3))-_;i~;^3)U`bf1Coj4y!=pg5!Z9*qCUJ5#(8-S55(z6~}&%yL z{+Qyb?rUKK;Dh0dDL(5y8#VyG9P=9=4;w)7U-t>|4HYkT9};`s+11WDR@}t2jbWe`b)eK$C9uCA`eOY6UU^`hvKU^hK0V2{G!M! z5+4SA>$R!HpFtlxwg%RQ4G?)kU~}kiFgt7jusm!4@qAMLPvrf;^}z;!J z@_N7`u>m5FC-Qe9Z^v}MW1f+x6ZtuIFOHpxPlfJpV*`M_VgnfN=GZJ)Ej9ocF7}c= zyEZlem@hT}STHt#J!`l$=>9e~0GKj1fW4bG_8Ay7Hh{gmHa38GYuI;=X~TiR27vp5 z4FKl_8zAysBF_bE9UDNrJICU|>e8+@>bxgU<24#ZDX(6*llA2*jR33&)V4b zm_p>CME;4*g*Nsuu?lPeVi?%V#5S-2Y%aC2r-_AN0}vy@-iAAZ4PbMzjXe%m1RKES zY8!i<*bFv+&E+<+o5%+d&lBD6F(6_>*Z^=n@DGR~VFQR?ia+78C%7Eg0OF~7>WS__2BJYA&9X0?lJZu1Bd)NTP{ICIt1!4mb zBg6(U+1thjAf|{7K&+9NBQZ#90AiE)Z^SII0f=Sd-x1@)1~A><#{VNGiVYyXw8v1f z0Zeyzj5YEa#K%VWd#qOcZFGMd8zAx(!~;+H3Fgmw>^Slfh%sXWh=1-eX>5SVHz0aTqx(4?-Ou-(a{%t3^P~IuJ#;_6pLqLl9pF6ZdcjAyesB}+C-L!vhp+ojy!+tW z>v=i10~;WC^}(mt^G^JEy^q9~*ZTsW;{Bof+t>hlzu;WFZ}2bPKe!m;8;D(H6bU))e@z6E?!6luWr1^pFZ({>!{v=+x z=2zm82Y+1i(YaROt(vdkv&4wOZJE#Le&#p2pZN~{%luEgZ^;MekbxshexUo2C+L3U z3%Vb9gYHNEp!<q3K$@P?(I z6Hi$B8{LmSNB5)O6AxJVzwO}t%0BR8`Ht)d;*Ne!*%yh&8~k0_Bj|qT>jqCZ__@K$ zm3`y)%00{eLHGMJA=bt-lD*{5j%O%)%AYOIm>3$*T=tj03*HIuhIb@;4c$+SEb(H4 z4=a1m-#ueM_F&?>2G2G4t+FQ*pEY=_vOj$+GA3o8`dDSm%6|2+%$Sya3(sIPV_x>J z&jscLu_oq->}8)j%puv+KDU@-vbTNiF$ZOj``l!X%3eqJ`y6I2V*|*(hv(sQKKP&V z2V6EFBajuy4EYb}ewQi87HojvamxRI*WxlM_?q%p(ETpM9R}Y}{<7;% zbZGDjgHISdLiyjWi_yvQ&(Zy^v*o|LE=Q-E?#I7J_j|4%&ObJQ@PNek6JFr912%y0 z1h*})0faZW?STy-JYs;aC!U`03%6yk0fcWP9-idqA2xvSAh!*%5rr4I?T8H^JjrcKYyja+ zZhJERgh#n;iVc9Rip?tg%57Q3Gqx=@K=9Cne+CpLiaX!lLgPxz|X z0K%``m&Kcl47r+j%0l@yT0Tf?IJf7h11aC+2iS++o1wRKY0~;XtICif! z_KxBo=zhmUz(%kE6fePksh<+1A)sU@h1HioZA(gFR;Nrp5*U`^N?VyTJxX zycqFef(K*ozQ+DjJP7-c7(n8=D1PKvlG^~UcmBVj;ISzFggxq*l;Tru8>=<;D%ce^ zfQ{uEdlqa98vv{e8zA^6HWzB_VX!f50L9B3JHvhkOTz{LTf@EvYr_Trd&B+)i^B#0 zo5MZ_tHTBWyTb+m%fki;K1lFD6#sK95F5Z`Lydo6vZBTY2!01xA~t~Hi{z;~k0baS z!P`)L5`V=pOT{l8%ftpyd=r1iF;B2hY=GchfQ`C;B%X!hr|5oS0FJF<1AzVGZ<*|M z3^sTZiqE3^9kT`d#|8k)#RgD(7v1leugU%z8vraAe-P{+8$j`5biZTB!D|RUgXtQ_ zoP)n$y2vr<;41`AA@~WV%N)}VK7!)iiGL8hgWwy0{bK`wo#Q_TuORpY=Knk94)%@> z02Yrw4mOVs5Ig~}du#x(eEfN^eQW^p_Z{;G`^W#+_7v~ec~X2|znkLux=xQ>pu=@v zDPFJVkmB=tZr~|APjs-yTJ-$EWx(FSYj|HN&aU?h?gO?C9^^40jT4U@p+hyUz?(eg zq;Uv7qM<`=jd^A0?&MyF|>ruenyHM)xVp5oM! z58#F#JCr;@2YIYf@+ZZeC9lvi$gx`T4crsC=dn<9isYonPSGKft0`VAIqbES(Gil{ z9?L~1NX~=*`bT;JS?|Y4k5He=&k=Fmi04KeSNaQ??bjrI=hwSn-OH zy*1Au;;s>Il^%y1=~vVV|y zJ|<)@r8uYTt6Fwfif77BLw5NXlwIdzlQGIzWz0r=Qh5+Qwi)A$b;dl{BXdA@sm~4O zNW>W7Q=eWrLut1;t$N*#lecKP_ z=Q4!j%COwpLH^Q}$ zPj2(twYn`Ve9UcTWPtFr6o;{UcN;w7E-Bt(ISGhkBJPhx$izGJ}EK)tO5NPafXO5L|j4jX3)3pD@Xhw;s(OoQ=CBf ze2NPQ&u8wtuaEC9{ZBvP{WkaU^%K4yxW3MxaQwjU1Gm@peJgN!U4O#mb$!>)I1PvbM;)Ed8@1CI;{JUVb_jsJGw&YB_XI&MWzmaNWRj1ILy8!LRjel6+$BI~E@J zEce1aNxtD{`#nqk;g>r$A9$a z`JQmlz(1uA65bg&XW*OCCkf9C924J#F(`e+-1jjmedS}9F&wz0^qY@$#(dz9_#DUp z=|^xZpEJ^*30Dj}F>u7d4+A%pe)bp~b2jk7zy+n>eXb(|Z0>JF2H4zpnPB^|519Kd zGh{y`Tu=5z!tnyX3*0X7y1?lIp9@?L*@g^|z2mYE86bPeWg{|D_7cy}WvJ{am#xSE z*;^hv=J^M17I>NLwUl2OxLDv}viB1H6}Xq|L)R6I7jy?QK=!2T7RHzC&4gdc9(CQs z_zavX@F{c|u_@WNjCaSOWdA1IN%k>w-*u+!XV<030NK~fH|*_%9|dj{cv0X)vfo{o zBLigLCmbm7pTK>v4UiAm3dn%KcLLW5JST9Rz;6P#3A_ed1sM?djQp8|$52xk8G!AB z3<%sM;Vr^hu$_|56GYYR^S2H`sjOXfAqh$Pu20s&)4~rU$5&)e!Q+f`R(Da z>p3L4JT;qKuKU?oN`PCW^iPx?1<31&GC;VlN!{i@p+$Mim<2?Dl znit964L>*hTg|)V&uX3~|26#9@K>=>8LPqX1v6l5N}eP?H2lx-JHy|U983PC;t0u~ z#D-)nh5snI3Lnxjm+%wAKMcPx{6We2(V&JFuE?AowrHQw-D+gwA~tzoZ*of`3djc49H<2%`*VSj2q zV6V8(A{+zz#_h|nD>c7(_x{Yoehj-Y?8UGXHGfkaIqX5r_hkP`9;A3~*m;s4DGnR< zT-b4vKgn(jdrk5x*=J#wNxr4Hq~ssZ!{>zLW3sa%J}7yLKj4@^*im6WNglVuUJ5%& z@;l|}hdm^D&--^75Oz=4J7MR9eG_&~*fTcXJgy}D!+5M217WX(of7s**d@p|#z5F1 zVSh*;I#$IP2sOLf>f~CH)q9E%ce@X~GXRuM-|9IpDS}&p>h`>7&p? zp?^Z}guV$qgKS}phh7PN5_%-`N9c{v7ojI4pRoy?D-rr2^gzh}B=;rnL(c2_*s<=* zhCB~BuHSc=#xn?c9dcUNpKy$j$03J9{_1()&p4(LayH~^$kmXidfxbNu0!-blDrH# z8S+u@({&loAmkt~pJ$-)z<%fCYP`5^O~m)?7tPZ}r5ev5e%^Cjj<%nyy* zgtx{#i1Dxfw_?2O_++2NxQ_80<2c4|jN2HmF-~KA>V6nc_sVj&wz8p^H)DTZyn!`=Nr#8o~M2<*)O^tYSywH3hf1&Y0`9f<%Hli9) zjA)L?M>Iy1BU+oXP1UAiQ*%?ksj;ct)S8ves%90lnzQm*jalWa)|PBbwWZk7+>&o; zY$><2#%1HGamBdixO`k=Tsf|FZ+35WZ*gz)-u&Liz2&{F)!FK5b+Nj+I$zybU9N6z z%eGb9ifzqp`L@Qka$Bn>>#2H*o@P(p)95LCT32OPRaX^PHLuFAYFt%b)jBCVsXD1R zsd-XS2M;nipkG2lU4yg_)4rv~eAJRCaJfwAJc4u{GacA?+ z{LaRm<(;i%*|KU`v8=f)U)ESwE^ED_f4T8;`EqODY~O0%V&CSz`M!;P z%Y9onW;a$h7B@C;%x`SmSl-y0lg+8-6myz$@;Qw;<($?t*)!EM#WT%k@@E>)l+U!L zWK*gs#gyihd`e?VIi>YL_CWPO@j&x|{DH;;5b{- z^wuNUBh@3tBh5$hM;ecmkF-W-qpQ)y=;r8rbYpZmx^+i(M|DSWNAr&Sj>aA39j(RL z;%afRxVboA+*n*LZoQPfRJ~NZ)O;y_sqs?zQfseluWGMiujXF)UX8uVy;|32*H_mU z*Eg@vuWwvmUf((^JF7aYIIDS9epchG@~qZV*;Cb1#Z%3v@~0Y4l~1)MWs|B&#iZt> zd{SdlIjMDDc3*X0abNSk{JzG0<$bMn*}7_7v97r;U)NYyu4}!Ky-~eUywQ9kf1~k6 z`9^D4Hmn*}3~LU{hc$+k!&=v5*HqUO*EFxmuW4LUUelVH&8%h?Gn+H>nT?s{%+}-C zR&3qgpp-H&-_oH#cw2 zZ*JUN-rSm-&8_AZbDMMXxsAEy+}3m1bJcUjbIs@S=NiwI&$XszQ>&@P)aKNDYGZ0S zwe?W;Q1wvpQ1hYup~geyL#++jhH68xp}8U7(AZFJXuXxaRlQZb)qE>|tMOL(R;$R0 zswj$Pkr$1kELxw>K3{#l_c_ z*jQLDY`vJhSiM-h*nBa6vGHR0VryhJvKm>8Y>v!FHb#~sTi0dRRo4~QHLuIBYg|`e z*P5Npu4Wgro3r!TjoIbw)|1(j)sw}O%_s9G8&8%`wkBi~stLt}=7fAgV?sHh_4VxQ z)z^!!H@}{Lz47((>#a4}nrcn4rnx3x(^ylkX}zAkUcFwt-h4fOz43badTU5Fq#9BT zX%5MUG=`KzT32URS63HTH?PjGZd_en-8v;Zr8=cJrFlwzO5>FBl-6U}W7T8DW6j6% z#~P27kF~~RW2!O5nC6&#Ok+$rrgc|#S9Mo$SM#p?uEt&EU9I!8^Q-fV^PA`A=QqwT z&u?wbwpLqON&dJm*$r?E-f!@y_vmPy;;23d^3Nu@n-pEtC=;cX3=am z^Jb%2Hd|L_S5{XRS2nNAuWVddUfG(F&8TJ+GnzB<8I2j`jMn$E?^WL`zSsO-{=LTc z%I~!f&JL~)E)H%UoFCjcxIDP^)$FU)SBtMUznXuw@zwIHt)y<0bAH&iziH#Bd^Z)n_5-q1Qb zJG(l&IJXi;J5V=NC6FE-!BVB>PGAlj0}MpX5Jj{G|LzYj`%i8eR-< z4$p@-hL^)z*JjsN*A~|{ug$M*Tw7k-IxRb`I;}XZd0Kv2@;EmD$Q_WwElkGGEzPS*~oo zn!Q@RTD;nPHGj47YWZqw|7`zi|6>2<{`vlm{mcDZw`8|ew-mQDZ^>_I+*01sIyXDF zI=48td2W7gKtv`O0IvZ+9h*|l~F?-vlIPS+B_YM1VSl4kgIqvZ>{awes-`1O48#nLg z`(V~{xBXW6=8~?%j*r7Gjl=9`KgH=r<-gr^-1%|b?Qz^^v!N&3EtaR{|F!G5>*Bb_ z;<&f7p@(zaSMq=8I_|+Z?#H&$c`SK0bgOmBiAB?nkNbTw4jg40d zsIB`ApO6l0WkbKo9iQFc)y5eo#epl+fxBlzdH&_H-9FcK;HToi-%kgAFdN##PhYwR z<08&@B?t0O9!>}DlMP+L8LvO!ue%QXQx4=M|ET-G4V>}b55LuQ;4`*9G`BzHH~aRo zTZmucbq)P6Cw`*u@UHE=o}oGS`dZ)guI;>zq2J~_lg7^N+Ro!2dIj76Z0x$O?L6(F z=W(6~$6eF4orgR0gKYoSggd&n^DKw{G1v3(pnYv8pn;zhW-}Ey)b52HE`cQisKHjjefo(v!ScF{+Gv0>N;)@Tle#w9LN1t zHuU%G%jIih=5`(T(Kv36t@x<=GaG*I<%H#7S9Be?AP)R;9N4x4pXR_r54)%9z^miH zN8-Si4L^GVS$W1`f7^B7H{!s5jst%%JR7==1AlZ_WcCH-nP-Nv2Ek@XdX`e zkwd!PsG&y>J$X-)Z`$5t5=z?} zY;WfI$$RFu(mEhJdC#$S#-2&(YxS^Vh>56!ZI3;DKfvy6s1C62cMiz*vg@!XV~bsS z*YYDw6E2)Icj5AtbNl+nu2{Zs?0Jh8jkUu* zvU1hRB_CO`VBzwyc3j`Yv9>$?8@zw{%0(+KTD&AnyH6h2aQvzZE?BkltOX10YO-wY zy2Yjs`j&CAc8+-$ELgY9dUlue7WuLB*7?DGi!vK%Y(H-Ky4g!EK6&NhCF}h>y zG_c(_W$P|kzIgG9CC9H?vUJ{>rAyb%o9u_oUb1NUYCqzP@kj8Tt_>5%5Bk=`3EkZ@ zZ13?$%{~5OXP$g!=kL5Tm#n*JwYE$@bJo0>%NNc)bJay_7A={3;_=6Kf4Or7lg52? za(3bPBj&BkmabT}z+9BBYn(7{(v)BzSoC{ z52o=G#vR#v$eJZ9mMmDiOF)J zbCye^rK{HT+W6=_K@zEV)|yp|maJX7YR%e1-;E)4>;xnTGAzpvvDL=$Hu9IO|H#KC zX3Zh3kL^~BtoF*^o9|QZo4+sLFWL^ z!nJF&zBQ{l9UJX^i2|ku z4o4+&UDNFo-?7!~n`?^fa#pm&zO$_#>+Gu678!0sEU|C4ZRq~pSAMhb-{E)pz4+ZF zwjSTH)$9{?zJF##OYFPQ`mB%B_UY@2?D2T$+QUY8wu0k2?6}|aJ)J*s9PPkc%Ca{;Q)F9g!wB1M){fsV>pYY0^F4A| zkzp~$66cG4wB6gQ?6tRJJ8hY+wzIVybS3QX{zdv#_TKIj_|*+;D1Bsf_ge!UTQg5_ zhrZciT}#=qFw>SY8(8-%Trb$doWIG^^?u#@&sd)c!1upRzhQsoclulC<3exj^#42k z|I_|V>-1lze~>+#-cG-?)o1WY^?diF|8e`H=ldc0_)Asi_=)rv*dP1H?;l5hk^Qmr z(m#X#;v!w|eCy9yVt;f#RP|1}bM)dty3W=5PDWWr*<qXz{+Hj|>SO7b1+|jP- ze18XJ>l=4vr|jBR@=M)?3F5ZHF18OgxCabVE_fG*{~QAc3t<;WcMSDi7?!&@){F|< zI@pFEyuqyeu1AQ~+TGp3Q`OE=3mC<5i`D+R+BIr7s{Ml6 zYt{aq+MCt>k=i@e-lz6qwf~@YE3I8zW%G^S9ZB13*Q@?fv?j~WQhx#MVFpdA|3%s{ zS@uWje~tFgEc;9K|Bm($(_88nHgyYoC?BA;-#d)<;4GV={#mpKWv;u}{~Pp2XW5O~ z|5e%#Wf>?B`~Qmez%1LU{&v~}>{E93kD#@ev!D8h(C(FG6V#tZyJwc2qW&D(ky+*l zsGT1573%ye^UJyX!p;uH`VVkxmTDjIFQ!PKaO^k z{l5BhXw67mtN!O`_sc9E)j9qyS{r14uKr)snxXWn`ft(hlV$su5ytrsqTRb=Zx*I* z$4(gE+r5mRIC;X6M@$+wesXW`IN#CvJAT}_$&+o{q$7`<&^dnokk6hlb4CZtut8%> zZd%4(Yg!Jsac@gwk~fE#E`Dz|Z|il#KJue&t#h}0ciD+o-MhWH@rq^p4;waP*lTZ3 zJaKE!iIc18+j~AUW9xfod|*boEpJWVUaiPp8&Mh_^O0#={`70-F8koJ)3@$@^7Hn0 zx07w{q+4vQ=cJRj?sMWv)~kNBF&{CpXHtI5p<8~i>>JyQO}E(J=56(`)3>%xvLj}k zymiQl_8S{G^YhEUv3>82f4zOgrt-BBt;xf_yqt4Qu1?zezLV^j-BhWY;v$L2kVhH^aXM;vFXhWVdIr)XWmj*qf_`X|{@HPHU$g>0F1fp2Loq3LOy z!nU5)e%1_N{_kO9)jF2OFn>R!dd9z3P519rziAsA$f|Ntexx;xQ&?Y?b4|_a8~(R# ze=UMxOFqM!;r`dUJzuu9{6sTfvR?c2T+J~j{iXdqmhK$(p1jajSJ-E_)hDma@>4nZ zx9v0JT>F#HWbYRH?6!R6_$)tz-VkNpeR(~s13!Lv*dF=Fd|LDOk26)#W2_E=l7)GG zyBU_))4?d|4jI56=?2p1XXF~)EH1L&@Ro;b>n1V=mPc$g&t}oEyUKo?&$@MBca}}@ z1I~EVnrAz!G_TsH%r3la(4mj}{@FBfuGxbQV3OO9(ePZ$Y<17AtneGw8Fnix3?Dma z;0GBnX{l_jk*&!l9CRzIOYM_qb2*rwWzWR@Ze^7>pJ%gap0`h#t;ug?Wvh4A=C`ua zxsA0&x=JpM3n&KMu&iqvKj{lseYkz{?Bg{0N{{ceKkVi)=h>Mw+C9uxec?8_^4;y8 zn|o~BxM9E5J8g2#sv10Ox0CQ>dk$s@2A*uX&|b4YoAUq2@^bgQys)p_z3;;Z zm6uNaa5=xX{NU8FR+VQ_JE}a-#`&(W_4tmhW~Vng$Fa^5`#xvu-RIlTbw1`xobUI$zGJJ|JUbsufmmYoOSYl= zeAn3dxKHla+^%%KKeBbcGtNFNe{V1Pwm6CPS>EG zD|Xz(=vW)4#<-1jcK6!FGPYvjep&v)KHc|meb;j_cQoC{9=2}3o0hZeOV6aoUV3 z2XB@iZexclEbJX|W?ILOti>I4zn#_&I$Zl1YaEBwNsC;fovHQ=wRlZzU!;}+OaBtJ zm#Mu*?U&Tvr1mRn?^OGzYVT9~u-d;<`vR@a)tA)1OlyM-qnzK}uKxc}A4ie>!)R?k zWH0&$sU4&3lhlU-#Qxc87pPsW_99w4&qlQ;^R~V}Z)-oJ?Z2(|ch%mg_GY#JMeQG}{kq!w)qYFu zx7BV@`;^)rsQpK^I7Zy3zXxl7s=mJm>pR|OE&MKy+e7Vp)$Xs>BCft4r<>!5N6_MR z)1Impx10VvwXmP)pRX1_oc?8MuTbmwp>4+-Xa66nMK6O_#rv|Z?~nKSn)-Xunhaw; z^8N1lc4XhGvA+=CI%2}4cZzS_+!LgpO+DVeH*>_qYI1(ehqip_r@L=@ZvB_Gw>JL3eqp!8)3^56FSJgyV>TF? zRlR@t^>)Pdw*URZ|F27r-@4nP?< zdHgl|=G*g6zPRsKjx$uN+;huBN456c+qNG4mE(rmQLWygGs^AxVVizBw6|y6DXV{N z)K`vkRI6Nl;w`*0d;W~7b@n$0JbuJC4E_V~YUuDJ`&;JC-?O92ya(-57L5z&6~^?n zBi_#m9n&hShR^Iv*y5O$Wk*cq8$FF#e50quNEW7L`~HP}RqI3S%X_fE%AShJQ&ttW zru7(djn`Q}H$T*x#sRGF3e&>97pBFpu;e{ov9&HtYXKVvFs*ah`*Sg^BRJSGt?$}e z7pC=gryH2oo^}@78<^IIJKeyvj<&8ryLPJC->|>uCYrX|q|mChyF|IVnR4X- zgYM^&=KdW~E*`g`T+HgUAPNmrqVadW6UsH&4>;pNYaZ{c(!6LNL%BYia2e}oo9$!3 z5>1@z=b~Jk)`2Zn7<+aR1HXYnNDI=b3)ot0T?4i_m|qgG#cJpJX4{%Cyf)6fBVskJ zvyIdG!g15=W5<~d(OJ5-4U27~Y(+CNHu-&~j;+LqW}8d#T~ii!0f79chMtc6pF*C> z;l1U&N6Q0x%Qb!F1*ZTL4WC+G(hCSRuVkmQ#AC z%sp#DLX#Xh3Jhr?K++^=Xj2l^@Ld6k2C2ILV94mgBfFWB3C`IiZZsG#+Qs-91hDZw z{WJ+E`u{bi#LSL`89aUXzLz(zXk1x+p}eX6zkmHwINog*%5MM{Mh@38~9*5_qHDTp7WssP(SebbVB`*%m10gj=?@A7-`yBFGee8*NTA1}*#SvF0g+0`PS{x zvFSM5r|U2o^( zKDj=75gS~>)v30hGuGPT#J{gT@MRq&+WviHIL-k{cQZx9aQ&)ozv?;iZ2SM6xE|JiV* zdv#s+sr|0nzfk+6+Nah2gWCVD_7%0;)Z(~u-zCq-T0B?UebnN*(mzZszAOD&t&iV- z1?P$1apa&2=NUWkqaD~re}56qbHw;bQ{E}g(~DvcO0Zi4ZYZ=Y{WqpJDZ zh(>nUiY*6xujYa88-MG4r%yj^`o7!Bo{3w=4Z7-{ z*WR8ob;gM^dW=(L{Hvj3zj4mj&fZ?_-u?S|&7S?X41UfB%{alf4t~~oJ%4`B$?v!r_i8W3XWsL>w#x`tjxram+%}eu>I||PtVErC!dLJFq7_S zbU*e9`^%ko2v?^+Y^&StGvrPClh0!BnSQ=qgGK{5(L2ku{8vDu8-8hOlwDiL^neY8 zlIPBCy_fB=ASw)^q2cl5+1WH4xic|pA3ydCngf0H6EqX-Q)ZV`x3Y3vr_*yQEAu;@ zVYjk!seSV76Pz8m+g52-`s!IUSJ|h`)@``;AzOJkI`*x!bbfy}&1tqj&*sp?wGKd1 z!|Z^r`|4cl*#p;lard=e+_~1p_MI}jc-XD1bgtE(MCSs}wvE1U>U->yXTQds@cRwR zfG`FYtFQv?s%ScQvp(;-n@jS9s_hDLigDTbp@DHqe};hdz28g!v-Y{|8~m!y z(L3{hoagfk(4ctKq6vvtwF?$icQ)j^mI3Rx9}K0G02)N54yKo~On)U9OC7)A=W&*p zzQ+yky}aj&)|JgKG_IRCtZ0dS%dH>l?4o+fOeNe5l-5V)YMfL-+YA)BL6(11pL%kSmkq{ z+Bj~Bo$SImNc%X>!=zo9)YEp{#2t>K`+fU#{Y*B@E_PDaaa3ZL=Za=i~hRX7~B#*h8Cc+hXay_Si<- zz5U(5q`1d{C7w!WOPOYG^m)SrOF8JtaX*aAfrVVx?xpmRF|egHB#80C^XM#tucmZ! zGWKzPp5VX&X0_iy*UxkC4t>T3&kWhKBW4wvx&vFyo99{n^OjFon#KCk3ocsGP1oos z1+H?4T?*#p5SvG%)kl`mpQQd&^?9!xKU4h`>aSCOgZh`Ne~tRrtADflcc>38%lUBZ z_`UC`|AhMBBJ5{;vj2zbzpDOE)c=|KO?x&RKb+Q%hwnrmehvMD)$dauo)i1eQU7A~ z;mvS7`9ti#Uj5tDzf*k^0p?V`b3Bme3cfW_?NMrvRXaoNnQGm=wd0Y=e2?c%yH@Sz z)Ly0bchugX78%I#Ja5`RR_i{r^?A;0{~KD9kIpl*)^RAC*#D^g|4eKB*VTVZeOz?D zKa|$?@2B>I+J30|cDSFvQaem7^M&8-RXbYkVQR;!ovhZMmmNP-{aI?!ft)A!VGGq? zs&!^{1-^a^Sd6 zsD(#EAIFmxdJwHAw^{4SGSZt#@k`>0 z<0ejir?}$XJK&1sM;flUyWxsG*UwnIrJ8Zp_MT4~7B=y$?bYFZ!}hTp#>UAbt0Stq z+8?ZN$hWs=n?5%G>iK^)Kkwv7_MNch!Pm0g-@C=WIhSvpzV*GQ#P{mz^sPfq_^y5D zQ}b_{|AYBGlSWL;`w!>X4R-9@)3@$(${6w_PyPr;o;b4N*gu>0L56N~;Qja&9;mj6@F9;3FE zWv}HzX4A^o-ky43wP?n$ZFzO<_Uf?z{cDrHHtwgz*pXF!H2wG3QH5npj;@Z|URlm$ zHLV&qx|%tEj}H__zXp1@`|1-n@s92N*xSpmw!e9={dv|tJ1&OXIgc>!In{QRKK3GK z(g#jql}K%elS(6J@^U+S`5As9awg~7F$UqC#kQW-d#xFO@Os!-wN9nUdsg@%)nD_4 zszP5Hpa;CyU|f~TnLL5@UGd8xxr$#l+E!Wep8vwe6aUiId+pP61shMo@(!o>`#YZ_A+}1awak7yK*K^v#t-uPAcT5>Du5ozF6D-ewi-2JKaa= z+7wZDt95OCmyEJ^5gh#G^Cr2h&iocQ$TQs$9DI^%&t}oEduK#&f*)`O%_RF6bF8|R z6$HL@dTwQ9YNs>oR#p({d3MIr)@c=#jz zfLQ~lMYZ_C-qrRoT#miWgoY^)L+n`P&0ESM4Z^$3EKQP?&IN54K01NBi#CH2wA|49leDN^E_dHNJ2^2im8RU6f55eJiURVu+&s^@St&ksdq3b0u%3 z$3eT1NxSFL6YV9nm>mT;gtai8@_escl-f!!L}ovq+-o zjGecTI<^usl5OjJB)w#7zq(*0mF_GxbK>}S3{`q+W}l~K_QH4Dr}xw&MwgfNPS}5R zx!Q9y4>+Ja)p9DQ&K-Ni1a=%a%9wIv*=qTky%V%`{|V*pz2iQ3V7aiD)XaVRIJj>D zoBNK5gUch9PCLt>P0}*&kF?BP5$U>#@%n_KEM68jceKi1i`(Ez70 z9hKro#=d#h>;B#826m0J^EFMfB8t;ct4HM`3$s+Sclv2UgIyU(|7&yJ77`LGM( zd{@|de8*O^$LxF~SkV&uK4<;z^IhI`KITiD@AqvzzQZY=we#VF#S*JuvJKtmyWY;n zeR6%n?Gxw2Z{<7V?87qKe6_pcB-Uq@5B_ZTac|klF0^g2#Bun$_6kRY6v2cAXe_@~Q`?$I5x!7vD4||>bZd#tQFFlib1HZ*@b`6hgg*}XS z!l%30#_5N5alWoizS@0H?*?{>aX7HVQ|WB^_u$jPUmF;&Jn@0$o$%@K=XoZ`i~(#i ziRHnBy0rP1=hGc-zX9IFSfiby_5`(VRoiyt3j5DhyGShqmhG3Qy-e*jYQLoRCbeHt zd#BnzRePV>ht)c6X6Jo@zRlH_)V@q>WAs&8+rM4?|DnF)JGOtAJva7)S91J8YR70h zt}EN!m9{qWGabLN?=8@N7!jOjwffGavA(lt?0c7M|Fzn0moW&ZK?ZUCj0M_WwWHM@ zrgp5_W7Ycex8wc!TRThJ@klt&r_?T0d%oJWYW;oKasEE6{k*n+QSEQ5y+!TqYX4a6 zpQ!csV&8v2{m0Zkp>{`{)8CIB|BCkiSna>4EqG40A6%LCJ!&I=)A3H*4!+EO9Dmx0 zYL8OeuNEYL{r>)}{WbMJrFMy0cu5=wR6zS1YOhjzjask+_TQ@ZPt<-*EnousA6NUg zYX4p>=)(WY-nYP4QC$D;-n~g~9zYb7h=>;niU>&v0aA?+LbyBx!b?D-+f&t)<#uZK+yOur@wgW9_g0zu&WG_RhTo2nB8F z-}&6R-*aZpoSB{7o!vR}SjK;-_;*D%o(ylL$bBWrr?Ot~>@e2{SP5r~#rTgD+Yr%~ zvRz=f{g#}tPPEs-?}Jvv2QgkN{O3x-K4|XDdM`GnF>*!={D&7~b!cx`)&_5Vc+jpe z)_q2>V_BQ>id}uq3pae3o7V7U+mZp8-*!e(EYdTz!A%YKa=OLppWM{?{W`~_OVxBo z$Cxg);mZ@5t}oNgiu4Tka!b0`$K{#Fpj}MU=REF?Mp>ruq*_3L0ray(+d}N**>~#tm@#C9XGy< zuP3GH4{JVqFzhs{=rtT9mX^}=hoz+x7~z}#c-LcTsWd*9Qgq}Z3BiYU5aFBtu(Xs9 zkNDEkwp8Pr{*Vn#e^^ZVn4}ALmUO=9k0x=mwDfp}PjSltDQv1>2IPo9YWPX{XKTO~ z7sohApqu=I_052T*&IaSBQq&86sz=8pCn{Jc8}Gf?@Ih=g3%SX)ge$?A7mES#m7zH*cMr6at0a3Xge*gfjS$GjB1`7sWX^J39-0WJ z!l&YuW4_a|mUJmRq6kyr?VYVn${c7;&G_=mcCgl!=5{P@(mgfdt#F`ZhE#L&&$s1*0Ym0Eib>+ zk|^;CrsL+PN?n4X?SPL+W1}cC0*Xe?f6n;t z(~P2=-SYAoMpq7R(vYtN!vRm@3|Wc*bngN;4Da6T1M;DT*YCi7!Uv^ELt%bLZVd@_ zCT=o#Lo@1f9MB6^fFaLCoSp9zc!+L9B=coG@HmJU!kaW8ouMdHl!Q7H$CoHu-`@5^ zTMjvshAPg7K0d#VGjYohVC&o4erPvC&ZMD^OQ3Ix6=2AllJxCuKeW44UjdcDy_wpy zz3oB7QMZx129?FSGLCWdkHX^=)R^!_$n`V~(3FpFxQ1qQHypgtP2OBr&w{q=rMdf| zO+=z!Q;|B87ZI0I;6829JbPO%uG7vzs>HHe!3oE7DC})V*vf-i@dLjOds`c1l^v9U zoq)J&j=ild#98NTGxo5zC9Pjob6X$gfXncJ=Bst3JkBK(6ZsZT9H2N-alGP0#Tkkh zC|;^~h2l!ZTNLk9{DI;I#YYq$SKO-jlH#uw8x%hy;@W#9?7&jbLyA)G;Gb0f z8O0YAUsHTtkv(3f->vwu;$Ibw9gY1y${9NvXZ?^rPO+mR`^XG8^V#IQfG^eXVTvOa z#U6_IbChSNn(5~#^4UrLM#Z&?w=2s1u@C!}TxUqn``5N_<@f31PfOGPV14Xf>|4Eh z6c_oT``_okJjuS*)cV*B%P{-P@z-xw>I&IMKMy5@EUJ9;^Ke4Q7KEfGgzULa7Hca{ zSybQuksl@Lk5>LDNq;3m67{b`NTU8ouwHgV{h`sg19?Oejv-q0qt7!ELMjoGl@PKH zAuSU^{PnZhx_)-!wzS>pZBuu@kjnM5z3U%MI{M@lwEeJxw)f{DT|w)g0e=N;d!$V~ z5B?h3(G45$1AQQpIhH|uDplL^+*E&>;ygjd42U>)s)A{mwzARNBI=lY>YDV3mMed_~A z`5x(}*3mA8q&pmc*mOkx!A712=Z>hue-z$dM_chMNVa$WI$BvN`!ZPH`Zl@_WFve= zJ^tJ=YzPmZb+lr3Pg+NNG>^j>NjRT%dSrD*} z%P;G=cv%;QWPYDtRxGL|!ABU@(Wcgt@XIPS;TLcm0>x1^pGuhZ#v@_=x{j74P0c73 z!9N&W7Y7OlNRx=ycbJz`tZdBmv zU>_)jTw8=thCTv+2E3KriQ)x`WADZpau5P+ecZ6Ai|XUMzR}0m2a|?6Dqw6`LqeU2 zn*rX?jCvb#w^;#(oQ60%-!4ZsZw>7d^ev)Ptj_4058l=nK?fuoVXT)-cyk=rfi`JC zI(I-H<%~0N*C4>wmt*Ne_chSR^u(6UlZn^L%X18e03Iz!zLuV@iZ6uZ!}$cFA+dm+@uF4^w`u z@(Y!}O!*bcuU7sxF<0>v#eBuyio6~vFZBc*sXU*7 z3^%sK$;wYxoTDi92D!z`FH>Bp_#MSHifa`)4T1XaR{Wvje=Gi2k;Vziy{yRVn*6U7 z|5uUMH^bjmY*dtbMYzX$19HX>v8CdF+8SDUpT~yK{%RxZ8w`81Jr))hH`n$!fiD;6 zSr-ZTbL;qhQGX5X1@&pM@%Y*StYL)}yLz4sKM;Oudc)EoUc=G>DGf^p;)@IAN5@{O z#G_I9k2<$BtJdZZXu zv8$*nJmiZeXCODqQ zwRJr6?S{*d43pqGGAxwBNu!uxHyB)q#zD_~yI~fX5Qi;2^X&%S^O#`ArW+IN+5qAc z?AR`0f*q%-Libn^3EwY);iDv7cmV=a_+As%Z#NuEx{0;5H$gD;itDn?@IqiBb831p zgaM!n4J}__$8qx^;y+S|ZUznW@nyIfY=h#3_QPCCI!8pT!2wUxv$D zK63`XYdVqxMWx_cu+=ykp3beh1wk$U0+LgkTD}j0LcUZx5MAKi$&VSSc_3O*%E_jl z4)AO(-6^7jgFJpLf|^{Qdl2*XGMY}92 z?tSva^DbBroj+&Jta(v945QO#Po6e)>a?j7i}LzJ3k!M_URX47@{9{6Le;Dplk?A; zGKHT!=zhVR3#N6SRyBD>KIHOxYEFKBiSaWucYhjt@Tiq)o_udXH}T-oiXDGy1Lkj^30g z7W|e^ytXBbEZt2H*e0|c_&BZVwTIkM`1yqXct&Br&Z0H zc5?I_B*{1TM)#sgeY#J^CrGDMN9RskIAb0@avbgPt)iX7-_)4Nngp8E)eq<+k;5++*B!Zif)NjC;&Ij3Uf9wgF{_?t84}1ReGU zS-wxP?ozd){P%2AYo<+ioQ^7oCPiGb9Cgs01RsIlpIkS{BLJwm+iC=MK7F@>F8EhbtY~$cw65_z6K$T`ZC~+zU81z8j#L=(6@qw zIuo}HysfVe`sxuzeOd5E-_4*+8jwy6E{Hp<07Kq{I9uQ9HvaKZUrTtS?=H|xQvgrb z0+m3!jBzCCA5=7QKY;S4?5vMM4yURHAns^XMo+^4jp`RIn$g1`XJ4xOY<*oR58GHD#lDII6^AK~Qe=BT`6-ILV98&k zc$p&KR~i0Y#oH9uE8eI0km6>=I>px&`I=8XV!J~dAoB}>tr?CB{1}bzq&&x-C|{_2 zALaWiKT?rXd?+U?aG+%XDNPLak}F9it`lZ{2-m2AK(=lzEbf! zigzlqePj9VSA0-W&J)77DF343tBT1s+8rAHjv{+;)cdjG{%nZJ^A+X%B0cBjQctO3 zxuQ(NLU@Jpa(=$39$>$NxtAyt$N`Db@U6k*p zSfE&>Sgcs0SgKgAXwLIk8B^di1it zGrJcXXYb-(y_;*}tVBL=2{umHH?v^p^qhttE=!4>32R;^*83KnSpG@d$axP}?8+G& z`=o7n>%$8leiUnoBZG3Y`h{Y<{BnLD`t}DlvW{YA2 zu-eyOSsdxSKmb=c5l(qhCIjs&|Ox>&KE|J$0Itj9=L0Q4f;R@dzV5LnWJF zSzQIo>dW#qT(zv8aaB&;fD=Nc$2?Hhu`!frSq({;ZCMSS&=~S9tD(WmZfyTRnOIiw zRa|H5X?Ov^4=!mPb2ct2+sQiSu(7S)g;;wXbJ(n7W*ckPF>{`AxPq-0)-lso8CuSe zq;<^SW{SP6V;1|W8=*yYk9Eu(0Z-wu#DT11egyI~xz1*x_?$5&R|Xi9D`_Wf09B`k z-R%_ZP0>Y;mlh^#?6E@-3UiSB<25Mbzd^Y}-$GavK4T{S+%w+8e}7>aJB-SCBm4H) z5fuIod{#gFxfP6k7GCVJvi_Mz2(E_{U;hjitD|K(^eV(=@g3G3%Yyx$EMEnE_I8}v z7Hpl_GSInG(-71$3u5!|X4=vL!3>-htP8dqY}?%Paw$bC`8AMoS~2nj5NjDZRU*F6 z2yp*V7ThLGw-FqqS;EZ|4Vu*yxQPgZL6pGgJx#ZxAqwkjB_ermfFxWG4@2x_fi02> zr%L>2g3%SXzES}FG-gI!>{Egy%!l`_ucYJ#bS&#D6Ncff)!mPZo{7}M%ye}($+_^b z1rw;KDP!!3l6WlP0(jdPdn))5@Yu}|TOR)7%0>7-3t0BQdULroR%GiM>+}zD(?2+| zv~y{0Lh#_+!6(XU?BZNakEG(LdMJE4-byu!>^OML#U+rvWe+&LycGH0o7zz~E{x8uq*=!g<|04mk@W3cp`OeqCBr=sbL!yQ+}89AIn$ zsg93&Rns{z@nNV$ljV2sczk|$k)F`8OZTolyF)zRt196r#fPChUu?+f$wHZV-M#57 zK_G(?oPInM?N~H4sR#p25i;|LIlO~OsFt)5m@2_iL)5B@NBMbMEJrA9&vvGXsIYi$IH>dBLu@0?V)4(6h zSjT3g1UmUfNmmYU1v~G7=_f6wL6Xor6@)^ViNE9-=9dh%F@JXQS(;|V58)?+ICp&08JKs~rtM=Fk2oTxZM@dCw5 z6|YcSsd$T`*wCTx2g+|yd_?ha#jT1jDe_umIsUBJ4)sC4Sg{`wZ5ORgM6MIz7|3vq zAFn(O3`{p&`I*YoG)DR5iZZqVx$i2!UU8%1R>h}@kb716Un>8m^6wH+9?tpan91iF z9zxs1{IZCM&n6=Ncnv>U!@FyEv4-RDMV|L9)3I%n^omi%T*Xrq^A-Cm4pbbbDCZaY zx0< zHz;mY+^o1o@d?E`#itdYSA1EqUhy@>*A;)OxI^(B#rG6HP;5~ARIyRU z*@|rx_cjKW|E)g$ke2@McaM>tg~iPs16$4)KD@pb33PE1_ZUfwwTw9p?=M^Zx!Gf+ zM)nvfsJsP@slV%pA5w!5v)hFqvJoL(f=qmmk%r1t%+5dkIDdzc?x@dnG~= zwXZ`+qV}-0!^ol0xC42ZeNFshidKE^^OS^Rsziv{>BN^=hmf=c8Gnb7NU+05>hAQT z({`^6bBB@Q`gP?y1~|JTp*EkpnOG~4X4h)3SouKgFPwRD{iIEdx8wYn4)rI++9t*1 z#bQV^WzpjH6CSoxR9E&ou6&@s%Sbr3btk_1bqzfSNzmlMg4`J?GZJU?qlA8Ug2Oyv&^&U`QHC4G?h}Sv2$vxm)@#B$@cxJoDRzA!L!gR1hk}j~ zCDsNc_NE?Tds7d41CoXQ1|(NV;&Ii`yg@P=7teDP^ZdXMg;?PH3}wd=UY3}DPcWq( zT^rXh+Aei`&8Je^uFA#g_q%rSdq!zSwpcB#&zTNQJO^uoH}v9@G(Qi`2Ul}Oq;);MnlTS zjGQ!V#^i}(<}8>yW!gkc*>(~vsx{>p8WQ_!d~&!bPmqddmk{jl(;@#o3n$HwYnHD_ z$zQzt=?jY{mbqrk+$m-}4`}*31DA@jpYAkmI}==Up&uYE)DovU&SbCM`q! z(^tV9`hCyGHy6WUF&mz@zHJ+h@;X(=TlEm{Q6e^C|GXdOAHYH#{j2807a(u8qU?{+ z@m<(%R{21s>jn?ALEL3KP3}=L6cW^D9A~2BTLFfQLBQ5m3PWHQM7BjZ%ffsk@Z;c3 z8j#KyG=6JHs55cZ;0?{FosipZ1sHNF;_Q5@VLarwvY0Q!O}?}@m^2`rpW^K;NqU zjYMD$_ti%1@qJVFi&dG zj&F^=b=*-;=Qt~R3&Hc8uUuUDS;mhAbV{126XSovp_XK#-BUsryI^1GD(SoyyzA4VNez9kX) z(WXc~syy3C@`cKus(iWfYzG+6E)LUQt^94ubMhzSIUdOPCzO9#`PYt2Fy2Kykk2H7Z>M;?hM%lF#C_YAVwNJWbK1P3in)r(wsH2wD97uOSgtr&u|iSm z4e`^IpP^Wz$m^Bqjg5S%@=|{YU#0x_6mM0$OYvUC2NjLYe2emI)2aU{MX`v0->&>` z6#t<3N5u~m8x)gm=dw>V^rW*sfwVjjrJjK&D&JKx*_Pf{!^;%UP&DfeCMYjsFwjR^ z3-zC;c!AT(zBIK z*l)Q<51rrdTR8V;3+-LpyQsOg&^37e!6n;5D{k1Banntatksz}wz$b@xc~B3-Vd#$ zWpqx1Gqj??$y^=#-j1jKx?^56c5;mNHsfDv8~U#I-A%i9EPeC+P^T+)Ww?>8ZmdV; zqUwrz>; zU&XFJEPkair|y-;_I1A2RBH7iTfNvLm5uw*n%##bUGzv(T3>7%xhY*s842`#QkmU* z%SUdcLp_haxO!j5zx31b550sMJ##1jUzPuL^1oo`n~g;~-fZl)x?)$$>^B<=)}`-u zvaTq9rLkMxn~hyo9|N1J)9~Cf=5aQxpv)yrY8iXg^kz*Lqo%PEBi%U(=TBmsE~O2d zmZ9EHU~b80@#VJ5ccq4;b{e~FjBE|XcodyuXJ9v&R~jSBoQBoQ9{b2?)lH7egRwVB>2$?00=PWpNr1915jy{Y5C0HVmA16lkwvBqPEpY__~f3^w~+^8w?@ z8}dc+tcavY(;7)@L_~b+>)nz*O@=Vt$O!6>gddf_FyG_A-GacB<4IS$0|6ACI?K&OTuk^h(QpC;|}!>-F9k8gWekr8^t<&e8sk-=ARYz3`v@NULK;N4Mt zV0VYlsK%c=`q%g$Pqv7$vJ3X(VEq*tXHxhL_^h7zbH`DTQ)XLmhn%xnj+T7xvu&kw zFI7$7eECpX>+-3h0L}W9M-+<+_*{$`}fNFBN zMXr;X**DWe3+&l@=Y%ypf-2Q;*#{@J738@gPFfypf7~6X`5WeldHujP%!wP{QA73$ z3l~Lb=B7FF#B-M95_xhxXUPtbaVItIj3i7)e8{#g;mxb8tvVLg)aG zByO!aJcP&d9Bqo+9t0%eOkX;FgE5qMLJmCTSf~>CGWZz$2zcXoW2}K+3%?HDINlfR z$$SX^R}%>2ZNZ)i@A??Lal9*bz;h-_1fGY|4*q=j8u&}#7sKBLzX84xK7`ZI5v-;QT_qptAsqYonVQIU92QX6`xH?qWQ8!bQ2YxQxTKHfPc-ZReg7c7AE+R&XS z$9qdk{s`t4N&5bh5^o{(uU9sT`Sy#?i=3AzF;paEX8w|>mq8&fU5?GDnJ{&MmzC$u zk9t`{z4>{+w$e}V7W(N~3-2TS!o2bYUXORYiW0nJyDqERJ^>s)=v{hAZOI9A=4+>P(q6qh^w%ksTQw8AFkp z^V3&jGo2`t>}|Zmu6iu<2u5-ehEJ^V85!X@EQUp7uADtCLOXzQY{AM}<}OdaDspw& zHK{97R)(+jt_xl7_HSAF&+p%ESLR_qh5p}aY-E=81TxRlZaA4R4+U-o9;wUlgrkj} zGV~GnGvKWUp|cLU-n9Y@IS6vLzR1!3yg=&X8o8z#DycfHrABI&VQ=DITB3nYddKVC&-?b%=^S zdu-%>gfUG4JlzQ>Jm1BPBT2tm(a3Gb>)wS%NaHBSZXHg2jfonB!n3ntoKd|E0fuJW zV#pO6As~;J?iG0ZIO=d5rk-&r2K6F6KPFJO8T$D4W}L~3XjPZP??lhp1^~d_~U1DjPGd6+h-g#2%akmvkT%14NhZ$pHHoG$WJFi{$>ro zO~dch@H!&&JWGV0*NM>c0TFsQf17$Zf17$vz`3S;7b4_~h>+*=<3PrA_-x}CNKeI6 z75gj36vrq|P~@|O>CRWYNbxeoRf^wLyiIYv;(dw_DQ;G*Q+!$R9YvmB=4ZwbT9C){ z@CYIrso?|dSj1F~KNyljsG{w|Hb zSL1)8{8r^(Q~q`3QGC(IR*QPG6nWp0XPZluUOce7@;wxJ|1h4tc4E2WV8!u@Y!eti zS#i4JY(+k&7{5qyvEr4AeD*T_21Pk<;J>eYt>S+vKA`xxBJWS8e@5{I#WxgbwPU=T zPvCpX|5@=9#lI>3Los>mh^9X3;i`OMC&iN#^ArmePg9ih4*8h!oJ7m?;}p+UtWun& zc!A?hvi-vboWP3_|MT(`0$=AU!4WFPm zQL$2Ss$z}ee8uGJVVQ<6S6rdEN^!N~8pXAWw=1qwyhrgq#SMyE6rWHu=UwWfRs4R) z$KaPgw&nltZ!D}&@1kN~a{u2R<#)v4_81Gp{#Y4TZp1L)>Xld-kau}~j3Z&Qn;idg zK569?U?k@H{)=R^#~&r&7);_Q!TC*&O(C^=;WCbFT`yy0drLidZ>d8MFXIT--ctJ` zSOravU?FeslVy=$yy|)#ui9G~mVUZa#;cadc*d{g|3~uw-JR~8>APP{Pu-0t)7tC? zFVktbPU>Wwj!rF;(V5JTzU;%ADaH6nnyvzHx-1IDXOc&ySUVh%Ik_=(?BseUe;~$V zuJ3Pj`XgRuw9AagWdCI7-p-Q;J*Vwm14<_&Mx~E%)UT;AKa?k=gaq3H6f4K`5n^Oek#-BeF?X$bBD9xdcr3LWYdI0+ILtYA=Gnb|Dl= z`^XP`#|LR_-H43GN5WSkSqcU*9B+!t<|d^b>1uZx>E4LMk_9$b31dR;Iz+g`@P}ur zf3S`l`91@O^O?{MK2n80cf_ypKaMQha<_tS6se&6B?~e}Brk7y6dui3j;W<{*k{~J z;Ko6FCe;k zKz1Qzp9o}y{U4Ei7ZEg;(*W-4y_B+l4rGOG5k^=Ryvp248SV(&Ldq#DLiRhN6dyzi z+k;Dc9Z@>?1sR!{DAbWIhljE<@udY6Ilf|p2L#81GwU@nd^(rNO90`#Oaj*)6b69^ z93Q}N%vd5tlg5U8$x(#fl4u-ZK0Lmy8mcAnu+M~RNqp=xskJ0>c{MoW2%KmlUt=Y~ ziwaD*mV{i!)J38g9w|xzYlS?E@HD*VTzpwAU+Gy;tb~Y{cNB68oL}D2@grLz3H&1) zZNzv>`I1rxJfz@*xBjtR6p>@A_hYhZNi@P^tp|aJBq_|XAv}I$7iC#T22DIN9ukBI z9FM|55_oi|iN(Q@2@^lIk;qG2yu@d-;H+JYO%eVIFT-3Us2<@2zILTz{SJq@NUxEo za|nK}m%2f&u5(U2Pu>jTm{AlSv4oT0Gn~JKPyS2jMyq#(@_@7AhNS=w`2zd_S5Ae36oFp70 z^vlY~G|w=ZAwdd72v7TM{;P{>3;Zerb&{8Jb$zTk7B9fOpG52T9r^ zEp96~wj#bWj}CGxAif%&T`eZ(0AtiopwjV24Fg_=%mEA>{%gkx_ZYTJva*;xvVx&P z9Jn=zh-VBQ#!?yH|6u7*>pX9E9tI9eF2J+iOU;x2^Z0)b|ISN&oUs4kvnke*e`oQ} z8-0a9UNp6Ygr&e6H9?}oci+*DJcOu^HX);LJZO^! zr1LT&9wDL5#LWP2Xhtnfahy^rQD@@#@V4`PJ_j8W$T44rn|v36HfcaQTM-#0q0Yqd z4anBF=s4e&MSU=L2Kuf8ZPI{revd?~d*e*pH3+cvt$@B#gi#;Ntbx8eK$|omomS`_ z)LQ|DOdi8~9{PBmsE=kGbG-M1W*Sqb-=pxGj1r9_%Xc?hZZ!%;+o*AjqyH&9uDzNd z9Phk64FjYM-8OhblP`i?F$s0%6utu9u9tcoM>fKE9BtsuaU22KT=O6uu3P#Y33Vnf zqIFq1MXj4RhW9iw`(_M}H6C~WPGfj%yP6oov$o_4hV2f13~xsA7#<(iXz$=T=G29V zc8zT($DG*x;Fwbx5!c%YBC2vS5%RQQQJ#hs%Cql5`DH}NuOdQz9TD>P5Fvjb5%ODz zkbja0`4@?h=k-tdw}_CZfraw_AVNNjn}PD#M98x*%kT*rZpQYOk%yk;MCf5hf_m;H zLVg1gdbSXuhaCsXvt6P*I~iIA7EK*(p~+)=&_5%TPqP`;1|`C=mE%ZZTZ zbK+pe>iRQ1+ONTi!xhg~tWxB8q1-%0J{!nirO5L_{=15|DXv%K`C+`+Ac32euTy+k z@sElh5K}N_srV@ojo;rip683ajO9UJYvpr@;7?Fq?2eFQx02zd8lEtAhkV8}99XGx z=c^n$)J!L1Hqc|%`_Pa{`BfT!v&z#dN%SYpXn}OZ4&CK)qRtd~T4>QIrld_-@JuxC-(8q~oT6MW;H#9MrZ`KnMv>1Ardy(Twc@pka{VCw7Ul0$yi4%`MY)b3$NQc7 zo=|*7@dd?t#n%-7SMm3X?68n`ZE-dP~<8Kh99R$J2CkJ#UjPzvBSX{ zK1}gU#j_MAD^6FOt$3j#jql8d#%bbJie`-YCgtUNM0~CCcPsu-@xK*+r1+SkT$f1q ztn&Y(_)EpN6yH_+lj28;jf#I)q#c3fOjl(4MxN~(F{;S-WAdjc<}0$jW4O%R1`beu zkRmPij6YkkN^zRv0>z6JFIT)uah2j~#ak4=ulRuCLyA9E{E6bv6*=dE<#HR z|6a>*IwGP4BZ|rG7#@WZA63j%H21T_<7MBpclkZccaWMnHr%KAd&aF`rvfIlB7tDf zxQfKF;h{PV1yy&TeviH}r7mlQeH$4O4H~=jig#CevdO z1o>~O;Rx~G^7luGi<=xF_VfRwCLD|rU%lTk;!9!fnHvJh$=u_MHz#lXdms9;4fGcKlp8 zn!NwgJ}#rlj|D3WlSh;1OHJQ`G3DV2W6I~@8g@70?@jnFazV%cFs8g69LAJsy1_cb z`DpdIMh% zL%yA3yt#znM&#KU39km1l8HZTeb*O>Q}FuiV0?KzY0k-Ma!h$DBHT0Z=dU0lx{>=B zIE;tN_n^pR1`hu<{`r~{p|m@KZ!&z_^v9G(QuuVR8TlaGQHWN^+-~jB`NvELUbZnS5nh2+v1#hRD`X_S!&J*gHga10o)U-yX;=pzO~A zSz%uj*$)u$S9lpy7QL5HwlRx4Xq@L%wDs>i|q3?7m^2|I*5hp-dgmV}7kgT~l$7U)*+NJZco zz_GBpR|z@6R066LYQ*)%Kbu@@bT|t3B={o}2b4>5OHT|2l@}uZa(Gv^c>&>9!g;`b zC3_U{Pr_TdtpodC@cT;kSHvR?bBkYAV;D%c1AZs`zBI5?-BIqSAQ?|LLg3h5`i{4Z zachy`UGVI`v+o{39MuekA8W}`-cBcTfDi92D&wmL`e4xjj=dS<%&+cqoOuQw`b~^8 z?~$P(sDfw%Q-IW9il36poAkG5lzhAKEql|g6u{FR zkM7ljMhSS5^sIYZ?qw9Jsd42eAcsyHJ7(fe$9r#2!vKxydW&Xs4dm>4VfpA@hPRI+ zisQ&e7>|Q?GjkltmxbAsv7-#eu-k=?RDAtCec$PD@ z;s<>lYeR8+9@N@U+-8B}c{?%Se7%K9eE%eVL=qqLX%J3*d@pC6v+ZhPT$yhNiTiFI zf~BE*3@i89`$5Hvys^J}aoFfCxQhM99a8 zkZ0e7@>7YB=WaWcUr2^qb zWc$SQmnqU#PyRZ^n-upp*1SREH!A*E@h6HuSA16SUp>}*8rnG?AHQu%JVUWUk(PXh zPgb0vI9qXvq8Vdesr+{o*C^7EMm@EPcPl=kXvUbgD*u$?i;Ax*{z~x;#rGBer1+^~ zqvDr}9$p@qe``fE#(cc;ofNw&<|+14{FY*=V!0wmGpKjGB8M}`b598(M=*%jD{=^f z{CY)>T9AK6k;4|`UsvQv1^K@#dSRbWQ{>PETC{V3b} z!KR{3Ih7MC*H*q>ncdSpJ*(cscg9RePSu2}wN@-7SnA{!Ae44S*+a0%niWEew%ox!I$%lA^&7;aqU>A;J>Ih0_+ZO>rYX z6v;5h;V??M(&rihDGMQhg{K2Sr-u2)kmlZif0vD@Kkbm{Mry#jeJS9MOdmq%$M=aS zd^%s8-O};+Ujm=;3$kTo?}X2saX}Bq9qgwBQ|P!u0;Z?q4h@(h3`F`2(jV&GKaatphVX0WXs1tzH|=%Iis#Knzhfo`4O)8=d38e8#)E+ zatk}xlI#MH(Icv68pdD=A<5AaGnz0F-oxlpEs4p(%yVl=_+^+E3d+zPfvf;OBO#<9 zKD8$=&u5u=df0w;YPxB@nrqOngF*j@==mKxcJ!u3y`%C94Hflf=6T2DfjurB)Nbg+ zSZUYXu~^*|3hiM+KZuPBWf@j{2ST&VX-{LjgzOpYuL-jo@TNX7wWrNF{t+j&n>X)+ zQc?g-u~)Nv{8SvW9U>Q2%~~)`m%ari_`|_8E;AMEHCH*-O~}Tff6J`p-c_NirB%bIkjqjm6JDl-aIFd0eJ~0{+snxTDMY{pihF2z~gmH zT#=#yBggk6(tQ7-qugSl{6DtQbOYc`8uAK71TXvRhHZqIAYI36$EGw}9tthVX}=B?m3XwO2vfg1*W+XF717xVO= z|9<2jHokM$fJ zwB?XZsHWgr)Kp2XTb&qCbsJ5jveSSM`H)vQxx+Rixo>02PzIx|Gs^F1exKH z=08`vz@BgvHg4+veuH;QWWcW013K1c#g=p^Z;YIl7b|ZJm!vefDUqUkH}%?tuo8wu zirl_g^_>yx^P#>2A&oC)m!y0Y3A2y?oXbA`wECZYQkr&4S(mMCV{X^A_@DH8X3Xup zxI?GLQ0BM}50zm?b@=w!5pNW23Uy|f+xMZe+hgf(w2$S23-y|?EY$bz_6+;W>yMY6 zUjN+gPc${O;7$tlfjNTGzXMr^E_l%ssWiO+9;4hfVIO!qp!W z>xj?^%dTr5I<;{dzNO;97Lk9)wpFpCV~_3h`(Lceu$zzj!R5um2UxO$O+sv~ZiJVe zHw}NGUS<3brHBzUlom#MZw3BB6`T)?8O%>ol#i^?$k`H-CT&1qp12BudzdH0Wa>sX zGC?H#S4kJX-RC+%dkR%y4s#zs%4+6W?T!TP?~9e@vh%8@3eKvgb0dpDxqTlYZA=wx zHlpz9GI_UjGRU#;8UKerw~Xupvb)F*-im+TPoV$(tPoNzxl7S@5M?&Gv&4Sk*C)j& zHb&3$Fq}~tsFOCV7iS{P zE5iY7Pg4ggLrd428}*LNYhUP{ANAVhb?rQ+FuzY}{>i!d1HGIQZ*+-QxcZzyGfuha zTcLuMxyH`m4Vi#1h8*heSlf>SYxfk`9b}soe-_}LW`=!QAA(7NGF?#q_B1%`+gc!1 zT2nP;=CrBfq^ti=TO|&$$sukhF{T-R|DD6i2*JDCwn6aDHI7ZnfR;JSQ?E+7I(&_{ zBE*H72VsZ!W}g>RvusU$cM^atv*~O3?@Jm9Fmm0L=F@|Yay&oAnV!)A1X#hc$4gWF z<77L;J1zWv;L%8rSH_@US&^iV`*yEEm~kerDg+psaU6H!`>Amzj_=m`N-t4uS^*Hr zd|3}X4q^?wNdwa9fQTpwbtaCFqy&B0{(CU>?aL0qaW#kr&ge_FL*!cec(0i9CEFoJ zAfk^^0y#t82-+@R5%lr+SU$eS8GY+PGfe?J-BmaVT>oqwN%{?nMlKic{TCV`jiX$$ z9pZbC>zO1+_62w=8|Qh*8QqL$`RJa3w~wO)$AO<5M{A%tjw3*uYZ;`|2z}d0s55yH z{Wkhs@Pvq z>JRD1DnCJSlA_cf;@KTyJ{K!4S6rcZgQC(2iu&plpHmcj4#MA5 z{tt@M!@>P-ju*j_o^1p5{8_OL5$!&^KMapwb$w`t*zX*Jo_&fj`+#o$c8JX=4_tyB zqG7X_`s~94cBNvm^&r?H!k;b;(<%{8&8cq@TigLQhMApW;a;>G%-oc_3H+>ZFZZ;x z`ff4OuujbEjCli}!3J@S*dTK1Um1`Y8+MG>=w|*PXJWg%%4pAM@kZxO3?ZKeYeN|H zgqkVs$$$2GgUmUQYe$M0mgxrW7+g$zFeJOs7KDUOF2cX(Pe1V72+yP!N?Cw3UPz`N zgk+N!>EC0YY`G)uWkTuSd*QUHOyT$My-3NX?Qhn;nf8oLqwh`vuYVTwIm5?#I zDb6wf?~_nx;wFN(^KHPp>N6{CFM_K`fT#Yze-$v-;@$q;;2Kv^4 zW|{(cx*BA}z3+@8N&kSNk;}vd(Ntf1GvrXD8i2UPkn3p}pi%w2MKgLMMx3da5zpw8q=#3d5A`I*h@Yu|&D&@o6AKMpHMNRtnlL($hp z*T8b7R{Wr^W6b|ZWR)G1fHfX>%^CAQ3gWC2w&zKG?f7~#`+*NRoH~rAHGh3lSIXml z<{%r9Z47as;xNVkw7xbDOZtqwD%f{qJ3-|6B1RQ+6;DyjSCo2!9NTWn4^bShnB1qn zK*Q%Mn!dG}1F%BFS1HPQ+(#eyLzQbo#D%^`A9#At!sd*{_xx5L%(kc7e;>FF8$omn z{O6rN7XPoDXWs)ihuW*V z$4f}srG#Mg`a9tE7`^5|GbY#nTqMJ9OSK5??GNC{t$Hq**oF=$@OFXl>X%UGXn;b>&FEQCfASm z8D!FA$2Z>B_3S?I*Vpll?4#q$IZx>L@)ivo?^E=432bJ+nOy&$Fzn4XtGScwUqSym z+n-!NE$X%LC)bmTdb9GpoM3XjA9U>3G`W7CeNg}K4shgKX5Y*AMuMLFzQ(}gUEF_{ z;qBlB1&8k()??ay#u~>q=@8AUXT5wguU;!w9*&?7rjNbYoFt%m>mLBx=w|dr_+D0k zA^RcR?lX14yKn@N$$jh!$eA=Coj-!Pn}j+OR|VeCj9P&g7S{?el=x8L_RF3&+cPi3Erdu>D&)}lrzr6Ek%H>uhP=T2Q%xL zuZQ1*H)%jRk3nBk^9F82oUN}0`j|eskG&pY)K>scw;LH7{euJWsn}rwX3lV0V zk^2z>P^20Y{wCy_>SMnE0V^9P8}H)XOd_DUuATvHABVl(U|)Ug66o7*=`(o|{dZbF z^0j96vBS7dJ2j!t3KG)fL*`KQvF&RmUMqgCUq>ICbsR6lf%ma_y|GT%o+tLP{ik)( zyn43P2i(Wzb;CY2uQQ^I%L4l=KUi_N;@OH-iq(n>6_+S3SG-Q~CdFG7*-2o2n-sSY z(N}#!v5ts~_gNz3eyRAThQFo!2g*x#336X34-kF47pON&k>{g1eduD9D^VP%I7D%@ z;y6XNk<=^o0+f0I&eCwH7x0%Wzd~`9qSOcC?^6CjMX4WzC)ba32@(F1%Kbu-_btou zd&RdErJfMpp#1*&@PAghruy(x=G0u=?6vYeo4+sn-y_I0sSl6Y^l99eeRXVkY-OyZ ze)W5~&TkvDvX@n7eDr0{ZQ-&BS_%1+IlQE*(^^H^)2(jIH{=G71r4I zONHL|wpHxPX!lzAw(^_?FVem~^3j*Yzio7)Lt+DBm9Yp$&oNK_lq)xN+cdHkrtiXQ?RED(zf3$BTkmdOQhd8h> z69`L-1y~pggyjkWX!+Vr1-N6<n@(_j}kB2;GD{i%xm1`}Ao#Bq4Ojg1t6v#E(fDcDXLtMf^&k(ddD&G6X2*{ubNqiX+%&eRau zPJpIK94~>fA!o6F&x39UUkZ<-BxrONNO7z-y>T?eFL1zs-~kvn4wuPcZg&XU+2-0E z>R@+hndi;T^IDd4F6i!EQsP}u;VwrCawy+p&9jO$c?Z949WL!JKs|D-D?oZe3>7Q zgIEJ^(tvbMM?{o_Iukbwysd9zcJpi%--bSj2F~bPnxwDJ(#L0=DPOX!Vm2bUKc#Vo zyb%F*`RbvM$H(JEl?VFPgJzlnc)I6s5|$e!;7QVNP&9I9z!q>J!i+O=$+n6oAjdwW zaYpqE2rx9`8X#9>gn&F=x@X|+<9OYwm)3|g^>PGg58gQLuf;x(aV9UK|GMDEJb}vP zyp^_KkA$Z_WFdLl`aVD(vJ=9MGx`i~&<_8`RuP|jUylk3Y!#+i4mO}ocv(2)wu%_? zrmbL%;snKMioBN@KTq*;#TAM-DBi4ihvGeo_bZBx0(zbzkNfC3Md^#I zLzEw`I95^W4e^tdpQ0%BhwvKZFIF_RjpfQqeL{|1K9=kIigzipd&BSt6*nm+*XOGm zZfqNGD*p$?_Y^-+{69r@k)>V~r5}y_j#d76MfM~qC-n?GRe64egyHPO{j+-x_?Lb& z_Z%o_{yc{ow0Cd`^BiCw$!geqYJE61wlQ)}W^4fdvp)K=&)CNB#J=Fd6Vvd$wMfrM z(TR^t+60-2keJBWND*TrJ>9-->k+=VGt(|c%;NS;xA;u#MiA=D9SqI{7yc;XVO_vt z?oF^0c9EB}s>&1P6bhh^VW6yk|h-xLAKvy z{4a%1f0k^2vg_bM{~H)fq#$xf>HYxH+9fR+pw$58fy)3-`y}5lDTz?gpntyLsJP&$ z*Ac@87PBobtBt1`Wv99V4AvYFs58;lK|!{xy5@jnDLghNU@lCfYYs^Ir5kNBb)7Tg zS<*Btt|^m+Iip6#=KZ}n-$K-3yAmO2_L^(5=;wM_t~Wo=%Zhq6W`;zY=ou$>t|~mE zs_?AwU32r7Fy`c;-uM!)dt`$*ChB$1yDT>rSS7p>U-_1?^_(|K28$SSS5IW)21K%K-orHhB%6LAT&?jV&k?W>3 zpB!}TJKAj~n`ycM@Fop;wx!2d0fy{{IJ{B^ZaLn=qljdG8LxanKeGa~Nkic?L;iOS zNYk0PDvM_LZy@(E33W#9+u-ed@4w(8X3RerwgszU&ffp>Mlr@c+yq5pjtGt^k$W9J@p%uG3CIs(3wHK|-2*$b4g$ zh}$LDW+d4qlJ*1$+UkS0OBAE-X=fOyI82f6q6|M*af%}Ed4^x4$oEb1s}#Shc$?yS z#rqT=QrxWgoZ_oQ+)t+e%&vvy&g)8w8FqPXxgUYy!y(y)A(T>$gxD8AuJO54X!ZrT z7xAH=^Uv%HFo7w8eF4q~x5vH!{G z2`5c%kb>~+n9m6C*pip{^NL2#d?cXKC-EORKXz0+c2p(e=EI|tzO*)w12GmJJ#zx{ z*>BIho5+u+YNpYiImt?RXu`j^ruyK_!FDzu#rX{#-n#*qCZ)Mu@Hz*5@Tgal=N%R0 z=Kn|KoqTas&s!OAa!IK-CeQ00EuI)FlnDS|OIi{(Q|F(cgE+m+KwB;_kTVfd}2|!)7x8z8lzk@8wuG9`Cz@-wQx5_rt%7{V)3t zuHTsY;~hLbMeuf;$oCk!GI%tPfqNQMQ+;ec;`B99Wb1Gduw7-}53f%_-%p-`BH{nN z37M-b-sDw@FhetXG9F9Ml2B*jCW5!~-GO)3dW11wyN^8wyh#Jn>EfY$B-EL>nc!`G zTx*|=FzU1W*jIozX+S!Ip^tLLnK-`J+xqG(eY{Ut&n)K}c#{UCGXeT?tpG#v9NGHn zp|7bv_BzNhO#wXJVq~MV%)6E=Jl~}$4TgD5&?}qD@aH?{803< zTP0**YQ+!yI@T#1iLA1NGO)(u?m+eeSdC;!eeA@&08CR2Ih;C-ooU|@_vsPjfk!DG zL&SOOOvHKVs^NVU*~UMrT=lW4P|>>Sy9>4bmN~3HTXeeukLqD_@bX_Br`|>L2^aY1OL! zHN?Dzn0u@LSp5{}r$FCX`KGQs$YuO$#6u=h_s43kJb1Gba;qT+*+^aPjO~r#)!Q2* z%eFUW)%oiYo@#7^_#DKyuQRI>ej}?AMwX9~(f1sD0We%G-vA88%$v6w!P$Bm8Z*DG z47=Rx(cOfKNBg^n!dCXfk6$Il11$LRP) zzQPS68UBFa_qMSlf%_4ptU*xHJ_YRd>plg%X6W1qXNI_E+>ie#yx-fFoeKDj@_XB| zQ^6}>)Blb?S9U6(0)G*L>{KucS%Srf0EM0Evsi{8EDMWREJG01pRL+-Pd(l_KlD2m z;6_U7soTpCc$?AjA;OM3QEsiIbq74d=(rQu`g_Tt6nOmINCTq}T|k z^GW;%t_vtk+$VH{mn{!Sc8wHPfhZfaDg58BKT^UcM(t;#FbrJwXzF8LaOKwnU(R_$;(I zR$2@mvjhA9|I>+sC1{)p;)~)?2|CjRHD!acO2T{XWN9Ns5!rVxg+!tE1UP<&lFfrWi79#B5m9drQ}MrG=!o{#q=6=uGW?TE4aCM!K5xGDJ%IzXWY`Zm zXP=uY?9&qA*RkX+WomMn!vUH;z8b^Ej7z4?zqn?ab69L=xX*PAyjKtLItH%e{btVv zwghl!F~psOf41$?P5_G}H2!Dg_|PG39)y%@h>OVsk?a6?lZHI|*Zr&jL-s?Q|C&fC z$En7{faA4n+VOfS`dF?Cc#{UCGX+iA8WQSETorgjGwL(Q-C+e7GI_qhTD%k2A(Htr zzp!Er(4+zBtU*MSggO&93%q?C6VTzxMi}*Fz#Dy6f;MSDI-3zeIpa*+QUuugsx5t4 zh%@>)l48}E%`^q@bSL0MFEdKOlce9EXyoof z-{V4r8E52vgaBMqH72|@GVN&?pi%vTMKgLZK%C{INV=Qj$QGhd(_mDb590~&o+kdSuxp|EAx*NT6%@f^PnTL$YmUIub; z*Bo00uQ%2S+x0|ShW~Vp@3|nx47Sw=Y|CI9McW0hGvcX={S^l*4p-#+Eaj>cs}&b2 zE>T>rc%9-+iqcm{dg-_UH)%LugW1P^La~mBi}zU~||n6Fr@SfV&kafsq*#c_&kOR2X? zu|{#e;-!jg(ag`$5FoqkO$6d-80l-=_Gw;%^nD9+B>2<)t3M zn{^DFyTbgXUV&|uH|rVX8x06QQNxqhHORbT#FuJ3`?=J2rXoAKmn9b%{5y`?Drc8y$g$qqvH0z|KnO*uW*4a=NLRWV9TkvYNLDO%7}MU z=tigEgJrAV%W~dqd*v72%J#9)_b;!$;)~D&=XQ9i`ktJDyWg5SHK%O%9~KnG-pTpd z7w!X`6)|x4+Y6q8G^{?Z({*h9_Dwgwx5Bx;`W?ti%meQn^HTM5U!<)ZxO?YzBuFe6O^W{HtHITzNzF^VPmAQa(`kg|o8F?v~+}GY0Pd zaKSsrxY)e{+AbP0BR6Nz?j1F?kY!4gX=Ul|cNe~1JvAq``wthsdrW`iS%i}8SP(kZ zXoAhieSTYIEOcAW?u>}DJCr?ScV@c#eXPK6PppSk=#&v1?#byH!_m1v|00BPzqMfd zrvBW$Vy0gv_cY|TGP~Z5jY3#iH90>fa-7uDg3xJ9`QbKq?eZ_e17jVWFH#%6{OliJ zy0MCe%SMu_Xt=XKk^b#g19lB`FaN^nR1o_`tFm1K!pX9C1hN&o-d_l9f34W{`n&wXcMw(bkpotd+&Rq3uP-Hg~vZN0Te9y?|CJM-$^cRHnP#J(CgR5Umd`1JDF z@Ysr-zvFc(mqXZH4|I>i-{%sL_!o+#$y%RqcmyKwEeUp;usMco-sz@3NYW6%OM%AWK6{@kT89%2NPb)5Lvi@^m8Z!?}RQ|&HqTsg^UiT$sOiK_>D1`xa5A1 zgntMwWh~^pYPSlI!u!&j?OsLtB+_%;0?__^lhpsm-nRfoQC

}+;7$&v(!ya@{d z1c8u{@DL+}JeD^J;UOx@E5V>VlOPXK1A+ot1w@NV4Yg>kVny_`)Y_KT$6qV7!P;tD zY^hR}g!+MKiN>$~f4@8D&d!Fn&|1IG3pc-W?mhR+ojbF4X3m*=My(?8o4F`4`Nau* ze@OiW8>j(gj(HPhyv79hoeZDL%c&RwA}1nO0!pc%d>ctH9qPvdzd& z<_2E{8&uIhuA;D63@tFbDJB-TV_;!+Q*5Tq!tAElVz6j%!WU#*W;Y?RPhR(HGcm%% z3~!F{Of=&0JqrXsO*01vE%kYe3xiF~W@e7>-dtRiV7#fZQX|+(*N<{n+qX8w1S;?t>&HhF@tWx*io_WY@{CZ4JkLPCQEnXTf2@0T zKQO#&@fqXq_D;CltM#}Wq1s7ZLAmS5(?j7iuDIKK<=x&m^k)RJ&zN+#_wu{Fd_v%F zMf0S&jezkWBaBJ0@qcnfJy|nbl=@|T~!Pgtd1|3UpYja~#uqSG7QpP~x zu|d^r!i}UiYPNoqFQeTlTj~w-#pO-N_>3sw0Yy3^8v@Hi=z2SeJ-rpVt#R@$R#RYu zYUdnn9vL3y7(CO!=t;5@G7diBB1MiP@I=CaR%a3}VHi;C4Z^pOW`EFvFaX&yVE-h+ z+XXNlXN(~PHBRE0;2w7JBarpM;uzK=yJd7^o=G8Oj1Ymdlxd77OhWdkF!dmic#3dV z#>NR#kx}iOlH4epKoMcSU5y{Do!Tj$w3>%iA^YS`ZvOkI^B4zEeZr+zmD4I`RaDNJ zQ4wA^cShx`d2=g_83QNJFQ0c!`LsEqnX_h>R)o4O9?-A*8Urwp4v{b*68A)fi^B)jVX)3E^*E-;TX{b;wB>Op9yt zP=}GdGpt!@d0FiTrFZJkD`QZOH49N;Lg@%$+cz_#XR5U{l%H-bO|urKb<5~V;(E1; zYiV}-P8r>^QU(vQ=47)0)mS~&6%MkNgmP)6%}j?~mo2)C>^-oP(D)z?-$JWQ>-NE= zRz(`witOFJdyTZ>*R8aky&0iwMkt#tuF?In@R=7}zQ!$BIIX-iLS=AV#vOmKILK2X zgX7|CYpY>LSBZY1OkNE;-jr*vl5&K3&rqQ{QaE#T>9o1$?_IF@#ibPsXIC2X(%RXX zr%zx;W>3}b9KTNs`ekBB=dk;bQXzevcg-SAs9^f+c{8pX2LrC5LhMAAj5&s7CGTuY zI$tsCnz^MVA=QSPDV%8^yb43DefwG%f;qdm-(~CUnoT&FXW^&Cgvt)O)qkVYZ&C6SP%>sEkw>&tQJ<0HK8-zLzy4OL8mzQ4V=m!_ayhuvUYn?ImTC%s)FPE9A#4m}@* zP^&!t)JOf?rd!|PX0QvPOed{R^BUdd=fiHyV--nyRO}MV`Sog^M>vwKsFCCT@XU-P z%dm|@y2MgvhUO^WRE-J8!%iIWNV3!saPt@>SE5~+KQo=Er;}!Yk^}~@l zrktA`yL050#Wp)nnKF%ciBlHN>NC^O%*>Km*GHH+3ui}|KC_m(?+dxT+0f4i@#~40 zlWrnncUKUx6Pu*|A*p{%>VGKpoV(8Ey}h24$MEyFK^!7DOt4UJqM)+XLTYos)O)f2@->R1Zo(b)10dQr=(i62V--u%J3_kRK0tyM=SukBN zOHds*$ma`REI3h+MltGBOU{4~3;zQ_TFF>nC-{-zKLlwkV|}b3?PcWK30^8VM34qF z){hsQB1k_o%dZujE4WZ_iQsa>f=>uOEBKrsEqL7S9>KQ-|0?)* z!6SmS>QTOlV6tER#rvj5eklA4sYv0;b3dVbz*IxuaQ<* z^OvX4?hqvlYtx3pBaoW-*_}t&!b}GBIjNHT!L7YJ4nRYouQ@1~&(?ivwudh`Xc>jI zp;5aVf~o!;Y+G2{aSXf_sR=va0l@YH*Cl>d)zCkgb#|X7=W|G3qj2W|op(K$$t_8q#^B%gyefecqp`zrVs?zjAH< z)-rz&#_9#3z+%JmhQ+$T62tR5o1$mJ^LvXzxZtMZugRcT@Q|v%VB-#fGDm%gGG4jj zl&N*}B9PO``dB;WV~|zI@ygRt#Em?Q9Q-qD$C5onmX|o2y$BUS0z1a`8 z*=i6rYc%Jb#b#t%=1IzM0Bjk>QuuU^7q_?NOjaf%18U8A0hWJj7s zv>@_9Ja)VpMnffaPbHq507~G!VHi?%c7o>Nb5a{naMOGQ;4KMWOD42|D$7`UlQOaM zq&~SP$F98`jhxg86r2czTC~-UoDY?rVgehn*l7YH4cTL)t2eRxfi{hagh7f_o*=tb zdNoQ^; zLEl$JwR%DBy_>hs#NKshR@YkQ*Hoj+Wb}p@+wB*aP4kOt%o)sKoPtM*yQv zpe_$S>_Qx%ii-%tRPn-P#A2JS1gJz&GHj+351zZtGF88@l2~QavjHkK!ycumy&6kM zLyk3;F5BqI>73Km86dq=h-jx9wgZ950*NQSojyWqoj9{~L%sreCh|Ju`;m7bKaZ>v ze-~NExybA^do~}L^Ox>05BP(~k0SpX`E}%d$orAsL#{>E>7O7t(Fc%u3UCKGqjK*q zLgpUw1Q>+O+xRf@WaOF1*COl0bD|vidSvdtJGuAsN({o;`G}75(tNc}qlhg)g}%YA z@@`jNz{k!xujb<(8oxDl%&lMJW&Gq3*6a|zV`!CSTkS)GydLYneIc)D-MwT|k1pWq z6t{i}J|qAiP<%)gWkX=?lI$UUdMf!eu=gyP*%r)UADMM{T|X7vA;qm-;xwdYvaxCI zmXnlHHoR-eq~5)iPD-v@GAXrZYVWp@en4^WMvBu^W39Nwh+Oc0^s$FqmW%+sU+usn zivFXbw=7A^QbOF~mL)U0DuxD*>%9 z<9u?03DHTLVE@el*AkgB%mHNHiMg5^-Ed|2iMl$V!c~_G+O6*`=oSJHDKHk~5 z^}UM<(^a6!l16d|VDCA4g6&R)oO`>WR(N+=w##z8-HJx~-o(y@P^OdK?mQH@^&Q5| zTN28+AE)wp9fQ6Pv@)R9w*s_VADy99sH8raa-IHdacsvry@KrCkJZ=@J_LM@*9ZQf8|3#{aWGgB|`uGg4I&4d?=9nq3{@HCC7P<@|cbl za?T^qd5VZ>P+?C&&dV(CFL=Iua#f;lrQq#?cL}QV3)_7__=f}^5qwrqooA5yrSLBc z?h)K8_?93a=(#_K1P=@Hp`GP?a3}T^RO^PotMd;yOv-7Vq#R#HC-R}5I9HGl^yHTc zt`bx}Rg`lcU_IvnBG+LOzbp8d;1309^JV=Df(HaY5Tp^9^$mjYJnrBV1+{NapO5N1 zM18i@=LrrKROch=#|eLh;MIaN1-0*Qsqi-m(oD?lZxGby=YzsOBKVl#bAmq;d`VFI z`t}QdKv2z#r|_}yo`leBNhC`2fLe!5qPSK{c;J?2%XdVH2Y-^IAfpYq#!m9V-b%L&47B{mC@yv?Ne&k$E^-8 zr(g5%^HrCHz2USlBH(OK4__Xp7wz(}FFZ+6-PPaHvRlI4!|77u3wIMK%07IGy1$*G zE-A|#920(FZ){y$Yka}iGp6S9dhZSC;furLQ>gc1^kIP7jw#!_FdP&19>!0&=YX2k zPeFQQdbp#K=m^8u_NesiBPF-j^I+#g7k7lB#SAb6GeQ+gWP*{x}*WIi-ci{oJbg9ml8_s zQo>BTlu)I}iQF|#&~V_q4A^Irgg+~?h~QCOpU4~MD{NBtO?L!BPI7lJ8>KnO=pcbZ zY#LV*CM&XtP-&ME7Tcu+_6)LwO?D~amx`RgzJ6$vgu{v~A|$I0PGDcN6B$yO){Vc|5HBkcmD*wKvYJA=CKT@OHa_2pYQKzJ$_)Bmn zH$M+`XXkJFYTZl6dAl5clN~w%yW@D6Fb*!?lbS`v-}GDfo9u5-Hw#&F@zv_=t9p;@ z(D9lMof`eMu9#`H2w6!X3txw7lRc#O<#4Smsk{*DiH5L+O^3Q%3c5VK1O6_ut`A+9 z(j6X|RqazRPHmqHXHD1LR_Y|{{+qKsjBI_H_b;=!Y7wR^82E+Yr&L|6&mtH@s0_*)k85d_|ruV(d z7}5tnSM?UQVRi!)+|d?ybpzm$4Q-=frMO30A-kY?-fRNH8)-X!%K!v zn#@H(l)mPMF%^~6=R?-|ib3l(AdSwLLpPF;r0Yt+YnoL%A$PZ$Z*4(cHx;aVyDO97 zH^9cYU6$+ZR)E%RKpOl$bclo`T{jQBTi-LSBDQ^);2eFog4S)Q;ySS>kY>_#D?q#T zz39>hlboZ^zKdW>JKX?%6w5$Gc$~Pua4$Iewt{AxbY!LvA@r110-hxE zlY&}~YqA%hOeZb369pLl`MNv_gORBjpjN%xMYB2|asx<6;_+a51=+nH`>-ELDC2(M z5IXzO6twHG8_S^YOnfLgP*#ObLG3AhD7&zM>5$P$?}z3!y34=up`0HdiXK}Ycl(aq ze#DCMso3`}(d&q2PAe&itQK-F9g6n0R4kkx5#w^Bs7tVVCxHHyG;E*#l`JCo96>%? zvAjt5$$~Sbe75k51^HX2{A%GJ72F}^v^P`#8-jfDqWpWpe^5%O&WJ4-p= z5M(+18}tX!u1tRr9}ePL*z+@yFN{&od?{ZnJbxFI=e+#y^beJBdzkb%#}aQ8Tq$_F z;0D3_1RoT9N^mC;cG2ercM&m}yiA1N8sUE@{9lAWAUq$rDE~i#eEMZOjyKCW-oy@4 z-d*@K;gvlI^_L1iRO&|wKT&w7SN-IicOrW-=O&h`2P`13$>h@o`wO0_--PEU+fNmo zB{)a$dcmcF%LP{n-XXY7P>nzI(Vj%T+XS}@{z&jAg1;10#{u$c{DGXW*?zyEIu76u z34d6S<}S)v96z8kzX6*IuZ|1&6yduFs^f$5bm6lEFA*Fp$QLQ8cZA?r!3l!AuVMXE z!D|E=(wpVwg4#cGqwvcGR}0=DxJ7WQ;C8`h1b-r^{WC8M|0}`0g1-~oC%9kmbZfQ# zN90V8-T#1KP_VgROTiSuPJ-P9dkJO22x^??^<2ORh5$a_atiLvlE!&WgiV_dG#Fej8c$ z?hPtlUC+riA3YUcHmr;sRzHG?_JO)=LdBYoN)49#y>9;9b+K zF6hatJ5UR$kqQ74}N3Vyw^lTLty(nbi#Rfy!pB^0618jAnH)aXEE=yTLPv zy8hqZx3N|8zF?i%&S1^h*>u^1^tY(!dM}OeSGHz?nC`k!=FOk$ToFe?AL)C z@>1A?R);7dFJ~_o|@SY-mU19AX z7YwN#>ERl%Q233+{L@9St1ud@qljQvo?AQI^NW_A1~X$zgD3U1R_hqS&f~c+sjZ4y zR|x;p&voRwUxr@`uY#XO`Ht18;x&0)F!@pgC-BAzP8h~m!RHCbpvnsPXG6&H`lk>~ zUw{18@F7E*K=F~pw^=B$>uB1wW7i?z-C;0ZHUFvDb!g9<3jR|Gfk= zz?U+tfHz{_-|P#3yvfH)?~T6aQL@Z84YD`*zKfEjhJPaa zce(jAIRAM3k=S?sTOca2@BF+kkl1$t?@w0->I8QgKQCNA409Y9;}#`$=%37&b#I~ZlK9V{ISW;S;IF4%<-&Ii@PR};#HH& zz$TKp3QQB;kJ(}F?jf5(b`rI7U=zI5&ORoZW3BZ?n4FT#i%@38w^XBMHl?Db>>LD7 zwY~~N>i+Jdd#P27*Nl(nvMDZI@^v$;gm##4{O)jf0Uhq{#H*^<@Ql}0VJ{=gqquA; zVa*B?eZMC+$kkMdYggcX;kfm=cnD5%)^Mp+UfDtHYmC9Ldn&0p`2;>H9$omT28fsf z+=}Bs77^Mga&j?Xx=r%1T!f4-G7xx=Vj0VpRde{M3=JXZq)wnDTpA^?DI+2|))52I zSxFWXY{~US5lMEyN!g&>Yk#zuyG#rJ5dC{jb$2Y`r^x(HMPZj}Ex}#PLPmr$0+qvq zLdaL-Si*Egj_Zf!++%o2P@ocTq8>qZLd#V)ihkGqm{Cmu-bJ|v2Zu}r-Nt4)(3_Fr zV;jZc<#Uq{1H}Mxr0p$^CyYl{OR)4lqq*va{Nc{Hhk-nQCpu;vY3^DAEF;IdAM0=b zO{wNSUg46{>fO3ftx`Mu#i2y2U}NXy9KQ_GYc<8kT*NzTW@RW2)Jg_x?IuATDqbOBEYE- zZ(IkHW?dNiV5BuZ&FUGl#@jL9daO$yXgzpy8d^mKeS@8T%IG2EhfNt(FlH#Apt!iO zm;vA-9vRvuWKax8eBAIW3Z{%6J`Qd3hW#sozByYOUodX`l<<(@qb3v={KtiYb9#v- zJ`+Y4j2SNj==iUkux;ltM4YqHF+;`-9}{*RlnHrx1>?pUr-~tW3Xfdm%vYV2Ky&Kw zFDS3%UA%FcsB`wIGOco9g{xD;#|)h?Y6#}huY+spl)fcSb|>*IokL7I{oDG+x1=vB zxQ?iFA^!5V7muMT@v`ksS}q-hr1_l6M7d=9%B6UH`Qn`{%wtZPgqx;e;94S6hMC(7 zBWv9t)tZ|xTm_oUMV(vU7U+8gmDI<+Xnnkg&}~2(Ls9W}5|VUX33yGjDhtopd}mcB zT{jg4?(LSrX3BUr+%C)Yb}K;ZHXw~#@C+X!AxYQq5yh=2jQZf#aP-{@TDJjd zd{1lwq?vTx3eawSuekK_v0e9XldBC#<7w#Irj@wrHiCBRdkgw_oY=oaWUX&2Xg25h zz%&JoDjJO+>z_n+%e{`BT)+mBSjW5*8Ry=7DK_$OubrtGAZ3{N(4%Sciy`N}(Psac zUO{&6$9~tiB%@C6M^n)HoCj%ahrToMEmfjn6*|%iZJHrdACDuq>DKo#DyO4NCwJd< z8PQ$-jc@7v_?9@PypGV9G{H64JWk3D6uAmV`<9|TNT-icr!Ol}*Kfn14VXR}S|8|x zd60;c?;#@Q5k5Sz{za*$34--CQqL!X6r8u5-_FKI!`}^k83P4}2y*^qd7Z0mKM?#_kUtLU z3kr4+>`KJE&1Yt!^3C7}sC+Y!&t*Ay8g#9Ai0WYw*i-m)!Ty3L z^97BTdYS;JXOiG#!BW9lf{O*03Em=jo8Vo7>UcxnL&85I_=Mn7f$MMura|(%1plAlYl3eGz9mSL8s+N*^;#R=@36e_nwwPo{#kyZ zV5T7LqbyhRg4`F7XCm@iL_8vhDdohzf-{X1H{i^_WwR02MWo|=1<`ThKK_z%;)-hC zKjS!Y?@OFGv(E2@HT~ZoDb8<4id&qbBEcc98zaTNuOh{%Xm+hm94U@`+nTl#jrU9JlEG_P8m+X^Z4FU&ddP z4%Z8j-%^E{xxsMYILm&bs&09=ge8Ebw7 zSzjw~hHohZZ}!o~c$4p9{Jqgfzv?m{S6SZR+l~^r3Fd?GTyFjhoWBTv5O;1GX*C^} znX^g%hFhFtt^*zL{u6&==`Zmh%3KSebtV49sVH-Cq*RnSMM;!73K{VxFFfXO(#p(B zG<_KG;C1MNIfC;iuO&hHW6Y5^ft*gZ71>d&tpeLbMVcE!_0NJ$xQcBH$sQv6J^ZoR zJ}63f8-L6q_IMK6`K%pF&2*GEfs3J-b(|R!xM_17yUGa;vE{H@g=$CHT!vv@L0PW& zOYDa76fjKYEFRt@&fZP)@#h0@O$Q2Li>5=Y8%5{Pe;g70T#J&hMGZ9M1<$;XL47CXWLg6ohs-8Y;XUj~<)3{0pdtCxAujLq&G&`1lUa2&TjQMo@qCjUXwh$%NF?mhLHoqop2$6mMm*Fv{MNZMC@-3|&tg zzj|beZ%5Lnq%R{hLsrfe61+jT48*r1!Miswk@$AyDB!kI&tRXbDah*tjt+riVH%fV z+fM2S%I#{=L#9IB@k3C0T-`#tHP4MSTB5IZX;Z|~aTbyDcAqeE z-VuqFXGhNayW;M0N6!1Zic7azN6tH;jC6V*&KHTYwoM-m~idE!1mtscFvn#nBJ96GW)x!r>w7hrJ4m`YMrnMx*fO-2= zCmvif6SS^NL!BKm?`>7PRfWvkCoQ+J7SeXz!`RA_5QFA*fy*#0vwNnsG|7CB)rhW#_o}9{?7_sLe7*FI_MR^=;KOA1XgNXelsxJ|h&*{yVaWlF-i2v)IhC$5J zCtHukY5OET!*ht~r;NMb#PoArANAGpLX`1VlMhZzyv)0kmg6k|X*>X_L^<~*mi8*9 zp2#q-I%#T4`<4NqY+97#_QJ?oH%Ju|siW?Mt1cI`Ti>Hlv{$F=HPB}mu#2idb<^k^c_TH2xU6y?b06a)@QUoGoN8B zo>h4Jq?6XS0tIe;NzlhzA&v{p)VhD0KIrE`!gf3LS5S_Hg?sebmowy7hey!_st=>BN0K zQF51m<1;*eK10q;r}i11IL2ROJz9y|XISE1oK~X0Yo#wMQTG`3`9YuHMjTxF47U(* z^3exDpCKQ1S^vD$zasU!rM@2cWqgL5d+DRf6dWixM6ghBqTp46JWttfj^I+kn+5L> zTrc>b;KPF31fLdsPLRJv>ixCg8-jln+%Nc^;32`If?o(KUlR226=mvEJ|v*>1p!M~ zj`_Y!a5fP?$m>O(zgO}q{u<=(5}wD0`smYTy^8w>+#%&WJ}m!*@X99yp1xhSqj`Y! ze-Zwm@c$50z9GoP;9R6!b3wH(2Ye6m=yz`--l@owdKy(J&v(>We}&Y~mGVV`%cXvm z)ZZuN4+%ah-98@Rm<)CLCW71IT~vz_p#ImFu{>$qCDqPVo;Ft zAbHM>#CC!`1=9ul3!cmes?JliA189t1!oG*5#;rR+o=*sLoroJ1jg+80=R+K^m3GPZp$ko%}q(MS?d7-YU3O zaJ``RZL0GX?H`iz#|57h+$H#;;NJz02y%Ym_CFV-NuPY8UO2Gng>U>VFM0te z*He(jfAWI`eLPO5@VWB7hw_cjYu-Pwyz%+nP0Aae=UGxdKrmY{M=)P-nBXYEBEj*3 zlLRLVP8BQ>EEAk9xL9zRV3nZ$eXJJ#4#9PT8wEEBZWi1kxK;2`!EJ&&1)mq(CHSJ? zD}uWP-xAy>ctlW*FYXgt39lc^xpe$Y;s*B5I`j2#jNy!QoR7P4+`yN(mlBC#XZ{HF-Z_(xT3ZH>3(9 zf8YehtvDUcUD?D8EF$NL`G}LB$FI(5Z%k9vSpojh@dP(eED)pS(14$}43T((E7;cS z{|Uhi>>~ucJ#1(LCCb&ztA+2cC^USuUEj=E2d?HT@%KjGBPdzs;{ukHkLQ&eg1CRG7qPsaUZ^WPe0q#m)tr^xt4tLW0TM)HDe4F_bqoLHr6t zvwJ~smztYJ7Q&}NEZOADNY3=Q+n2eM_OvZ@dSjw~0C`E^yWVcb_87WNX zZKP4LZp31z2?(~*5fb^^u-%6L=1`5gpSmL_>mUz64l+iIz}^2ULp7eP+adIeUHuOZ z)u_9U*9Op0m5OlE6eEANp&Hks2kacr(-WPutp64=P5}Z%;r7*%r||&uSEJKP(Da;A z;r+;3g{~*M<<%pIigoER8xoqp{l$428#hi8yU_Sg^`zSIh|qD~WuEvOWKxQYko^pg zd5_T{o2FUwLRQm|H80I-deZ2SSI)F92&pBDp>v523CHA{J^7)qAB>|b^v#~3JTSi+ zH_5u^W`6kV(OzlF3+Z^DqWq0^bV$cM#gKeaYZXu9X0yl0Q6254oL{)G(s0~p?!c23 zSpGKC_O&_nT-ax?vx_cTuy9&=Y2nP#rPJm{*1-L1Jd@|?(_YSSoXYEX5=W!cR(ynK z5xmlAI_|hti>~J+V<84Qvk$(^rh4Ekr)js0M_hDaw}mx}_ozIJ#}q%8IE zX-(@Z2CdtGG(N%=!G7VBT%@kVMYB8^wxXlz>On3dHx;ydyPso&Td*;1m*sl96`i%s4t=oV! zE<+=(yUE!OaE+e|jzws@eAK#)LUmllbezR_gyr zgdQf!b3P^p1^F8!&-s;z>06;XzTne^?=N_!{>jNAKUHv+;2gp01(ymg7hENHhu}Iv zb^Otv?+Cw5aJ%4-1b-sCRictEgD@V^C*2{s6NWITO>Gyqdi8^Nga z1?3r1-d8YNFh_8x;7CDr{-E7N;Tx~%jPm0{j`6d(eeEZ`NqA+3NBJ7z)p-V9`SpRD zq+G4n0slSWX~CvGWxoeDUi107)c;

!c`8V?OZ%!9#*vX2kMig6cd3@4>wb%VPzb z2r||N%efAX*x297=xi)c6YMK^v0#p1zTikf#=c;?sP_iI(?-v7?SEY&{EdPu1y>8+ zC3v@>dY=I89})fuLG@k%%6AI?yx>cM`nzrV{em~7{4av)Jp;6_75+oPV}cEWUfle! z|Jv`X<91#k<@7SJUi*Ff2|rMfZU@$n7u0b(rwC6!gc={g)q-~j(jUS49|}Gz_?#f! z6s-TX;O_+gAh=)ffFPeO&c**6lHX}(LH)bsJ!s>2qUCcc&N!ZE-+t*?A(c)aPc+C$ zwUPhyj&QGohs`Oqn*&Y5*VcH;^2$~=cnc8Cv*6aUz>zQdyxia`c%iICm?exDY8*+j zCO%#MREM%F$`H}B08udus>}YU=%h?@5cxJWC#q#lhgtW}Vyh|YFH8P1E0pOO#Igf> zjk-WmJA7}gZH*N!N*RY3p1v?;5W&;9^Qmr6vBcg&Tuq1YW#A^2vHp_woZ6_RS^9LYhlNt zN-ul$`tvzUm_GHgg&9!y44#-jve4t_mBM>B>B3TwSo!*QFx~?!DO#jT{3VpZ69ocf zuHj#21|Kg* z@JjZ?PU<+B!%>7dnY5MrIY%Q-=1rh=Y|IcuWd&<3ikVDKjd5*RF(Mvh2xW1+JvK+q z204u^uR`W1)@}l2$HpAPSHFHkmX5~4qoDW_P4FrZW)YiS2NsoBc&g%H{=sJZ2+KEI zP@5@iOLPEimazT6HsMQYZy|Fs57O*yuBYA!s7v6u+N_bti>BHQm>M{tHwv4{ena4N zzQ@i+eEgtz3s1f0vhcIn2Jgx6IfXr3l& zrkcSRi4ptGV-3$CCm$#A4j8@(oC#E2okdGYA-;gcKF*38LKS`VPv!p090a=EM&AM3`0gWkFQF4 zq+F)~6>0rMSfrHn!e*4W9rdeU$4(JoF*6fC1oRECR|NjI;Qr{ z$mwB~hpc9yG1j$dnJnm-nrU6j5`4`}NubcGNbAe9XQ z$X@Nbbhny>Cim`T{rG0v!4&am(5ZmjFAH7<$14%#c5+IiJw~=S>O8G!bGGpx=qz&j z_9a|I_WH9^IOZZ}h<5cjUq72NrMO_6F@5&D8P|=QwY1bwPC2JD=ejPkVARdFpj8|lPZC@&#-Wy~t?t=4Ux)#?@?tzyZX%4yS$w2I1d8_P6>@3U1J zX(iJtrx|I}D=KVH5ew5eq;fpJ@gM2o#WliC=i)y){$FX5$`kKIFJvmh0_SfY!P}8Y|GL5D7`TZXS5IzHRiYp^W-qZgceA3R<@TX*>jd zl+#Jqtw4cW-}5egG|%b&@qS;op^hEUH^o(;N#5PK_3ef}ecTdJr}b?G%{J-COidv) zywUiv{z+uF+!eU7TEGU9SjW5*8HZ}V6dSKWE>kl=$}sIl*0d_Xpy@u4XaAU9L3Z!Q z8?JFlMxEXdoJQQPlhUE@4-OaE7PslzJ>z2xMh*&Fp}ZL~_3`*{n{Its*Z|*f(F63Oj*Cw8$@;|Idy zPdheF4~4CXI0w2Aam&nkjP>dc9XLezVSoX>3B&UXbL z73A-S-neh?AHG3(EBq{u1E} zgdZXNc;ROVE)cw4>Z^p;>%blq{t3b71%E-r_FoeGH4)o?OX`(f7`$5d1-Vb89=oO5 z@%P8}IAjWWj*t%tb{6a**juolpgO*gA0m8#;21$(SEz5AV5#72!TExV1aA;rCAdbA z^Dy;n7W|%|@;{;chr;s#l5)=r?h;hT8|A+h{$0WM1&<0I6Ku}%Wfr3K>)d~TW(?-Sm%LUc^;kV~{mNOCc z`FBKkUSm#ZA3nnvlKrv3|*;&c768GOh zyDhA;%VvfPYcCxBYC~+n;2pukW{~B9Od~C)=J_K=;srHmx0`Z>wLO(o;%9e!j;})% zpw%ei;2i-JG9V$*!0uN-Q(#gPf?_F>+y7w2Fm$0T)jX&J~Q_pMR)#!hY z(O?|zx1)2bg1Y?+)04?@4{UyCJCADd-rjfPVTsP!-f-k-)39|k(UY_T)@Vj@RMzNc z-`~dbKn=Io+y*pP;>2r$%o`YYiY$VefMV-Oh**7dL1I0Oa$0%(%UD4NnN_GR8&OMR z=1|n@zm_sQzSbgj=@1Kaz&{7=BCBM^frIqV31&b|ngOr!DSExbsVU%f7R!7D-bY)v z;p40xZI|HL12IBQpcvg0z2YypNWU-%<gt>L;f>zEi${upR^v71oVZ| zTPx%==v-u;V?0vs6+g|IJ;G`g z!lI4_-v})7xD7$=mU7X@7b;TS@+A*WP6zj?iea~W$?sh?X`LfAtCk#4D$^&OIL<~Kd55qZBTU|s_kr8GBZo=!UFoWu3fjG0+Sx<0U6$+ZR=C=L zH0Hzh5F#N-tDXnmt?v+aAPHsM512C@eYb+vZ9p39pzjqDl62h)@NRuvHVp~1 z(Z~B3-3FvF34{M9SAixsqRy=^8-`YW+!9fz_jfC3wn;~3%8bKv6UId+)-gXRsO9d) zk9~m_k~+%mM7CUh1ur_E*+`D;Ze+^qGyrm1H_O;RCXSVRKk~63dYqF{r}u+)Wo*|; zWzhErhl^~B+jQ-o(X*L7&aF@mQt6|9Zqu!AHqO&Dl-WSN zlt%e|h$v4J96&^Wv!%XB%9TABa#N(7zGH4zz4wjsMZ(`gMEh?Gk70_k7YBvsZ=7-= z!OnuG^H=1F+)zP2#8S@{g3|;`1$mudeTCo(L0%VF{w=}vf}G!3zFF`Q!N&w?Vq?AX zPXYG`zgO^};NJy57OWRk=MCCfJT5?W{s0q&r}c~Fse*jgCC}$w;t)aQmjXXZ_#(k8 z1*Ztk6uefjLU55_mEcOjZwam!+#H;A+7;1lI{}6x<@XRq#>4ZGt-mpBFqL zm`ucth8`b1rE_`UnZ!Hm*Qb9U^}2rO^zZAx5yZxh^T*T|!XFdAI=mvhK5QKRZIw|L zf8>iSQ^nshIx-4ZO!$xWUgN^BUDjRIuq1Nk)%djLCe8zT`}R~+eX)iW`$&*bpPi!+S>L;{NX6x z92^t=@!q()_%^K$TfQDOo zEf<4*&uSmtmRop#Z;l!ZEf=&^AmxTM1J{%D#QcQ{JpS*I^Qx$5)z|#z9-aN+%8)O`#^|Ui<5uL~|F|CXB;sj^Sq zj2>oo!5z!&b_jnH%WQ=Suh2QfGJ6rDid6{R)Y!`(&ad!v5H3Q-7ooh>BnH_`pqj)a zn+aBvn2U^HP`sc|MFzPO@Vp{vAI8#XGsNJ7Pn22oQUb>pZRK>uvqPv3T zwmv)dlnl%XMuRsu-$zDo2)5vah~NaRM%`s7#;c3e(a;QkpbsHaq3#8bmOHumTT$ov z+K0U2TgG5~Z%XPOES;i2(VBx%k zxNN^2S&AW)+0o(89CXygyRERop}%|$3sx@we||w&rWW?Kxfx<#Mvk}q1!ES zD`Qs$ZuQ^hTOG5;yVknhb0;d!$v=Rf%s1-}oRP+8s&pa#29PbAJ*#ixxUU@g`qLA7 zV19AZPO+!bZcQ0xZZC|i`vB6Y2lIPZfhKcN=hj!>+)#0YsLzM2^)>bnaDBS{1`dRf zw7wD-&GN%gz&EpW(sEN#;NI>g_y?*W$L+FQZYQ8RC3%N|q04c}hJnz}8 zu?unogeLHKFuj88-jDg%4?WJj_0z|#DQJDpgEZ=)?@asy&qLWdbP8%u=^q${^Zr^Y zmZbMX^BUdd-}nd4f844`7-)_$=PLReO7y@3d0sfLu-JE0jp9_fzl0MNv})n3J~Is` z8kPI&Ij+!Dav!QgQyF}M;uOEvRhu(DQTQUlM#xkjH`B`Lp0*!6q07mbVq; zb&a;=u7Vd4G3jMV{UG7ro9|-=C zh<^N%h;~fmy@El(B*BniXTctVy#)sdW(yVw4i_vIoG8erbZ&2&pgLaQXA4gg7wgrF z+d%$K$gdS#FL;mOX2C6jyoOO;9Y5f6!v9S0CBat(YXsjAd{^*&!J~r51o?ZSevgb} zte`sHDCh5r^{oUu2x?!9I_{`Xlk&cT7YnN6j{32}PZCteALTQIzeaGbAb+3SF713o zy~gAY;d%XI`2&L0f{zG3Cit}Aj|6uKaxP|j+6#$q3jSH}9YLBAS^tUP=YlX%sB*o= zM1Rvq%@4T0(dQe6SIOz~F(7>7^Ab~zk_!py^Rq#CRi7B`yO=+3QE9nE8_LLpccO1r zdImfc>B>oA|IJ8G@7J$iDAc!a2L3Xgz3-wGR>mRHP~yhzN$XYznyzoYq1ig)@XgDU z?pqlSmaS#fp=(B#t!VJ9*>f=Nnp+yI$A4WG_nkclJ!>9~zqP@)CjL8~2MTNN&&a90 zZRp$e!7YzAe=vSX?d`d~Z~NC-)#2K;Lkep*Wd)CX(XX)f@yxdm`W|mn=LwFiv*Pn> z*W~=PdAm9@uCVq88E@C;tQ%Pu<84!C#KqkU+kY_jNKzob&Wy)p>~LKb*Q<=F+4Ob3E{d-l|~Tema5B#d5M^LBmmx;AybxZK)1a^J2Wuxn(UKR&TKr*_Sd?=>&1-JFhI z#*GQHpV+hf|7zZ*&NSj4L=S_|n~_xKjT?o&nS*{D4xpcL_Zo-qtJ-tWNSzp-5@s*$ z-UV{lD~w?(dx_qzgLDwRBww(v-kZ*zVpLOun+t2#4crG`(4K?7)bGU`cULtSsUvEa zk0`AD?j=n&8Q7;ls(16g`e6Ey+NuKMp6|w^T|tYwIA4=Z*qbeH)hD3`o`Ruu@%|yT zYx7n$U)>N`lW?DT&)fCc+to7`E~vn9F>cy{q6eD_JX=te@^W!`LW+Ato_~q&;7>6!rBKi_SAc; zpmmM4X-Ms=yp8cK>H_9aNdCIj53ug&;lBB`Rk=fPOqVy0+w^QJ983R-lpsfI!_6Ph zd2&biC*h>c%^vX9SxuAHH{FzU*z#Udlk}Yl_1^1nW|=GEr>5lAF3-OmWABag!KY@L zJRZZIp7j)Ddf=Qit8jF*1nbN}ZEAWm0#(~<%a%8o1(ex}Gi_Dw6VSr*E+$^LxwL&d z=w&O~Fm(nZr%iGLPL!jxZB$r5J~5U(&17ZLB< z;38U2K{N0RC8@q>1Ao-RHa7-!F}LFnVoMdED5eg75L=2{@OjxYpO?1>ev=nLa|9&e zOO^)}EG%N-NZv2>LJnL;b`<~aBKtVm(R=Z?7CBaZ)uxczcp-_UH>ZeO7z-}$00?s| zn?9(v@ukmR*Yw{Z*TmU=J{^+>mgvB!nY??ATM07>q>%?2Nn9mNKU z^np=tKn#E!2Aoi?$jJnb5q5ME$7d}v#&5h2&JxlOB4hJ}=a5z8CKA6=3_K^g|4<86 zDsf~`jl{FSPWm@-B3`XERSR3r^urxr?J|nvR&}U{(#RdgnZ`%jW0=`iV#rz$vJ%sB za@(eNh65ub(^?$r3c`vFS&P!Tw(pSzhA`M#I%0K?!Pb;CDY<;!fZG@pkk(#5VEF(tmbJq^v>wP z#{I0Rw)&-MY`qM+owVz#CCQ$ zHk@4qE(05dSZa?Vth-nm8a*1DLLew?yFA;P!_8YA9~^V(?L)fv>3v_Hkw-cfSi!VQ zt^5(Vn>5X6OMTwJ$$6v44IgL!oieVpa^ZX_$sboVWz?+clgG_lSU#h4^3c4z=mQh^ zA_&7oMNIyB6@l7N)F(h9n~o|z!N)>uCysV_IMOQ0k@|DI-$3~XA3HIm59W_)rPHR*GR$ru zWAd;ArHgxw&NO^+{?W0XX5M7;0<)#n%4}`6F;hI9Ftw?f?_~Z9&P%xop_PGE{#$*w z#jN(OvDSKSH-{w5N5ix6UpO(7obmeFdoS8z2snQF5|Rblo$NW@Fgl`;au`aL8q2Yc z=|W^a)16MPCuACL*M0raSCxE`1E|DUy2JFwP@>5k(6LIw{&T1)Y|*IXMIMi<>MF&4 z@dBpXfHXE?LmNp*(sk3pYnoL(p@eInb<%ZLqrko0&bZS`ha9)d?QuVd3y^gikVY1s zi9;kL>AE@K-TKDE=9Yvq>f=3>*0&P0ZUfR7FVEPdnRHzhXt%x+mp(poYkl{++JH1l zppS8(b<+AapunxK68gA*>>qFOwZ4ZyvrRfO(=BL38=_7mnV%5Ua_!?!?2~vFayaz! z0V>@IxlGLfwd!BFXjZ=nIo=BC#Qrh8jO^ZzWv+3-A$0Zwr;&3mgET&ezBfro(%U7v zhRfK9gO-lMmMCwA%o`H)!;>!+yjF0L;7x+Oo2T5}f_%my|6RdH1(m%M<M`&Wc;4s1Qf@=IwUm|>&V5Q(yWlRt7X@Dvq@jWR<8Pe!C&5}lHLfWCMEFkyO^z4JV+0%9iMvU8Pr=4^VHyC~ zeuAL32Tv7V`2|ovPxz&RHwms0{FWds2-NqGpz;rZe?s_Y1a}JV64Z9!8sXm%{F9)1 zT^D*j5dM&$wg-PIy!xHVHHrOTB6NhC|JaI%K<^If#V*zmkz@y;W##PIyirfBK&{NAFF z5o?abUx`gm>nM{M_be!L#5@My;BVt>$7zx&W*+4rdGhjCU_%&^pG*&80XY5G~oQ=cNyX>8D zxR6ELJDWt?JEKF?yT62O;vOX_#^5XCO$oG)HggN85s(Q_jHR|={7fR|971aqF=r4) zlFeMEH!9|#hpm!82|Hp=M0PA?bmIB#wmfPvcbQwZE10tjeZ$r~2hSqT%~+m4{4rX_ z0#ikU|EFRQ=Z1s_JB6S(o@(7$*SqZ8A9a$RbDSG)|1k1t;@s$8EF{&BsS|Jv^3}*o zk=G(`Mt%%gCw7qcI+VE$j>A1Le`1H@<(L;`aeKs_dZ9~gTni^ zX2|>%UxZ9Qb01`Pa`$&H>O5yG7fD>qc0u`EK_y718E) z9nq#iMU7b{5p6zE5p7nfh&H;$j%Z`otWgndjwz|zm++17PgK;JRVr$Y(?TNJ{7u!} ztD@7`k!tR>Bij5;DF6cnx2=hBZ$` zzsL7S`oZXjmuTIAX-;qFv!kqJW*~q*-$IuMB&^*Q6Xo$n(i2!i&zsdU+K{Tvt75)9 zJ5#WuiuTTv7Dc2ziQ{d)QP$U4*UT*~38}`)7W{QEr}8%0 zZA)$Enp`-yoKuXL#x~Ud1rcKYlWeH&x!)_tEg$H>*Hxjwt&f4RL#U)a z{#LZUdqL|qAdO@^|NhQZpveuWbL$I15%-V!5|FjNhd{GUIx^Ei2>nDW0Z)?o2|+El z6+6kX(n-rbivk>~`MUf9*fKLU1JtU2<)T?V402jGdG?R#Wn}k$bi)oLp^W>1L+I=W zP9tvDNsFP6_7$DZ_qp=OOQKXm1 zEdoXoKa+E^p$=esJi@AnZQv;3#|m;jVEqh1p0MN>3a$`bBlvB>2L&G%+$Q+6An&)S zN5AX)n()fjhw}dxUcJi+p7+xDX7j5l&=$hi{Ms4^*cO;jg{9F>Ti6U zmCY69$_NJJ{T=1H3HB6B7t9h=zgx&<3!fvHFE~talwgtIc)_WHC4yywvjx@f9QrGT zUo5yxuu5>H;A+7;1lI{}6x<@XRq&`_GV#PV=l%?QaypxHzyAHt_}$_0*bY)-o3sBe zM4^AFDkhA#GDqH&QdpbSbJWq6R^exN)OYx7_2+GaqiU_Z#LsT24>SZmZ=0Ndv}FL1 z-glSmD6DOjw{=H;t(Bk3*zdbjcVvZuFEH|lx3AH&yr$pN&^g=Nx3IQf_rlNC)DJ(} z67S!(8&18WYGa2N)^;BTtpgH2TXPgG?+71l8GAkSw$6KYN4VAsEBoRPupyWUUG>lt2fdlp)n+(##g0OZ`7rFwnb2_^ z;^cn{J>6m(VlOU4Uxs0S+XkVnei-((ur`&NHn-iu{&3HZ?~}K0<_=Fbd-V(=;ortc z_-0CtHym!2{HfV?S6+InXL9*{RkOj&Y*y3lDV9EyOD?{qW4P(3=9MLjV;W-m&e$=k z-7~q+Gw$f#=2KzG_Rk-BN%+n8ALl%&4wu*Dxn*98Kl_n60k{)`5gFd@S@>(2zQ<8( znSl^EPk+$fzN1;;iMfRp9>2P5@tp;4;Y?O|W7LFCPmQ;T=eXtd^HOI8VlHQkfS=nF zJ2vW?v(W1=BA9^%O2kY5pXK%PRJHUlZTJUMwa;stygBW`q%`7zaC;@58nim$&BOm&Sekh5(sl7JHrVhelKN?w}??)=-w@SbfQ|WTt?Tk~F%C|&sXftc zJa???G^;E7ItIrrphf_@1w_~tg*=f!yR8-K)&{0?j{YQMkOW?ky?71^Rg)@1wv5V~ zt2ct6l18@nQL1PxffBZ@JtE7yRwwb;d5m;N6=|mu1olQ-$w_WQHjT^JJ*ubu9Pi|k zoQMnqKcNKK$FI(!Dze$j&{U-){N)uHZ}1ZMTXBCjmDSYmF$Oq2;c46n*)%2-*sKYz zx&xAvJEVp>x9rlfnnl+lCt#F(u5uKq#Qo&$c3O0O?4i!Fhq~r;$>|)`Y*^=EUE{v^ zqD@Dq2mGzLI(-vZcc-=b7tc<8PUoDi|DU}tfv=*-y6=AdlDsUkF9AUxI}Q*M680z% zpxGf1geWM45J)s6KoSH+0cCR;hizn45Kz%!90;h0dTkmxqL4x9ff9sdZx%XDpt?KIP?Y!#h3KgHJJuJY_=mxj&j3v&pf|mF!FE&mE zZdEEG_7ouxu@083ak^`T8SEvduy-%y=DSiN0c>d~y*bR|+??hzY*AWjR{vDBJE<$XI z$Wy5f?y~F=mc0kjUG^jB?y~M*I9O&VBD?TPM3&u*ct0YKCzkyL@e4$~job$MNJiu@ zN-2o$;O;N==9;0N70hp{U4Y5SCUYa6W&s#Ztabhd2hckjGojG(%>3zD<1(iV$ipW=PL*Nv(kIu7Y(Q66W+M?1CVJTirw7Km7i{P{^VvVf1Iv~UgJ<;(kb=)N!4=@zo~ev zyJxe&dzNZR`|eUn`YC159#>tM1E1W}8sN9O`1|&{B=Hh_c(_TsCf)hz;TV4tt8cQ$ zgPos~H?^oRfm5ry;O7$e?=0W)Az|ltf<9H4a?Ks|ebnjf(sd|}uk?_%p#&uu&$p6s)3Um$Vt4R)%pIJo;*T?T-F*eo z*J1KwYClP%UWD=|-6&UD56D8#shrt(sw+p{deA_JsGD0Ka2TT7-wmwDWzb?qMYC}O zoJ3eKO3?YPg6^(&JSxQFv#OW%(LHf0qAml`xEV%21qnJW7rNVDDhQ?;uyH%05VgNs zAnP&^jg9aZ?=om{4$|EI#={@4UG&G}Mf>|bWL*ZL@d^r6ucV)sBCUeIhR*iUUo}MS z?_S9C7mvvBPjIRGToq7c_~G8b zB~YE?&Su{FZ{VN5Ep!&VOt80LsvsXDnQyFMj$oeP4T3id-YU3KkayoKf1e@(3SKLyemlYWYX)`T^+XKBxsuKcA@$#hzFPEqM1Mr|{i3Vi zPLTgq(chNz6GZsufxzEhc>bVYwHh$6DRrc)Z=@of>uWK+huC`)VIM8_@q*V#dY+`; zDE38Szg_HiiG97`7D2Q~)yq-N`gz_Xa{Lkfg3Sfn2(}mOB-l-`k6?d6vKRDox!^>> zY{7iN0>K*v=Ls$mTp_qlaD(7B!JUF?9H73ZMSouKWkK~`1Jd6X{fOX)f}aVN3zC~- z`=bSG3Dy(jlPA;lZ+YEB=TjiHQr#~Bl=#!X9Zsn44o%Wu8#g5 z5!@rVSMadl-vz_DT|cAWbkunQ?H?)qoi3=(7wjj|L&r_7*ry5>3eFUqEjU+jzF_Eh zS|#?-akW|OTLjg42ki+RZ@VOYkKkUx{eq=}hXmgcd`s{h!6Slt9R5r6V}haM@`Tt8 z85dqbpJ0q&4MDOc94CIk=7PFh9r~*t{LL=-fW$@8^4p*3H>-{bNnQLZoO!*QM!Z?W zt!I*g)m+ zn8V6VpE_23-hImGovq4w`GZi{IQ+Awo41UiptD!QV$L_wOcE`LU!&jCvU%u$IbQDKTiG>)isJ$g#2VWeXvOmeKc673OI73$!>)1>dY zcKr2v?Rb*ISb3ko4#cwk=6YSbYq|JFs926TrzQBWN3u4!b^1EHnfN~~jeH8L?c$Z4 zg*mZ71%(sA^qoQ}TkHU#k$;Hw+x^Ksuc)|wyVY-?qH8O%ir-`QcyQ+Tsq}2Hk_uGl zcU>Q(!nNF}xLQah6YqbJr9-f{)3AhjPC;Q#W`SLlmsyB~MGE)}gz&J=E?1kVcwE&7 zr>rp&V0X_4(iJD{3Y=?meb@qdCF`o`PZ9WWcf1kPhfd&frTLW2_p^q8xH_2tt;$28{`}5-Z z&i%yg#V!o^yB{*ka6B-)g`KciJAqD-al4?-HxbU*2Ri6{yJ5gCn5ylsAzz|afZ8>A z3N16)hsJiHAc6aX;dw;&cEn&i*niv(h=J|E?qt1z&=ZAtJFA1Pi|E{KI4NG-+o!@9 z3-#MLTFyV@?+ZF;e_Ge*wx0`*mfIB!x>p>F6*zje&OICqR)wBp|8QgmgQZr}ck3J( z!C>LFX7(}r+X>Wy!BVMiojn)~@cIA4I^=!OZ`@wab>jBsie4!CT+w+%ody>c%vZCcl2|+;4;D0f|?KCF8VGa&UJeP_Y!f8KSP9{Qqf-%{U4$q5&dJ) z|4&fyoG7n&Bb0B5{-Hkx*25!>$a@@W`J^Kk&>L$}3LE$&*#I{b!sD-!Z;x zr>gRb$sb4<`tB@gYfrSXI&{2w+19>?N-niMEjA+OQu|(eMaqE^t3{H%8o7qq z7XuHJcw2CWym7pa$Jfkgdt+(K9m_uKuY9kzABXQd$!K_uX@>QHk2m*>F0GfHn!V|`75yY~Z-=)h(b72kYI`ND zp6Gdf-zeE(_eZIl?dR>+vaRDMlSe~)+&*aUM%r6;y_^T(d7b?rtk2sI*`sr;<7V_I zXxowJ?na~fZY_D&K5ToA*D#jl41;}-{i6L$_T$*@(RO>=LfsQ!t!ro5-ozEK?y=vp zA3wa?{8+}@{}yQ9=+Uv82tcJyV_0c2hgLR z$1aBEMP4&;F>)J+KaXYp4-b0QS!-I2uRGo=YezS>9|MP}jtPuMoW;y}_;2#$#UF%1 z131j39Pg&DACkafl4Qi3Nyny)lD}dRD<(`JBPV43XRuJjKKSzwpFDexAT^OVJ%bhup z9!H>DGEt^{BbBv}>X1=!&z! z*-GbPCbPTQ0hrzGC$fhj$1{%(^&o&pBs5iG`gFiej(9z`eIYx>NDoI@mUk^Ef;{RS zE0Cc}kcm0MQEPZJbA2%PaOTpX69m&3L0}FptQ^eAOJyM7HXS+B2u`b)asa9jZ0hJ> zQ%CPZ+J3}V#!PQ`t=UGsI_+AUM!nj#X8OW|a!f#8AKbRlThRJqwVA_%%~3m?6$a}| zYYMdwA{IU&uuiUmO;>Z-1KfJdHm6LV*wmoEG-M70I^rC6og6yfof~$#^hPR;uDtxG zf6saBY~4nH2j%3A%E(PH90YZBda5wEahdr= zSRBJ)M89RC?5W&pC4}cWTWREbO?|CE^-dj-H!*AG>6RG58QMt)H+~kAUcd7^S3XNh z*PkD=U7hC>_k7pp`iKYeB#?6Idd(@-c*6fq>ox1niNm7WaTBv96iptNlQ${f5IJMQ z1gxd)=45m8Gu>(i7TlhkRp2(AYRS#X%hDb(&)$g3%%3tP3r9g5mdlRIC@h?wGoh%k zqL)c{M1PywD&CbhFF5}On42WXG1yN!=u>zK49urPPvqe+Y6co?+Iv>|BFyDozkdG&SIyR9Y+Xd~-o zecTRWKB6uI(P)ncDnA7YI*oU675w3@hqtZt7lo+(-3(cmfoKeaKjzaxr}2ix?QgHk zUkuW;zZH;m8TuFpe=}VMEiOTt+g~Z~%3x#rcvGVNZGg-&@rVq6#k1qX+6i=ujDHZ+ z`4+(WG}v^|`FKlSzuupQi;s5cNM z!XLR69dx}!?Djx7fzF7Bu|6!d5ZNy^5Lu_&Ut1WPz@~%tr*(~P`?=s#D>9sHT`>F@ zb6(je><=ff$Ah6Nb6)ErJNty^_5fcRyj=)RdDW+CtGkprj-1<;Zse>|E6Au)J!&1ODw& z@MtHoD#n5nor@2YJZ7cpBDBEW=IA%rmEJYh`Xj^<)@%<^! zm6;~%+gdV~TvxNm<0m@|>g)N)3g2WuRNSU?#&)*1UUB>4$5OU{rQ2Gv$u{}rwZuVv zA1c0(o(9z|Zdv>=IJ2fUwPn!i7Vj!yu7^{=23lK6>e%LCU20?Tk%KL4&njzm*xaYe zjcuAoTWfFo?mU{qoOM)3aRo{Z-(Nd-JX$a8SggaWcr>0kuu28bBbD%IaTulyXW-Fz z)^PD?8>!YoQHMu+5h_lFP``yoD?_@AN9&BzE*_1nh>J(#(R3d3Xgt2iqY>G|-@>D{ zL>5qLgw{$N!7Je%j<^J{Mv1AMTTfTW3qv6A^bAUkz#Pt`!eCxr6#~Hz2`m$VIY_7l zbB=&D5NbdIp+<0;Uy)E_W3iIJO>C*tyvunxeg+W}4i5v~aYX)r7ONUPQrEk=*DNh+)Po&K9Id@0eq$eIP#!f#5VJetobxV}i{Y$>tnE#H>O#hdv-` zSD{>*_ElMWBY5$sTD|H&|LNmL8{B#?RP_tt()6OhRhWuMF0Fc;H7(9>)%08WaiG)^ z7fc>^-35pDfLKzi#Qr2p@ctCUn0h@tFkdh@r4pQ3=(4-tpBTd`v**K%MCTs-bi5c3;7WM0 z-rtiK`vt7P%cW9y?ySg9=@TE(IXV6~?}C#@&_SP$Q($nJ)uKMvxC~kh<;D8ozI!|p zc|F3ddw}N%<;7mc25!=oy6PJ5l9@aWWX1=&GFRGI$m%|cnGiPP0^1WlS+5U~+d<^B znya`m8jbS9rh`u7vz^=D5fBKxX44;UJ+!}@A?q>_jqBi#`E<}}p}g2VlReQjTgHfoi$BY3S_;EI}x!9rUFzbL%u|< z0CoEgxMU{#(bz5&B$pCJbNr6y$58wlwrL>@v1T`v*4JrIt8FQ^JH z=Epc~5-1hi4wp%Zx*jUO@?y0Vm&HEexxFGU7P11b;>CCw`~JKb#}Rp=zJh}V(*)B6 zvjlSm3k2s0E*AWq;9Y{h@?z*;oOiw}FP6!EMES{rGX$>}RQ-?i1){6|hrV3&je_?J z{!wtd;Nyb-Blx0Vso-A)|0c-CW47l%f?o=LBdGXEq=#b+Gv5V*il>Cm$1K_vUkPj` zdMiObZ!=xZ+ySPDZVL_(94n8;?*-QhZV-GxP|vB; zeA=U8e@5_mLCvSVE;=p|-;Y;QtI(dASL+xbpHx*|t?)Fw+QMz-QnTwk+gf&;&sgeR z-k{tZT29~sfx?L}jUeLerg zFvYiBJ#$M*D;x5OLaCk23dQ7F-gTHmfY!^mZ^WJ$UeK)a6+fSvEJ)SX=v;Wu%l2vTK){V*~W3x@PK)v%_;ZZL2H$FjdyCz z@!>LWt)~5OWqjLJ7yxe~h6WGsE~>rGo=$5LEvf zBM6c_(w!U!1ymM6osGfA1?%B`f(p9PT)LA@Rinai(OM%vf%R)dEO|-Vs)K6hNbSnK z0FD&}u)>8jc)CtbIn|5Nq?C zLM#+{AZKk4-yEw}GFZB1m9lgW0SA_e>p40T)V@0dcc!^;?1G=i^tDr0Zmi-QwyIHd zf!_qb$8wG5149>s1M_tJ91r74__o{D^|7xYn}-aN><3`Ao!8s(=TL8n~<-R*B=?I33qg*5gH{mw(wWgr@l!yj)L zbkJ!x!r=Bd(dCcFi}uIoQ(cBWo`XL=)9Ii^KF_-S6~Z6e!|knxsQvMsF_wu(WN3)F z3=e51&?z$V=D?kAKb%#@&Fw%w?1HHP6*{63iCO__*U!3SCTAlb4{;szxOy4}_jb(2 zcCi1r9S{TC5z5VNK%qlO*Fo1ybPW$937t_DZf+vR>BZU^Q2TS4l<2mf3vQ14Dj0OH zIF=t{&KmnQI9}P~!BCYsYju#FeZup4MQ)Cl^^hrRn8Xl{yl3-{>Tj4IJRFKDRJW18 z@^U}h`D&TmPdI03UXJGw>P3R{1s4nQJjV3pf|~>%5PVp$Sa6>ppI}(-CBcJ&q!eg> zTab^@)Q<_43!V_PFm9R7$9`fp!CHcRYNx%iU~|FNf_yG#da__|!G3~61xE;u5j@>H zt}`TE^KAQ86-?i74Nute|~!RG}J3ce=zmf$;rWESZ6Gr<#r zJjv3oj%Qp`cn+b?K;)T>sQaDgiOS~3aUlSFPU_6>&?a{2QdJ($8_iY(=f^o~^Bo&@ z>$dP^m@?PtGs zbep~JsAp~18mr7x&vTc>_fx~im3r2B*N?<|r{Q>Swl!K`a$(FdGtw!4#lhaNw6=}q zjvkA*b&b_#i$_vkD)(+!Y~OD8D1H36QN2ScJp3V5wGq>TTK74))K0Z)+6Np<>#krN zy&KGqkEFa{H#*qjodam+6)MfQJ)$fu3Z>Vw?WWp(W5)}s7vFH@VA)94vi1t(b6WGa zgKyY}kA|;`Si85}nEQ0Ou_2PY;qThmn~y$izkQUR_a8lIKYnzLy$C#_I)2pd^_sar z^HL1R{mM}BAKrf@d5HI4J0Jn?zmhz}`>!N`Fj;RtG|M3mN!Ve5zJ3H>SbJvkMT7%_ zFTIlLK$ezFGkp_O7VrNkqqnIl=a7e!krJ|oA8%w#o(-HirbIIxs!x%J{U3zh4$;?| z2?GY>|4gcnP#wtBl~hks9mH~vLQ*$Ordrm|dFfS&&P%UK|Jy~W1J#wmFG|ym; z%6@UkLzVgsRFH?v_`|>SiX{L|+-01@mtNHw$hfgNk!Lr{xbXltB@h}y0_R0&tHcrO z0L~5XQw1XN1rmuD_{k$);7{O-vUp#%aSN-OFRtU~t*n8d5`8z18Pv+^eLvFh40Nfpr`0sb;6j7ndGg=+KqsnqZcfK1@^DV6 z)_i{C0^h=jMd6FXZuQ<~-R`;5>{YG*S@DT{>$NazW?`IrnEv`MtUguhvt}z8e2CzH zR7eukp!3DUKsj6znD2m2gshnkp3c?njO3e*2Z_0m>mxD`BkQvfUBwMPhwvFn2Q8++ z;P!U{{&?F&e{75PHv+OQ1JM|R4dSz>4mxcj3|eN|f06G(kIofL8xNDa-jTRRn2UU@ zmv&um0c5wo256KYHXU?YJ`8SuhwuP}O;P^%c%%I-gsjUzG`hkc^XZ_|Zid0_?}*DE z=#+rJRgiTV`WOIz>^~i}xB>>Zzt7;0`-$5NDlOn|Gh~*DM`XAc&x)1tkAFg%JKrEU zCwHI&(-?OlVi!!+_C3g#s1+ddFz~KJ%hZn{Ul$4z*nbQM5Z&8x!qqPj1KUBK4D|*= zYux0yr!VNbh_2yb{0jtMDvYtP^R|)oa{sVSx4&ctk`LM=xR;27;CUka9THvfchKJx{XW0NaV4AlOAPS+KXDVik~osOTdE6%7IV zRibAJ<_K~evA)@Yw+Jp0Tq(F#aHHV;f{zOB7JN$Z&w^wK=wJ0W@Ey^Q2!_sQ{6g$s z3#$G{xiI!0kQ4(kR`6oMW`b=6;{{3EFn=$>{(^%AFBiN*aJ=9|!Ks3Uf{Mz4zd52W z6ueDPaY0DGTXeE7tp7nlK6O&(<1O(C!SBkO9+mQCf+Sh!_oQG1E)vw$msEl3xW=_n zk2iF)O6M7w`Hlhn)EXo*PUTVijr(Y6Y&T zhfzi&`+j2+7~8k(pVRPOZ>J-%y~^GzO0YM_I_nA6u=$wka-`kEjCoMcyOo(P_V z@v1Xqy(ZsuC{_+FdQHAg%tLpc>k9eb7uJZ$zKD;Z1)0i!GR+%Nn`x#mNoDbFRYotb zm3Xa~he{ad8_4o}VLXPdDJD-n;a;{o!t~+4$z#$vvWcdT@6?+EUV!XJ^zqW=Og~&q zbu<2%gP6*5zVqdgAtewGBSy8yKXd44iYSH;k>DfqX{>9kqvAvJN@e4ankXs{Q>aOz z?uQCLm44Ly9IniF4!%>O&WD)N$oA@h%Q)^uQVI1CEn}*0Jq2giPK{YlAq5ec9tG@k zM8fNc$Ul2Mg|{4K=6e2E#fp$0ra*A&Q7k2MfISRm93IF8p&=spN`jN|%3wxbr~-iv zi!$!vs8B&?bK7(pPZ|>tG1rnCu^TZAoHm$5iq19-C-Bm58Pm=66r61;FkRckOQZ_i z9zP;x7ZOqs-LoQfe_}3XJtQ?k#8gT`A15czp(-$$n}VDK8xf8ITg85$4P8P|muzDy z?*vq!M~{*M4pr|vsm_1y4IR`HBF6hr&+A!=`r?v_eyJk8XjO}|rpMubv!q7N8#lYc znvrZp`>o7mt8tuF6xX9klV;tTU208)?zf7P6B90K+Wt~&R$Qz0)~sZ{V%#vUakI9~ zF1-|qRv!3CeujETn`W0MT%Pct6&+^{yvJjKX9U^SDG4(a6=fss{N=8v7kvG<0^2yP zQzE(mUGbe((fc;GF}UZ8w0qSCa-2%gpEk*voR>AxuQ$lh=q(;T8S*$OZC1 zK4qTboiLuw9L0*9q8^~~X&t~+e1MheET%m&&`7G!5R|tQpNTffuMf*#Gtjj<&cHwHVf`SB{mIYnQOd5>) zy7ycLEoLCiUGIK898~sQ6W$N%GW6FT&kKGE5_H;B=x%?9aOH%{Q#eIFW9l+=F%15g zPY0cL3k+_5`u%103m&Zl{jwUeE(6gR2Y(Y>1}**`X>Nafe_8K0@>IH??}N-T@rVph zVJEE8PM}j{+$N~=T>)p)VADb8dmIMrf~ng6Jn|)K1*l!W&9HM(W zPPqEH4$|~?)P#(B10e~84hOVgy{zB4@o*B$(YZZgBqza}ANs3-$U5Erx}ei4+YV%_ z5cKxZcrG|awj~&JuQ-+;gHx=Hs)B7`j|W3lI7Qwj>Oem&5!pvP*91Al;MK7riI_Vv zXU3HLi4|{3a0}@0csyU6&HP86%g9r4KN7nM_7b!O(*)B6vjndZyiV{Y!8-((3$78o zS8$8qp9FUb?iGAhkmHs7#NP$qC1N0cDCwVw{-x-lyj>0S3-c?!2-uuDwlhxbiYJ0y z@j}2cV!uWZZY%I4yjy2`xZj9=!RCT(1ltRC5lj~BD>y(fRdA#r=b6**IKgbeT)`s2 zS%QlNRez(L>Tlpmu`8Yw`bN?D>`ecU2<{QwEBLG+pR<`SwExKl(60I&$fs@Ud}1Tk z6>K1=`WyDvqO0jo&=W-`FU@j1-w+jV3e@i#^YNYb@q(NIMg3YqKF?D>9WNI;pYcq* z92o%mJ0SQM!B+*<@%1e{n(h~#6)NY^oCW&=JX(U^AFl{A=YK+ce5X!e(2|lmbg3$j z7K?F<5SFAMuwI`D9?iGH&M5Wb`?tRCJ}_sP8`rjRaadWi-gS%1VmsPaS<~L+(0oak z@0fva;QDfzqjT{$u~u12yLR!~2B3H@Wv+&pS649=`VGv1)D)D;?Owbl)>GE1Ut;lL zl=58aDQnsL2-vX$MooO*G!nlOvBV6=M6hViyHQ+Qy_xm${+;3x?2D($b+fl*&Csj zgEW25sGQz^sdC;ty7hT^3lc`>mb1KG*sU;t6XPMTd9Xs5ga>2&45p8Bi(NbzPZj3C z3HYCh=-WnB@nFA$BMBJsoew9Hucg zm~jLQf#6U!@#~3xM7%9a_>B_NbfM5GW&4e&S~hKGZHkar}W}<0gsA|QU6ZmZWKoooHF*) zd`#C(AUU%EgDf7F@X>^m^IeR<`?crgd^H}&I`GVwQmxMXum#?Q)*{bhb=p50PAND? zO+A485*DWWsraO}*ca@7-ZL^JA#(rdpr2fO!=Uz)B>14DxC~n4{2k|3&&k*p_dZ>a z$mdDivZ}Kaf44x^Wgy~XOz!9IVA>p{x&1YF`HMlC z_DBB5?Qby>2DuDcTpHpp3I4c!Y#(nowZD5IvrIf9!>iZ{mGMNpLc8-_i|2=Fs)X~8 zX^ea(1HZyGtPCr!|932Y1`Gjp(-j@H`QZm|(E*4ud;b zYL5pkmKvFEog*t4tdIv03q8R;W`8(=S};`Q-B*q`_6g4!A-quN!gTsv?acGQ{$uON zb8z1h>k2j?MxXwB4ZKBU{=R~P1&0e>Eto0D!OHySEB~YT2RTUi+|MygRQ(6!{-f>} zY%Une^K=q>H^JV5{RC45M+&O`gWt)b=Lt?1oGmz4kk5K-$8y0nf|}pCPxJ=`cM0wh z+%I@Q@GpX|3Z9AQ`9I00_%*bH*C^Fbg7pP26l^M}=F1`fx#oR%P5rj-CVV38twY51 zDpvI1O`x;D+ZlP74xOsZ!@Psz4xs`M0}dvp-TxjlGfN}v(dFJjF~?7K?DJ_v%go|W zV}bUkv2kEwnrDU`GsC={N9`!uj$DJiowLBtAiah9-?uE*yo|XTmLhd*ZgJmFBU--~ z+q(}vLhj$Yk5$$pE3^2j1}M{P4F98yx3fo;A`5c|S(u21;DYLWWsZ5a!QS3oV)vvN z$4sM5pX#Ol?XX7gNwL7i`0W~Bnb)rP%1rIkXl;W%DQ)_EesDRsn3_`^CMMH<6Yoi? z<3??+a4~66cySC3p7&u1thYv52Fs&80UOp^BT<6&*2u+pW^%wNE(S}l{gsxN`A=~% zSXXU6OE_E%mR`FHns6~lOJZL~`#F_UaWPnW?T?P8xEPW(vh-TmT*?)>n3>2b zT#UZ@nZ9>u49-a!Kvi)u(;!9epsKhSb3{}@(GwkDJF);TvSdT<`|KQ zxd=5QrBWv5+^(XAqcntxajCe`s>0VlIif+vsEZ*xC6t)q=@CTBZ2+E;AQILgdT}4) zSMTXXDH>u z)4EVD6o;zZW7+IGB?XiV#Z@Y0G+}cvMY{zP1fvSv@=l1D3gj4M?ygc;hZFQjs!UhE zIh_9=(^U5!RbOXJ(J7`ge@Ez)c1@Z%6iRx+Wt^zvuqp9P+BIq1;nFs=3?#n-Hl>G^ znryX8?$KCLD$|-Z#=M_Pe?U^@jO+-v+jUKG=B)%+lE6%sQ|TColQ?@`1unU0+D}ia z1PPwga4BlFv-5#a;k};w{l7-~Ufc~I1aAtefx5=SrhPN{KggHh zGH8+45O=-JaetaB^|C&02QeQ}mw{;bk>IBwL8n~{-R-Xs*Ct+`xE)c5+TYEPbs308 zPb4s(4m#~77~KBmyZrH3(f(FI)@A4;6$#u99kjRv2DiTz@W<_A`>G*oe;XjPOgtjP z2JD0t+6i=ujDHZ+`I7MH&f75^biSQ1SS~*0KIBW(nSk2$0hi3=H;_;Jrq1>;>_>EO z$2x2W{?vBV2I}po2^sYUf)5+}T0jfd%la`y0$~F>m*ekDd`c&x_bXj4i54H936@u5afQN?iXw>cqSgDkL2qw z$Oi!Wxm@sS!3lyq4=}w*aJJxFLEiE+o%i}gKB^J#6?{;T&yBS6975bB$a4kt7X{Um zD)hgJ{;uE$g2x3v7d#=zfk;2pyXH^M#B*r>b?6rdXsq}T+>`P>R4jmX zCZ3~XeARglA1^8{ozB;!ll>;CN(( z@t3I8nG)3hsN*M-TH4-YrWIyK9PagZyQToV!xkFbXJ3M%GO9S zFAK9&5`+*0apN5z|4N_`0`{8Y-S{Jh@W;=uzNr8$v32sxf@*MUbeND%^W zkTAi;tKQ<`Q;B+|i$Y7K%<`?LFwjwA)>9aXh*zU{p8C5Z5{@B)gPFaa!q<*6bA1x3 zXA?p=81gBYDnnon(-E4FX#hZrr2p8FUt{>wGZ~ zrXyl;Cbs@X#4!A>0AhyXTPkG~;RvE-%rMte;PA1GS>}2Q&X&#cxVG#{m{nkhvg`P2 z7tv{aV0+ltyjZ*V9QLiPOuX8t5QqOg5wSv*((%vnNlk5?GV3ElDfs8s)eOd8#w;3V zjRWlYDy$0ivYtibx2h#~XnsYb4sAN%{i}2=i4(XTBxY_bHjT1-+Ewu*xV6$w_ zLVTFS0M7by3oZoY5n(ISXj^0YwfZ|sl&t`7T zsqbrXhyVJ%mh?4FBr3GRe;=ZLhE8(Kf&V%mFPoIZC58FiXIgzeZVP*)J519hOtxJ^*!8wO|7bS6n-zQ+-<3#RI%y~vlS6`*$gl1patXUNxu zf&{jY;WL4vNAh}|9t{66G(7-L}}M?!x!5LqX- zBM?&2X}l5BLHpCXMz{T3@J4J)Fz8-!Ea&6v8r=aRr20m$n>y zRPO}>$BCXTm@8N$I7^V^1+C)D6DfyEj83UVBB#t`e(7lD!)CVfMwqT_xTYWaNzFbv*cZW7```Tkcr)VSnX& zwf#7JA1DcHu`>JB?Cr=K-eM?9cCZK9E8%fBR+icgj}a}_AkByWTT4d6YfLjU**MaX z8)QAB=XLgjus&};WRJ#LQfBlhXxowJ?na~f9x8d)K5ToA*D#jl41;}-{i6L$ z_T!L7+wJjfPAhr>cetC-Vk!4gz=@`3t>Ge z-ZB%Hr)1gn=;a2)Xnu*atK9@&AM^M%wA08g~i9Sy_u4U|4&1Wyq{{n zEff(&be7du)^}lyZq1bb^hn>)yg)eWMykF*>OQD=kB}LEc;55ef0L6N0_xLGWDkeZ zp!K*}Mk=AH64R#xZgRxyvF*IW$I?^bD9iE?kroI`RO)a7bEpqdHZ#`;bMpci2%R8- z$Rscah)kE?5rJ$FIBYP_jNr6-=~$f{Z0hJ>Q%CPZGB0ke@cKe{t=UGsI&E5;M!nj# zX8OW|a!f#8AKbRlThRJqXG4MwS38__2J1^}3YAxQ(2@k!NivqM=CTJcgO5w?Q>IUB zYS3RAG6w=3aqgT>4xLBG4Le{8o(L zDkPEF*in*(SyA^`QIo96uUk3y;B%Y3_=(LZzctx6$x>h5Y}T~Zy{(qFvND&Ksv9%1?H`(7yBmUUfWx*#1u&3j5ddFtYG?itdjq23Auy z-H=2hJSt*Hq^Fj*j#<~NZ^hyz{D$U59{yCVo=@C!=$h*z9>{|}rJ8@fZ$ZSu@I_&Z zy|-God2TmTz@DDndRM`B6Qz^Rd+PLOHJ2_1`$-3{2q{4BUmbcP&owTC7Wvbex~Y+j zsd!Kwk3?Ri__#uUywndx)MX$V4}qZCL_va18xLK}Od0|Q@45_HU z(`$b#AnP*pF%JG_x(r%ef;6|kQuyO`vVFWM(f&3-W*Hu041dM5QXW%01P@L}T88%IE7#OS^_vFIVp$e=kdIKUjg%(6);sX}*ahwsm3HB1S z1=9ri0Kj}%g1LePg7X9y3;s^{-DVh!{|3;s8ID@~7hh z6<39N8)1;K{sbcYb`rg(=zT>WCi+OxuNEEERN#bEKcl@I_iXpsa)v2VPW3a&4-tL1 zpz3efc@Cz3o;!&=*Aiz4YR+(>=(h=^6A^?(CA&*StnUvRM?-$$dJ z>s}N2fKMb%K;-$F$VWgTpZJN-2)-=%ieNam>svTN-4At`4<{f!9s-A{vozHi=L#lu z>Ds}s!uY5;eFxj7i3Uh8@g`PK!#S82%}O{z6Eo!IZ?l$<`)IZ0Sr%XJ8AFb6(cDJ1 z$M!bEcQT{vFRuRef)mxhUR3^0-%*PXfDwfLHF&v*>R&HBaiHW0``x}P7w;vVBH_V^(C( zQncZQw#Anf-=FeanQ5}VLnUL$bv46mz7B)>dOotkH`xyrw<(>mo$akx+`jm+lsCZA z9V*#mn`KtCnK-ELL&X=;)1bP=EsGxpXV%oFwhUU`;sYhj^>7NA@IwO2L|_gQ zYQdZ%U=0LboIt1%oaR>~)Yw?e*t>}>b((iMFUQXyVzI5mfOj0R2C9iwjUK6MVmTzL z!29E-h^UI-bj3(+^a{ijv$)G7&eDK zAZk~kT$=V(S$ZRQ@u*t8>OcSK<3}6ZdM{M<3*pkvVr4GPrNycFfO&DC)RGotkGt-M zgelhe1C}DqEHGlE!O}s4-E*DrVR(;p)12Lk7^^i9#8~@Eh%sj!Er%Wpa7MpSVoddU zU?WLsRh<}9i;n$R#2A*NI=_f9-h-cx7vlk32`|Q3g*e&^W=$!~m;fxC?qIf-NP`)1 z6Eg}kjJOE}1%~Upl6(OBB`n$Xv*N|bBj}({$0;zl%*I40*SHK?4CTf8;J$l25_vts zt$cvz7#ia5Wt{yt!KQ=uHy#EpGi@5kj1OD}EsjMRxegsR;{w|gK3T61k=sG!vzjgg z(HMoO3H>)?;qb{%wDC@;pf*qM+1c+6;jyd>)~ z5RFCf$LC-jw73KYcl*4xo$aGP-j-^A8z8exJR-x3;Z@_su19B0bBd_{^uf3j5xZcj zGU8tu@+E2osM~kIB{SKN#&)3~f$d}1kLccx7;J~`7l?uFs0kVM20}UtRfQMhT*0dF zVt$O%CIRok?QoftsJD;Gue?|-#bvQicy6!Ai-j)PC8uiS#Sr{nbL2RV$Q$()94we7 zm@b$lm@8NyI8Sh~;O_+Q68x1HL;vEuqvz7`+)v#W93sdkAlg-b19=Xno+&t4aE9RZ zf~x!PdU^ZW2>&QfD%#?6ExXNUEcGsLP;L(L;BDMxbBBHL-|OqzX4AiXaq{|l4F}mT zmDgEfG}&7g6_x*y5xw1BG=Y)6Sf*A!1KUJ2IC$;0&b!MHWFYauNkZJ2*zPv0>!50td9bBo83al_2D zL&)98HjbNy2h1C7PPz9ETC2Qkyi;qA50`msHSLE(__hoj6DB8h@*oQh9^P35);7Bk z3f3QMMeu}iaAR#V-q&G4Gu|G8;>17oy+yrfnJ+Af*?bYvfZ&2=JRp&!4bx2DV3oyN ztc>a-ivSw^Xwsp7Us)MHS;oo_q0tDu>LAWyk<5F4P)UTIN=)P3 z>}E$KyrRS_2uBdT#%wH^#yvyFC<$92@OTINMsTWK%FBEp@E#F_8$pss2GStJspK>Q z{gaOi){~}l>PGVwSvK`~Rmw$cjpT^?+Od+h>Y&;=QoCX~9q6m2$~l5ScOdKts}L=t zXwG^HPH$XJ;26|1)hIuMh@K>nSkpA2x+H%zp$-Sh!b zy9#CIw6Dt2D`V!^kwF@x+%4BXfpz`TTMrOCMQ>W)oo}MwqKPe|S ztH9rSW|vNvjGdfUWA&V=@pGc(>f4mc zysUQo*m!$2GpIe11Ai6MbMi8Ciza3nf#d;VaNa=S-D=g>cmpw)Y*ok1wh9y6tej-4 zew>vPhskY1&Viz9n4ZmvZdVps@dLTKTm2)T>W?$zbW4R>IPO ztKxEK4oz3!`cPni%{oshyTFffoei~+T3~z5f}K0JtQ4MV`=l`)emi^CB|zLUfsp*-)-=8MJsQ^0~Q|`QSXp zBaxgD9wU@Lwu{eqx(r0)18g8~lXTE&<6zJ-({9BE@%>yKblMmg-1Q#8ReLJ(v0m24 z?I7kM>M{_G)o7HTf&`s*4Rp7^k+`ejjR5^cA!>i~AnP&^jmP1S`E<}}H^SidH__#f z$BXv29I`G$AJ4%bZ+msnBA;j7{tDrb+sF1*L)8BGt{BV2BQi9^GuK1f33Q5#yg6{^ z+Ye`zadSJ654&J0K!uKIM50!J+V!(8naSD6$3t8PwvXXyME7>g#&+m_h8Wn6P;PDm z3LT;Y3A$dQYj_w*=!~jxbNv3o#o8HA`*WF;=(e8=ZjSpZ7<8{VmLFrz8v8XkUfJWp zP?h!H>L5G&gy;2&++4`=Z|Z91oZrso-PPZ~H+i_ug6cLBdSB6b!_M?H!F0ha!Cb)t z!Fhs<1$i8?{9S^-@^a`8oO8OfKY%HMw%`!K;ex8ak?(Z89M2*2QzSTFQ1w6Ts{et@ z#m;L0^FJW?uwb#^K0!XgFyBjp2L<00d|U8eg2x2Q1y2ZC7`OBjAy`eYmS6+H#)8cS zTMP2JoaK`R^}M!zq7M}uAsG73>m;%BT1r1N1T{Z5PxJ+Xp}ZW40G8V#xJ_`U;1hx+ zg3ky(FL+S!HNm$8-w`CUK>wc!o)F|omUiB+eB1mu-S0e4R5m}3Z|`F%y)*N8iCwx> zmB;f&qcYrXIQK@a4ZW7$t=qzvd2H{}5#`?7&8`v4Z}(YCJ1ltQ?LB_7 zdyS6F({sl#dw|_jU!*;Z9jT+mwn`DKl`<#+w6TuJ!`|(SY@7ip1Ul*pBg@{)U(dJ9xLdL3CDZ0tih@(4^P) zyOP;_VdN+9(kqYq;7hMzGP(Xf93$DuB6J-kvWj%9);?Vhr@WSQuj`#5}lV` zmB?Q$qj^a*Q|Yk|%0=@o$Wd2Q#r>VA-#`U<$c#VyORsmO#QZSiVRN2|cy_al8`*im zz!3t@i_lhyBh~?&8{W%bg!sC$UQYM`5ky|keQ-o)A%s{hm2)^jok)$P{UHVd9}G}} zAjzqLGzj%navDLBN9yEYr<`&G_#HjXXAd$<$Om`SQZ>A|+~;;TZicp5j6E-Yi| zo;egYB1TXNPiVBBisO7ZffcBX!EPANZg>kZ+*sO&FSt@}sA?X?iwiF-cqKO22oAGA zVC`i7Sg}*jm2~ZF#Fccz3nx}190=ew5#mC?osM`9fR(_iD+uKgbq$rJH&V6ZpL%Q{ zIz8=3&VTm24kID|GG_QWi{M~$s<3L{^CS|T7iDAo2^QX(#rv|2TUyn9aUDNzWeot8 z=(~B$;8s>=UmPhzzxB4^2TlTY=<_f4wXyD>a}R8BupNOdIl-!VPm_z=x3`weDa5@% z=-aTG%;I7@XW+Y>&G==^5B%ZCMb$rv9YE23=eJ_dCpz(4--G4hTo0N|Uf=bSqFafXlx)&MD&ChhJ8F&wPau#M02Fssn$<4{b zPXmreOhYu{GV`ZQ$-+F*IJ{RJmr+7d0F7~K9&z#ng$=#OpD z{zgF7Wgr@3Kx*;XQwNm?7N%Rn?5 zpizDb5_DQVbhp1lc!0vDD1Uss(f$@f)@2|XUEz=UbkJ!x!{GLJ#N`k4N5J1I$hr)D z41hoOpAK4F0fXD$XYj}U#O(!@7Vx(jGRwpxGTeI_{_#&pbLSfb=j0A_U>f5tMC^j8 z+P(+*614(k9tPfZXqoyk2^sYULTlXQk!#RF*F|&< z5943B|L3iJEbP2(WWC%!tkdl;8Ad)y=%D>+U8CE6F8D|8t6<=ff z$AiH#LUra22J(}2gR1h=JVfW%V4v|iQGuUyZZ$%d4a}S}b#h^Ftw5-`g@NB{c|kDn zr`F`-eLvUa8zq=4I8%_vCDWG)?j)l5p9yj{2=(6xCJXXdqn+%ody>$lo!Tf4<=Dg3AO~3*IBRU698u`Jz37dx?PP=kQ1|*e!1Wkg5w1z3QiR)6ud!jj^IMU+XTsZ&@WjR;(dY-3i7Fwc0S$` zzb|ikRQ!|)l4POZlY$YrNKlU!RL3>0je5MHn^n3VkH&EAyE1V7sMy z?~mpgPt~tc7HRY<``>~cW$(Za4{9hU_ z{3c>@arKms78!r8zdyEb*?UEglpR5tvii3iGkU$)`#`zT6RYM~Q~M45;{Mv3?PtGO zo;mEZ9fiA(vR@h2UbO%JUd~zkO&wk`-uSHeFZX9%|Tc z=a%IBx(`fRc;kIpTmQA`Mk90MxO?B((C&{}>x+7Qa(CMs7OvYiqv_f|4|`@c+Ouk1 zc*~W~#lHLdtESz*;`7!8%NLIBzieEcmP?z=h*`34**ACIKIhZl)*k-Z9X&4m@9lk# z*SLNC`)zM)7&YS7{rPhjf7x=^qSPK=E!^>J?}hfuD;E@u|9t*?w~d{D^A#`Ma>HNy z-O{Q0i#Lyny7K0i4<4WQrzy+ljd}mFc{x2ko4a-1j=AyMXV2~S%CNbEKWsa<@fWq{ zZumd%Tx_pG>a;VR`Iw*OSe}09kACT&^{_tH%lg?4wukLv``Avlm+fZzxgFddZWp(Y z+sW`(S9`JzBtY}-Z<_!{x}Xf z9yu;KJ~>V~UO8?#emRa&uaWi7?w$^JUFUt}cyah+&;Hvtwyah3(D;lCT3)ld`pVqW zn%U9eb#7|dt=`*Ha$~o?xvpX74lgwNbkLU<-SUmU$?m%So2}2!ZISo)-?rM&dFv(r zoBC{X7nD^`wuljP3Nu?TxyO9^0tfhnwpszjbLf{uJAD{{DaU z`ex#x-d8{IXx|zem-l=3(`yFQx+8heaN9TJ+5f&YwC1wkrVe=99ufBBS7~Ew-GBK9 zy9SNkzvQFzHM4HMa&21evA3LDch$XDUp(&B5o^ZZ{^SJ{4$YsHnR@Hn6T5HgItlHW zJn^eHvpXMce9fjiuedh)uXp5LzvZzh_m;hx_m5jY&A)7lcUsZhnCbt1IJ)4eBWB^A zYX2$BX!vT;2cQ3OM)Hz5*G0bBZ|1hW;j@Nx*)wZ*LiY8)T_1HrM|_c!-D_dmx0#{izY+@#}fx*Yn1&=Z&*HZ~S^+_aofb-OFbdoTR~KnSa24 zGYPO!!g=pFd7A;8V}Ip0HwSo`_W_?9FEOVObEdpw6G6 zc=ynfdY!UFkX7LmkzrkTD=oe-{_GCN>T%HYZKCG$l4QXz^W5VY8 z*3=a9CdlF59rz!iR*Nb&O)A#M_=mQ6c9pAz5p0Zy(RT}O6PNa^vrm}j8)mUQk@00 zfl}F^=vfI`eH&^FSKPvyp=?e@^rJ>}j$vMCa?|;W;RT~1n2l6wC+N}nMTLghSm}I= z;({$KeUZw~KCJcu^^2807hz^~_6B>69cXqpFTwWIh(f0Mh&4#9^@FA6L8MNUTv)ig z7U>(9S$GK|SqU@6R0Xf32Nqnf3v$mh2MX3;!D1vJ)Mm9aA>*Ao!D;Y5HCFa^%V%8Y;9jXJ1h zAB_*8dMbI7tapB1;q?66+^p$=S94B%m+Pl}wM_jwQIL~2E;GMCeUKy*-6TI*6lTX| zvo`{BLe$_7Q~hJzdfQMaNl1lkkbhX4dp%tD4`cz15nLZbka7>-^RQabA!0 zPwx_I&FplqX)T^p*uGr{YgSw7ms~4bL+2b+|ymXf`D?M#$MrKalWc)-kyjPz- z@`_qz3$3d)!7EI`_#szVmv2P&?l!jfkhB45&i`>~S%pPY#nLA&b==^b31idpi>7C0 zjl}}w#!S626`C1b1-*iKTBk(L_sGc`nK2+;2!|Rw{$pWb9!Az@BhsI9fp9)^+%p;m3ECg; zHFO)8)CB|RK3&L_HWaeE-nUpU^08k0loP1;YF8PE#@p2}6V+9L7I_WVGV?{&!0)4# z)XSTDcfCh0Hq<&)tTzf#Z|@w)Zhx=VG7LX#I_R_;U~v0u-jsLf&UWzF(f*b})@2|X zpTZyW>7di@gu(4E$>k559`LsrvMxg(7Vbs)d#nyx+yH~yUmy76{^a(ue%-!pkXa@k zkzo{mEc>^10-Yk`6M{NlZ#=n8gG~pWZ$AteqyLY+F9DCDNZ;?Co+Lv^AcSxS7$Dpj z5)wjyBoiP6M38U_iV#i%qQnpc0U-z?C@KglDhevAsHlh+Dw2*TDk$FQii!s!pbLvf z6p#P=R)00q2|;kz{qOpFtY>Q8`s(=V?CLtcsxH*_kHBAwCV-mtZkL(P`{7UXCe8Fw zy#?*gM}JqjP>w<8qZZ8i*?`fgU(ZnAwx*d%$4m4m8|NKLeIl*8!_C3U9f-41Y7Q9_>gCOO<=>HKxTks9Re+bq?fze-O z`GVH8N0lXuJLPFeEBONWS8@fQ2Z=kE66k)uAmwaG^Yu@pKsw{OTj-5KKQ8o(f;+_i zU7m>}3*u%lpC!A!yaf_Z|Rz>|+^55RFkPZBH?EEZfSc!l6K zg4YS&BzUXfM!`*jrGn22zAX5v;2y!ff`^DGmm@-dE64|r_FN=m`jz|;u)fgof?9q> zwJ*4H5sm(pJQ0wKXrxuU0#bg9v}#|#%5o}PHlzCz!8-)+5`0!rwJ-QPAoSOQKM;}b zIMy%R>kGD!`c~})_GgGaSKH`sv>?~hNY54IvKi?+1-bS{`Y}P(kD$@$_JZP5?tE9# zpDs_lY7Gzm_)eyMM|}F|cgdwBr6xK4Pkv9AbgjYjeUwXqOiG_6xkfW@Zaq0!mb1&R zOgv|1<~rsu_}KB!l;n_$|BOxFK0JRzDWpRR{RciS98&Jj?-_3$yv(!?mUv$;Uw8eG z^5#ae;sgnl-k0IKjn3J%LAeWXs?OoAPXa>j#L#w59O?OxL%AXppH9iZ!}A6)Y*_B2 zU!cg0k>%HHec_)qp6)h!_|tPfxaR4{=52mDtoA!k-*LkaPfuJ}W7|1N{%vpVO5QeY ze6MXg_YK{4-N;GX@}Hc!?dye$ww>j_dfT>#uHQDh%Wc~}+H}{poW>7sGv_|OZQ72~ zZC^%j-}X{q*S4u+cW>)h^zpWfF516s)#$_9zE3abl2+-`_pH*FH$;@qyr6n%PV1Vb z``?Z&t$#_~(yL<{mi}@}GDd~Rvn7h_7__l+wx8%!u2U2jt9%T_^Y;}0j7cE0QU(nIH5Q0o8n!qUyx z7M3oEE-Jlf*7VZxyNXK#buKPFkUO(@Db4yK3cV)~d)rkCkv`k4>rhxuaum`~=H`DXrE4lECr3(JS)#PVXfvHVz$ zEKimz%a`TM@@BcS{8j-@?kfX;+{CfqaO zFBASV5iS$qv%n_{{Ib9|3;eSXPZr|KLcCdsKMU!|LVB{0t}LW43+c>4db5!3ETlgR z`N%?kvXHMVY=d@{exH}lVOV0o}ySUxN#mKV#7<;QYld9qwtzAR^! zH_M&n&w5~euwGa{tS8nN>y7otdSrdFURl4aXVy3Co%PRl!1lm)!S=y+!uG;;!}h~= z#P-B?#rDN^#`eZ`$M(l|$o9x~$@a;1%J#~3%l3=*oKby4R7>_BfAt&x*?yz?hGhvX z@4xzuzxs{;8~uiA&wq{U{y&WC?&Z9Q0}sfgjKROj2^kj^Dl5o^a9s&fD61L7^rb^G|O?EZs~W zWiudwvVq}z-esVi%V~?uwy@Io%eI5rob3pX*f3L>oH+V0(KF0BCd2!oNgC!{lZzxH zNn>HaFfUc~Oc<*{_G7-uEL;yAISYa!B`PpxYbnoGqa4WsMcedDITD9_Q<0qv^D^bi zvoqB$Nzo*~*j_ymf968vJOf4}ifLK^Q}i+z&NGb~^kxp`IVDF7qo$H4VXn-5lrnKd zHk9qjg)`g|8Qzej#tDTpDhpp!x@JOzFRDTO!6kg5Z>gp51y%zon!y`v#dDOFo`}}c z6IvWYq$g^+q$kvL7}66&8=7B_0t8h}m>?uU;0hXK3kbJChZ{$&Z;iHVX||!^g#VyY zEx;H=u%Rn`k=1r8%NpNPz9}?>fa?1@ZS{x zsQPYMy^8Fda>UaYlmS2|>0HR5qysFL0M{nbCVuvqiEXS|{rz1;Eo@eas`KgP>lK^^aCm|ek*Pq1IM6Lwl@ zw?bHGGua4?)ADowZCj^nO+1tt+c=AV1YJTsO=wuzZ6XX zHS66jGo3$!KX;pE`l#N5cIRV+t6aEWs`G(l2cHcXjrwt?xG#^**272?;5YZ>`GL08 zWGqVOL(>}F_W!AU`K>xKmHQxp{GWVZzB#;ePoA3l^ltTM*q7%Xs8%sBaK5J%={}kO zk{(it&aXssZ(J+-=X0$UY4(Y%Qycm?IRNM7Ur`PqDC$??stWhb6`dx}4!TY5G%0AF zG=0Xn5HWVbgb>kbhAYgZ3ua8MAhXFgC;ObpdJr2Y;vsKHM5AVXM}kNaevhC^Kj`O3P`hT{+Jk>%7+}S6SregZMf>DBOtF-qE zCJ0uR8Aua*RnG9AD|A1>k%H$6P7o{*EclJ!F~MI2!&y#wd_D0vFG{;-8%|$WrTE3!P5n`?0~8# zxQ`KgF0jx)54I3X1hwqIRYL1;-K*yTm89zj$yDLIf+yUg@06V4cd6jr5!i`$HshWD zPixC z#Ob8)u_6T#=Kw;hbs4nuM$C5@KBT;O8%DOGu(tq}Y*_CL<&Egk$*}$|l+VXg2G$2El&3{h#2JN#wMQK5N1QR)us#$jKH`iC zhV_w9exn+>w?gPh)#n&tkAb%KhOS_T|*66CYj#3AtBISTo6b?vn zQBGFXqVu0ok1y7rJvte#i*R2U}$v;LH%*5h~6e&IK6o6h2tlx zLkfM)9Om!kSD#o?A7e`Hl+?xF2Ez0c$4;Nv)_)EzN$jY<*mPRzm@cP{!xf9;3;ej5 zaq@J0MaK^bq?Dx2=Q;~dT#}Jf8dV$waew4U?!SFq=m3pv#&w2|#pq;2IGT4CKH(>tu>4*Q3D>E_7RAX`H^;L1c$g*+X zQHIe>{GDvA$MC$MK6+ z+HD3b-26tk_~Atp<{mMHWR2-ZC#CLNrEp@d|mPklhs)XD$H{?Q!X9sk@!e=@-$FJ~G2}=7P--#lO8snp( zvW2z>p4$h&2H;g?x<|VC21qBTbf(lJtK2$!n zpn;kM`Mj%?r5AH~g!4`XmoSvQVU0Jt0K%9rOk?r@;c?dU;at>J)0h{-H^9y#)0iFM zk0{E^j?u7QRsK9Jd}`wIns}|DCN8^#icu4n*M*8Ts*xY(zmb=dl@az5IlU2X1FD;x z$jZb;)jK9G`LI$G7aG*Wg`xlNOk9{xx2ixRr~juWF3FwInITiBG;xW;l9Op-;E$2E zGm5?_xiii>SGA{n{H&yk!TcXKarl=`b?e?cG?z*4Yy{^#oQ9lWA_b@9G~`>)D1vi| zkbj0gwV9Txfza0h6bpt{(=A2m8IJ4ot~%*5dPlnd6w{dBoX4o=?BAWopd?&3`TsSK zK}VMA?#y6jXHC@snr7z}>iBc_b$X=MSNs8#%E3QhVp?eFn}<3PLPoq+c!^TBxeT4X+mmFF=f;OEY- z<~IX=-TaDO{C;a5vmE?RWgfE#{Fol555{2nD$iq9Veo!~P89snNPUN35|FAL3il$% zsQ$IT`#`zpF}J|qsmx<`!Jps7Pq%~0^O$9>a?$e+=8I@PS-kTM-~ zpC~w0aJt|E!6kxf?+*TN5LzwggI+K6J%a2@$akM$5*iw5wdV%RA&oZKSCIYRZ+#c> z#PgcYRo~}*qIpfysn2VooKE?a_hh(j;XF%T^Ihb}JRN^0*puOY1Lint%gqy}fTG$a;u>g5l8L;WyWsgg0cE8D-?xllGY!-<8ev@YbRA|0DUTB`ifm3WhjE7eq;B8 z{{FB@OmOHQnhnU%zw&3qf=S~kk@^n7ByqR|8N5i$1nuuW znBDV)1Mqh$^8`OC%TGq4SbkKM=Lyfb%7vp=UCuP?w#RVU;J1SYQA{5d5m^kXxu`@x zEbG8V^JD$6Zr%LWpc4L?C$NM<>bK?zC)n?B-lJ8`6WEDDv0tDp8rvwx*^H6M`XT<_ z{f@p8ZlK_B!E*)A7c3Iw^U8Qi1o<41zD97R;2VPKz8JWxkuOlq57741z6Vg{=Qs8_ zE+8NH<8xVYpQB6K@7d?*oRlj2A}8PHXoF`6DmWjgkJ9D0eHKoBVe+1OH#g{gaNo?w z4}LN~KDWoNWBjsC-)RSYzFp;hdtC0D_2Liu!h0Ru4!m1fAJI^TIad-niG+DGY=2#voI7e zD=vk77oH8koa6!6VzcF1Ql5yxpsa@c({f@r(ZL&$O*>BCteKNx49!$(!!ES%qJ;mv z>Rxm3zLH^m-mMJa^{P!apZ5+}hN+5lM8?9}(bokg=ceHao_E7f1I>LG&wH|AqQu8M z?+c~G$2@-*%BN0wdOlF0M10J%M;w*-nCC;Gl=ztEBcc4xE(~X=dKcyh)44a?22@u^ zT5;$31`yUHc#2YYo<9Q8sNNiZ9^84Z9IqC~n=F!1>dteTaCuT&{F{uyFxK%8%G`qb zse!3a77b=zO+E@{pf{ZS&@qfk_v&V!W1wnXhCfeXd@Z$6R#-pwbkOX4)n?xstM)md z@n|q)D;RR2%|6}1y$(b62U&+fDX&|XVLOQ@Tqs_LVT(XZ%nZvl1hXICm@530AXRu8 zRNUm42d%?%erFi<7(eTf?96^DESCjT*q2~XaZeBrI_w9aq3U~8DVep*mNjZuw`w%1 zF)X~6IoOOr$Ka7kAEwsUDII)uPX_-5K|Fm=xxUF)QX7q8BMSYWbjf#`SnsTu@ z<@S(?7+yg>*c=v)%gNRK=(W`4Ap^T0-lLS!()62)4x3b z|L+Q828H}4UpUz%dRcMtA-JEZMuf5u5ioHV_6OmKxC?udwa+5@aVPeQODDnp?V$Z_ zu+LETyi)rg9zXo@{%qQjd8Eo=Ni8>hIbI>?u65-Ll_=gYYoTWwkn;VyFS)UoGb{X%ZVMnH8P`AL>{ zbm?K^y6W4q3#Jtn`-7BGt3hj(gSW$O1mw#BFI@F9Wx9qyyZNm|Lb;r+l{QYS(cf9ej&KeElWqiyBu^3wOhS7KviSpARO1l+;cJn&~etgl9AI2R)ew@4MFfbZN z!EY7~qO{vW&~AP|f!{jVksqHIoxYo3)?r{Y&d2a)u**UluZNqP-x@6BGk@gAZ4}M# zZ!j}V5;WD*m?u7|nSiE|dXu2`HxtY+f}K{{-xIJvRTXOc{qR@S+RILOa7APA5){pw zVVORvm!RGGSdVfKVF_;g|(GhP@^#{NAgH$Lk#_4L7#(oqACkgdnk0Mw6$e(e# z`PGMId)R5^PP?`vy6yi6S<^T-^I)ksmj4M^Q+ITf9c8(&JRHRm4=H{F-K~z7MU7SG zG+8F=peyXz>aO`X(Npc<^mV~?m}pst0jhNvpjwB)u)HOBbA5z;70+g-2&ySD=pI6I zph@>3f*d20R%b1NQ-z)`xIl1;pxUp6zZ-<+)QsWR3*IBhi5czL4-wTFJYYW*1ZgEO z2~?{BK*~gL{pDuC+lXj@4~ze&g?>TYUnU~oUkd$|&}`V`;}xt;1fO`pmSWHEXwhG1 zvCkGdhX}qy#D0|EL~)-i?lZ)`MC=y{s{5Z2-)eEcUF`oR_>kD6Se$eUvVUWG*v^Q4 z!304*ceL*)*i|r7u)koQpsG*!A1`!~;KhPh3SJ|q>Jk2L7h2UHX!d1{_a(udf*%Ne zEQl`nH}~7w?~;$sCnsN|Iqo6)1$BPg2;D(2T`)s1TQEmZ=XP*btr_;<=1o7;@Lz0% zAFb)_bHJP1WpiBIrXOPR-fa+Zv}Q!v-UV>P>RxX`Q23x0oI*=_ zl&^x9$pq7ZalT|qHy>JUt&wz+ht9sL-)SloK?Wxa3zq8+N?Xyxs~>4Q|C>bsat#pJHps z>S5aIQ4X-d;+cTk zU}((17~&XzXF?cJJw{~IU5&p6Oqe-1o=JNSG?dDD6Bsr@n*&CnbR_3BBSZQbo~ zu9V-#tzgHlC>McLp6ijZ(J&EzY0$3daaRkA*bm!}q0K%j5_6c!(?QtO^}#uw1F5&XuU*Qbh0*G;V zbToQgZlqU2V>PW z@L?r6Y7zjeq69iStD=sRvjljy@-T!z57i9)@bJM=YB2uQgA=;0P+LV{0;eA2eE4B- z*SaSCxR}$&Z!nJ(PPl+@txk*UBY>?Cn(t%qCrC>5!vq_pD*5UOOGK%Ck>oqvH24-# ziUH1qHjQBfCOJ$cB$#<^?YhR0eELHBj2T9Dt70UW6q6LAY;=U#t(phfoFH!IB^;X! z_=w|Ln)^W`iv;qE3MQT&V4+kz{yoa%bu92t-&%#kp!=&BnAt(HFVgDwxYy8ufSTuU zm{~=mp!1=%I+;7$P*vfWHa|2gqZ_nVC$jg$Lvv{QWuaw3vj$jdtU;~(F#H~WY#W*n zt6eL1Jgi5za+muBc%J_+EsX1$^GtKL5RH#4Pe&ZY}m)fezqbK7Zt_!~CA(M}MuII~9Ra zSBisXn)!aCN`;=KOwONvTlN8|!_Z|T^m`ZsYo*v;Ptho-Q&2*aze{5@7F@01oLA&#@3;BqF9rJ;v6U;~Dwe!{B_deXU(s2<{ ztU;9;dunUv6A)SZV5o{|cUf1+(_d@np|$giQAky+omX+(DcEPLKIh+AJ5NWPT&q@V zSHS*44-y3 z7Qq(I_YCn0!K=jmW+M2iZ`lDi zh`suj9cb=_()~Fi!fzM+K>QsN_j0lSN$eZpJ-{{jjzok@5$q#)hTvGiiA4CHNkn{e zg}z+qYXo_x4Bgj=`#nN$7ThBCWkSC!i0V-3U?0Qupes|zeucDOFhP*dJ?-_{eGj2~ z3#xVn_dKDwEJXk33(gi)?Fsf*34N{LZGv|Q-XnOw;B$i81$PU6Ab3zvEo_4ScS8Rt z$ki#Pr;echHltr?-V{Oi6hSUxk>)ZOae&|;K`v?0o=eR{u51zK2&!de(3E?mJ(s$O z4+?U{i!|Re#LDgaJ+a>-$g#(7odx83jeIKCBj@O}_Y3O!Y$J3B!6ZSBZRkH+Fh{Vj zpswc;LUXQ8|M`Lw1PcVG3Ua(ee{%&(1Q!V|5nLv?T5yfvI>GgVn*>!q1HM~?-YU3V zaEIV7!M6lI7W_5D%+~>UAE2j=R04y3_pU046bzhTYi52c@G&a zT1+25{m$v1PH#~>zWC1KPm5d37(e6A8K2H5e_G{FMdLNc1I@1ZD^nH~|FGvXmt|r4 zHo^h2+vk$~TD&C0Z4#Td>i{9PgND|`P zg|G}8fr0`WJ3bExrM}c-SO+WI@p(ubojX3i63V&b z^J}5}$KUap#f1Dr?)Y2+!laGUJrhlCRPnBy01bZFMAwGF%VZ;J5}CdgEb5 z-p(jo8I%{tbUa-RrTqKW^8ULrttUQWtH!9#864y(DAtO?aINcMw1LM$6_8~cW{dX8 zGaI*9*|=2;b2p%VL3>xb#d0 zJV%2l?KT;-Hq(h`ltzgkf_9q-vpe2&yg%|`$9QS4FS!g5I<=p(X zfFJ9L>BA5-$nPGQ8HVkFY7i3619V!^Nd1VQ_ICi|+N##uo`ydpsSu#lIjGdC*4ti( zt1B8~Is9qf49N1M+6nE>hwUmCjuLe_*Mb@G29*td9|oyVT#VBhBRGyrP+1($a{z*+ zH^nao$T;2nc4IWc@t9Wbv}-$}+x|bl-o_^;q%2j#ZrWXP%nw^;NLdD3R!ALx?zfg| zFDws7vBX2lQoGJ>nk5)glx1xgB2~L@U5QQw%`(e_K7KvU88a{ta+UN?qE@%0eQ6&xaXw%}O70zs}jGTfzt ziv-zE(Ed6>KEI^ZS`2WH(5+Eev{!RgpjyMjv#9T1<>w8!1~p8O!dmpN)<~o|a8AnS zhR8uSk#$V;3nmD*7wjm=`3U{>6g*vUfS@W@%sn+fSS$ZJz7x%bS%*cFCOJp7rgc2& z{jazORs<_gJ{R6nm#GNNg&W~%$GPa5t2V{1XuRenqxOn{2cGlA-WtEA_HEvSVYR$j zwU&FkE^c5Q^cm+j>6sI@vS3%OwL8nROJchCvb;xPs@;CXXO-lhRql(rZoem{?l@vZ?feqLbGajPcN_~dcb6O4(YfYL zn+mGKUz>Gfdse%C&zF(C%Z?encb5Ct!Ef(9U;296$D(?hHx(Atgs=2<(eP74*&%$) z&hjMj7v+Te($m{qGug;Da(bR#?u$RY+#3~h>ze$q)g$wLNVl(hk0u*(+T~O`;;R<6 zV%_VtZi&Bj<^FJ^_L?gj#@=MK=v|)dZ_^-tO|4sdCj31_uy7WQFz zEz30ymYLUW@+NORV$__rtI?WtC;6(J^c3 zqGJ)~?flZSG_Tw{6{X|L%+1Mt;h5EX=a=5z)~(2C$<&_JR>5^tT)`8$$nkk7t@Exf zK$!FXjxq{EskbSqe&gk0>pc&p1V0wI8s}MXO)81LanF}gC@t@K>l;lx7!hW!Wyo6B z4=AX4BTB6VWu~~Y{>XRFmobWib?aQLh(>-{--x&c={b*i7~SO4oN+mk$VtQvH@_Y$ zc|ZK9HGAPEv%NRBMsB^_%O}^~<;$H?(00jvOSw*xKih26a+mi=lqdS-u?6OG<3?xw z#M*TDY2!$g)uSN#72`&8xntXQNjkzhA;-=(+a7$q?UDma?<+{pwHRAAIF=^mI(Fp# z#urBETs&{iJIibG`8O@RnYODoUGWd=EF8aB$Kc!3t~-oaa>*m%37ZeFw$LhVDE~bX z>%q$EOV@#uXyXlIXJlPZn>_M?3@wLnR#!ylnRz8`d|^`*sHL0Gnv7b>^+vo4--vM& zIrzL~iiNkCLmh%!7^T^9VKJq8!?-JHU0}`!gnM67|Lja6Vyy2Y^5NN61Ao>J&i7tg z7{2~Uh4o`Z68v~tczm&BbxcUh_fL{PMeJ3sUf+E{>*t6s6zTJ|Vc1`URg~{>a{g7w z8b(+qeH*^701@%lOyAdxz6Zlx;=4exaNexeY$3fq_G8u@pOYG&?`LwHD`Yj_ZA{Ij z;yKDk$yRHg&q-ViuEzyAU&uJ$Qo5F?NIfm;qcE8JFm|BU0w34ds+m*a#k>bbXLFEf zwm|wKxe8|9yBG9n(2*=M^FAiIKgr8TZlvq^Bp)T0`$;Z?u6`H(%m+w%Rv6XCl6p|( zc7-{z3|F~`sgd^Rgsk7jxHzp*j~79A<4Zbhvcd}qHfL5F(wIv z3x=!_GZC+y7*$5K%)PK|2Tw7okYY_{Zv<&oO0|{yHKbKB#VPth(yE;5D0&y@T4NE= ztgFI%R(NAo>C`uw#lvupRmJ1bO;JU$s(c!#;B3ONs(>7t8%nXNgc_>w*OOL7FZTq7SK!HOBL47!4bz=}cv* zTt`yn@&b~tgRH^vi#ZK<0vP77I1Zi~!ng`9b<8{u1~GAIuw$?EV9>6P2TOW0;l#Gb z*7@@BP9xxy2~Ho16TH_ggq@iW%cCL7dUIh(JBbcYMI@;DoCbz_A%bhv=Tp+ayqbYK znI@SwWa=BTUPC5$d78!1!BkO%96~1C1GpT#%yiQXSvF)})R6rLT>g+t9`q7ug!{IK z%HLT!p^!3i@0LpDMSr{_P(HF0B_hyz^;M*wg{=IY^I#-l^64ghBSegFl`p2_#s}wW z3ET*Q-a0lUQ_Tw^C?~DI^8_+(>18GgD!Dd=n(JJNhsqPVq9=mYbsVnm8RfXu(;iWW z&KK7k1QUe&3^St00IiMJBsQw(qH06Nu5w8PVn!>x)K5%8En3E_9)<)xFj!B=1A*P8Wvo~~ zp9T+`oH2;NfXW`$O5KZpI>2%b-;YWy!oOIq3R*IT9B8DG;KWemT}wlxieWHJN`<`U z(W?`GFta+e2ZG8vd5C^vFeav{oZ(#JRxES|3^!I7;Vpc@d^Z<+k0H?85f86f_5e@Qu$G!S@}fv`KbK;fROUTh{`9hh7kFzwKUK( z>oPBxWLPLUDI_@(MtZ{CA%sKFD2Yer)9{V5ACCW^a=Z>EXtpP8BHBZ!iI5GJG}tZ` zk`2u46P051t%6o{LBq=qv1UFEOb%Su2WzPa7WZmP8a6>g@ck2jcn(!5<87zhRqCCL zqVdqcl%i4LU#XB+)zrz#G&qb?icA=YjVDw}BOOOaj%qgui24)6r&l{OSL>j$&qFu> z?WyohRm1SZu5vxXN+~9dtqV0rU|KBWqKb{i153T*Bt1qPk*`NKAV5&X!GyR7PFoyG z=;_!J7^u>oRDESNh|pLW^9Zh{oULpJ5uD%^nowQkI+);uIV%+9;82uj!Ck2i_-B@! zr$HH1Cqfe|j*8K^6+0QKs@%VXo5%PJu2tRkG8Eron?7k;(FM6PE*xKsFR@KG{ulSb zf~yCo`l*TsO*6x)=5L(bu4B`V)@*;vW(l1dwY1Jpv|8Raxl^b3?7~j%tmuB$^h7J# zKelD>l(wLTCgh&k?!u-+E-e->Q>gWhFLi3VuyHwrJX< zdB>*79xpC`(c5k}c+Bi}2`#O{epYlM8Q197)Qa)92((Y`bjQ2|E3%(;vEPbJggAX3 zbSvnoo3i5ZS<`0Lz(ngbzcr*EBi)MVVlu4E#0n97Wta)^3GtaNth)Xwy;fPH z6IV^ivg-G<3Noyki4a;bO)RqXpLk)kTJb-bB7uiOq(!y(&ULnE*{+Qa^FC!xYJTa?ywp+qqult(WI%DsILVU z=1ea(3VTj29z5~lp<~BQooG<%TzydEUy`ezj70MynZZWk(3z7bOqe>c=irHBry5Ra zRJ@m_a7fYkKkgX7@%xH}J)9gB4xCZkNfp7k$;J50;l!fpW2dUzSFz0sFDQ!KvEz%U z6&byzO`L>#u@!VO3QxbVQ|N-6LfZB;rp+im-Kha7FZfC}94?4R-KsN~z6Mval>3HQ zGt&#FViU56Wv7y*I42uScXIGtK(KwNjZj^>Jyhwsm}nkO)>!w2ycG7M=5zNtOE^PP@`k>NKe)l#WlbV9WaWPOYQjEn#qjf=)>= zAxN{jc?e$c0IB@xR`uuDq>Vxc@7|;3a7!z`9(vaBFY;X;u{ivSuqEE5)|H;C%pNr` z5^?+E>!S*PIW-C(ORkv#`TFTmBQCV#i$K3?&o{W=D~(WBW@sb0a_dxk!NFkqb@1ok zA`X6Qjw2STR0o3p&QQQGn!$!|c}%^Ps_c($RNRB{L7&VYhZzjxj#m#OV6BGY#NN2=9{_>IV5_%A&{fz-#Oz!38(QZHM&o1h!#aRg z+U;UkxcSWjKR=j|ANgp0i(%GbU^MdKxXfjtjjJp9I|SxoRm8gr{@n4dZf0Of+ljY2 z+;qHmSK@aBLt5rnD;@8huyFI+-3s}D9rFgqw|;u$6>lLiW}WOt>kYZ z#^e{lPAmGMJ_L>6h1&ib_)F0QkbabcA!vq08=Sc*aa`0t(?`X&>n@jUE~>Sq*2<8VX6uwe;M=SIjc2AXlY`E5dn%C@GJJMG$z=(hhO_MDlP zkkX~%*zkU&itet44=)y;(2DMSVngcqJ?hAiBTWCw9<`eR_nfhCQ&%mDtod*3^BjPdRP6M$P5gmRbac?O!cQ@!iRp_ol_Yzv|^}&6x&}WJJM8P>? zUn2CCLaRHd5bh?Sxx2-9)Oj4F<9?wZ7x%3~zaaE0Lhly*MC`v1`iRiq3C&KB`3oZ= zo|-~a7K?Nfp<4=l8Zp8!k_9`9dqCX#2|ZBgvxOcb^c10|2|Zir`9fbQ^tD3YCaBK$ zAe|2g{e<}2CiF`}zbZ7(pE6$`3jL+fUkm+%(7y;>4P7t&*B~O_4TNqYbX%d5gziGb zOQgGCK-?+QMLxrc;FB-(M4_h%T`cqhBKTY{xJmF8LEZ;R_iqH_(I&|^AUIACk5L8L z57ke=jeR29F~$lr!M%d} z1-Z4)a6c3A9GZNNfvVpEs(uStN9-F2s{RW0i9&Z4RQ(q0dkUQ^$lY4rXaVq>3^KyWWfsrRsRO}SwhbjTqwwWaE8A@@K(Xw z1vdz86nt3lalvhZ&j@lOo&4Sw{6O$y!7l_43jR~@J3%$R!bGt`e~I$)vp)e}Dn57c zu8?zCmZ$1xfhrvQafD0%N5r4%C*ZE0Z|#mjv+j>oe+xQW_)Q>!E+E2xXb6hq(x)P; zmzI>2>Zdxntlr!NM1og;s)9CH`*39SmTU@NQR}9#<;x6fRrpQTZDDKrHZj|F%1O!b z9xO5DzBll|g6iRG_dv$$m4lEFfQ*~(;EQ39P1|HP_1@4lH!inZ!I=fMsZt=<44$MyjyPAX>m1wTy}WiffoH+6d1?qKGi7BIu?KL zPK0D=b0xwYMTm#@fZBsEop`%O9Sgq;p?B;l_pU?OpCXS%r5MLN<9646=ICo_-kW>% z+*2N9Zz%WXZzvBpT0$DGWw|HAo4KOrc{vjxk>{=EJL2`-|9ZrlJ>_w>(PC>kdf{?U z{(?p^tHW>eH1Licg$V)&fYM-4;juR^GD-?3^V z5pv5*M_=nY@WB4grymIGoeN1uCl<5oketCe+h2F2CymkrcsTJofbv3I1@FkG@V6P{ zVW3+3bHzAj5Z`3g=Zb2A?+$mSIb2HQwwA z2vcv+0&^0~T83{Z%n>o3=N%co2ITf)1T8&~;X99SfbBsUzD!2)Qc#93maZ>H>{Xt< zK3*B(c_k>r*NLt>gjJO9V{+apBxLx$C9hW_zGC$8o^u=-KHkabIoCH!q6ZkB(L#Fh zVNH-@f--!5a>x(L@Tr@1$BO4DpBhYz3(D|SXV~#U8NQVaJE5`+pBgYsbY%F{;N}O* zd>d)7D6AHVn>~NDNJipj&tuADRNF^J8^zn%;_d#Rw+9@Px&ZV+3GyA2QX)YXNRS1= zAeV`^wk(S$#M>j{?a83GryP^wyj6mz3EnaZ@^=Yxbuh>^;*D#8o)^R$2RF>xi$QPO z9h2hxk`tu5xdCC+A9n0vq%yC>i!ACiI^44tG^YbmY(VC{tU%8Gqd0^$@1yH#lG~9c zN5Jt3kkO0q=Lk4LqA@y;)B~#SS9ohcqHz<=??cy2Vz`G`_8g3rQSkA#2I+lamd}yqe&Tku#zXNqe^>-$++sMq8{qlt8yOZm{lPU zcg(7Y&r<&DqJT##Q$1C>XRDT8PZh10RoR}SLe^6SD`r)yqa1rxq+;f{*gRL+8`VvY z{?$=wEZU<)N7FGAqnP@TYMep?r|C}fIe#xQu#KcjtP*leK*`nY%$#4?7oN`sS&I$s zOjvE9b@3Y*Z^d$~#&KQjOZfYchNtnzky-3R_=8BC5&Jh7l4!UIhJi3N*aZd+_kt<} z)sW-4g)lVw9)^Y%OijSLA%!WEX~2D;Mh*?FVVFom3JjOS5YIL-1HsnD6Q%Z43$ z027`ayQY*1Er!#FaJmoP>pD)>ilO0#pO2sUDr`HrY@3B6ep(7wyjyy~xw#|!c_xkd z@X>j0RTa{V*i3a?wR3sFC>!uc|smsH$!+465o{ zvg*viEtM4P5LIn^F#J{3_A?Evw#ImxRJHMKTF8Q%XL=bKpXFpYs%p#QGpDMJrM8;h zt~J}!8>?*&y|LP^Ro-+zvW4ERG|!(`I2w_ z1^(dj|5IYtkx^|Or9Xd0QCSM6s?VQQcT14+I^Jw8?8+Mpv!UDB=k zK4FoljR^_ZqEB#N-AmzBTqukifWfo2+XX#uFf9auD_CqZZqu>Pnsj5+aeK?y%mZt zL1hvp)l%Pg+$xy8pcpSYIEwMMspz7bh)i3n5aZ=|0Fs=xcypjW08)8`TxA?eP%CGU z=q0vc>o zjO4XC0-9l^)RXvs209F~l7UuhX=KmX+?a_MKCfB6$md{_i+thPtyc66Z-R@Tn>UAF zcvFfga|&TF;Se-3t|N0vZ8C+9#~~q)XN5ctfxA-Lqh%C(RjOHviqORg5nqVvdV^`u z*+iX$_;EO(6kj^4pz9i!%nfIziVX!#<{HzDCh=?Owhp@9@$M^f!r_6AA44~+?1B7R zIey@*6eD91dQgN~(e4gqcafLKGV(ww6rdD~<6~%#x?oXRsgn9k*ox#i@SqgAeGKhRDeZnMrEqo@h2-gC z+lQEI0?~(>g*lymv^wtL8o~0J0FCM;Fpz1C(Ef>Rgm`cW&6F{Zkgbeo5y-;1iJT@5 zv*4XDS{ctG{0Qy%p~;DbtNKCJ5GFKe0=e*^4kc}{PMZ5!kAt@kD%4PdgvulKb*u>t z$xk*C_bBtM`a~uJ-10)n844SvnDkN5$OS<-M7cObDS!B*SK(A4IQ>Ex+ZBYVRf<6z z=ix5r7;#k`9p|AgXRq72%3{?XD9A10wG|g1wm?fqMB_8i>9}TmmFkEtF`D4ZA?T3! z$TgWEw)4D>D=c6=&r7#>)jcuv_NqC|IyDXmtduT4oC7%CYM9%~m1$JQ?&dQEo=Tw6=m^Y@2RFBCMd!<)(ft!%h4z3YahGHE0hD6-Rt`?P z-wMNSYc+HO@KhZp3mM&~Q`oBapflOVSN5W+LRE^Z_aMW2p^;v~%g`RzJ@Ry32W=W7 z3C}>Imz+y)~VQd8fibk1iYz9Ae1h%g~G59A-%pE2rUv91vJ3)>&2cBhE_Zt}Y0Cqk+JZ zvy7Rc=aS)RiRTjkj%or(gGTpBU_w0@OK3&sbZCr&2rLZ@2fV~3j+u3&6lVahG@wrr`hzg2dOJ}l(uk1zDlJW;%^ufsC3q=nOnh{AwpgMvrlhHEy zuG1#88m_EH5?EdIGc#!wM;Zz7m>ovPaZP$B_>UhS7etyE}|KZtcz{!8jR~-Kkb5vY!GE zOjjW^^D`T|1bQ(vWZ-3qz`bP{wL zbOv-bv{onbqup6=%9 zw^T0}TU?M>z$YVkfghG?@CtzqddLTOTq)A84hZ=>#V4d$#r|e3(ya0P2FI1*zF2%a z;{o-(jW@#l)=tB3Jv_gkHN$PlT;^E0d;jl|P%P$|*cVT`b@fW;3+qSa%B6~MpW znvPRR#n$x8!04ITiA}A+iB<|e#4#(eV{%7pK!%m(Z)Tl70!NNIHXYd%r<|If(G za5NYjDU!%TST}0iR2@L7=bw_d$r_zu{ln~+X8m$$Kin)a0!b|i%dl4A@X}X^dL@zo zJPig~@Y~tT=I|pS8@x1sI;S7Zw|Wz;hW)Hb`1j)<_FvCQw9Z&=Wg$I1GOVlT`7h~j z)f-_=4xVw+$$8gfTGbQNtVtQxY5aV5NmwG{PW+eR?uUrqV#FJri2c_0xDnq%=A8o} zJW<7JtZ*y=pL#gKNh&!kb(|a~LIe*`=@U;O7Cbjo*SXjn#Gv{v|w>rt$Divi9q*xzq`mIA&ETPbe zKqNqAyhjd>ZSnA#YU)*=1ccw?PF%5hCTkX<1O(4kRoTSQoaKDppYO0$6uRsaowee- zt%@^LJ!)iQYl3~fD2|1C)<{@X?Q-AZh%3UEge~=6X&pHe0d*Z?tC&Rcbm z@i42~%Ri{op=ljX0xBPb9ygQL{(8fVZK|M(YVX{^K)HPETq%D(;3#M}zXA+6IEK_p z^W%8bl^mlS{=OyyQQD1TS9iRrh_@UOGG2NoKjLC&9R@~YA9kpkslg7ZkQ>LcZhsLq zAZx02vy``>+bWRmcsnE;h7AkGOYb_~yJ2?o^EPzGxUg1AyWI)O&F@e*!|=n7{Gy>X zzb9eVVPG^;!7rwYd^`p>H@~Rvh!;aV@~a80`R#z&%`Yb&^-%@C?UndtWI6M0@~h?I zw_Ese98dKY2Ka?)Xz9?5i~3VR?JuYKshzia6#h~iR_Z^Pb{K+Yxa^0&MJ|8LFV#=b z?s6H5d@v2nM_p)LF3giF*~Ziss0UXB+DLR2m+?p&v;$b8T7vvyU}l_de#Pyac@wOa z()={7(QW_VKW`PG(ko`3MT`kCdmh>Hh_Xuth zd|Ysw;PZkn3%(=xy&%Os$ghsz|L=2FCOQko-$w8p!OH|66;$&6@E3zlgZ}Fg@m`~- zCQ-@r`)h<=E%dEIZxGxp_Kyo) zCiDwJ?-KfLp+6FOKN0CaM8u2enAm&K@iM*9g7t{ZFA@IQiG7M-rnvVI_dKy5DL7u- z&lC3|v7aNjNN^bu<#)5-U4okhm7G1?Ul#fu!9#-Og1qXEd~mIqLVZrDjnJurJq1rE zqPrL%IEaY+j~6T;f?tu)GlgCt^kSix3w;w2{B9+pyf%vcqk`K6UliOW_@3a0M1=c7 z=);1)2u7e|VESSN8wfTRY)?e|9f{x*5c|G@gT;NgxK9%MX@ZxC`=#Q3wbU{vbROrhEmkO>HTqAg=;N5~x2tFVwIf$k|3K|m=1u1V#TD|vx{e(VKkRrT% z?#BsE5xh|FVnKBt7yc;VOaJOU2&{a5ZJoHU7ramKK|x9cGyF4xFA44xd`ob*pn5;T z|EEHKC3r-zT<|ABi|-xyj}WXSSVu5Hu#I3xLG}Jbxb8x$bGx8(h3+RvnPu{)5IAw7 zpgQLU`XZrc2+kEO5nLju-mmb_>s-lawct9z^@5axrn@@d22}4|pgP|MRPSHltKyI1 z()9m{Af={BtMhEYpM^Hj7HCglY9g<5C93x`&@Xh7pn6ZkzPr%soH1yMUNhVf!LtQN z3l<6%3sNSV{;v?cPVff7w*+?!Qfiz2)%z4k;ce2L1u4T#TD?z!1BD(UNYQS(PZlf` zq_{TiDe+BQDo7!3(zgmyUYqm=LCSuU-YWR4;ERH<3F`Okr$X!ZErr4v{+OTzGwBFH z{T^;4bT`2)K}w6$|5U;0g6e$?Glj_MewE;Lf;R}>CU}P+Ma${`F+ob0lm1HZTfrX$ z)q5Fc^xq{6?@Q+~{6gaFF0I!IgqH3Q{rrQj`sYXvFqPWOie-w=F9uw3vbL5juGe>*`+$CJ(!%n|G>m?tze-M<#ZW2U|vTVcG0cI&4-{891!h;C6Ks$F5_abBF*S03;A z#Xdo>jbI1CB*9d{Y{4ACzJmP)^8|+qju0Frm@ha%ut0FC;4Hzpf+d2B1eXXd6RbR5 zTqpMH1vdz86x>2Y`E3=n1)me#CHR)$Zov-(_X{2pJS_N)V7cH=f(FNBh|ep?(>A2z z1nUdN3;G4s`UU*)*bV)s3Z@HY2xbfB2&(Za{HyUQaD>>863iEzAjs1uY)8d{vjpb~ zmIy8qTq3wkaJAqX!F7V`1vdz86x<@XRnQiEPH?-R8s{QiyM_Kh@MFQx1P>F@{&}v4 zSWZN~e-bn}z62ky;1Sjf{M{h#EyX^L_O(Ovp$wt3iQuQ&E8JCk1;36dDQSL}N=`}Z z)TMK3QgV{tj~|rtk8jMRrNL*H-C)l>EQYGhLCYDc=YOUL*wrASWK!$19VIS@b{KJdwkpb@q8df*#np<}Uo~~`!b=#K(b~iEXrZ+zln9{+p zJ5<{cD9$kKj9Iq?zCF{h^S-zy@b!4ZE*O4UV9XrDzWn(afj-w8_J-8Sfx90v>|J+` z3e4MO*uTW)1ztU3*r}KG3aqMQ+J#5b0&jLV?ML$41(r@QZF5)Sz+=~%_V7Thz^JE9 z`_TuyfmvUfcH<`HSYO=%@UtIYul%p`}h0o-W}h~Odnd! zZoTg1%wNl@*-dI~%gpQ)X?M8nq0FP}Bke&)*Jt`0R=2O7usZX(71iy%Z(o)9arG#B zK%e=UMN6XWH?|aI&W(t+3)@Y~{CP>V-Db_m%x|M=*gr%M$eggUhP`ioc4oi$n)X*m zQZhH(UDJ-4&^mK&=NLQhorak&J|AP>*SALIl_P4|2~U}s&wf?Qe(JPuGm0;dwWqDy zpK(jm+IG*{A7pghTH8)t{94AD=fv5)e|RS2{h#9OnNuIj*t4#Vz5SzmGS2E#*X};# z){H)f>)Nlqusq{|Tk6@DcUzRP?DYEf=m%zI?ERs>J+k@v85=h?uxH&cI^*lH4eci* z2WQ;fppo5de(#KT-fU!VJer;{cX_;hZb65Pn+7(vQ};B@XkV*|ojka9M(4Mi*h60o z&v^8fruN#5AG_Z-!EeWI{;GTZq-OTU)_c1j`?;B2cfF)pzPf(*Z`&o=uf#-k-_$(WUbghtZXd^Yvgdh@c3a#a#lB-OZ%Y}@x} zuWmaI^{^Wxcj-2yMlXBZ{q4F9?381F-nL0Mdqi*h&bw-LyK6zNeRGSjZsz@c?49e% zyT1N@U%PvgLtX1u?`QA3<)f~zWu9U0Xz*s&UyAzMhi`nL>+Sarum{zBvg?-5&a@A& zy1#4hW_k9`+P8P@oj=GvaNVk|Pu)J)?j5_N>)$>fV((osr>oUrn7y^uw65HVw_MTNqU7rm**X~_6q3fCFjz)a- zx}N#?82jS})w@1Zd#qh&%`fTq7LBv7Y4XqXu(!tB18)C3{jDw&?ZFA}rPsf0l6~9V zJJMebFR+u_+vz`CG}(@N@Zt0uKbm4Erre#rVc=BzrpIqiPkiPAdqBoD>8-jB~S%0y8>*!wT7q*#YpZj@Q z`mzTuv8POJm)@ky9Q*mBjni8^GuOUgPObD?2F|l5SYhdxe>C5|=c@89pIo%S&WbzK zWpnsKyZNmjb@}GjMfO>(-t2Num&Nu655CZ4*PB<^4|jdC%ao#}_TQhqzstq7ud;`o zd3%>{A6sTOe{WTn&qrNj_nfe#OW&~N_M`up)1~pI751fbrgfQc?n?Wni1A$-M_+G8 zt{UE@Z|M#8E`Pr+pG{wFe|3Lmm!s`&w)49ucbWd#Eq1$?61q%WcdLEIS@pYYAHCLo z?(^zhZf$zIeM9lDX`g;_hizL&({9p*b@o4ITRo?w-MxK_ed*ihrrmqrllJh*gVGwW*lJ(lCDcD}OF%l6}SzV19fZioHz z#=V_Ct@)~bch1|LAB)~)KlZ`)&Ob)KVYi*Jwe$TkZ`qz2n>xQ%=N&uy?mIh=ZM@t5 zJp0DZ<66IOAAbMJ&TpiAV2__Muk+@fAKIBQMV-x|AKNAOP3*kwyie@*eMWXZc?% z_ViVr&RORkwTn}}OZ{l^xAv!Re3|<7=I`xoMSD`u-}{5@tNnWFS+PIa_QTJmZtDGu z{l(BNsWayoW%ItfFLmR?p0Y)&*QO5q+FSNxx0R`5+DDY_-Lp7#&y;FqT^Gzw-M+DU znYZPIss1C;W!W!{P2JZertBXV3`=dWAhxVl?bB1A*b!HD_m+&*7aG&6Ug{;ao0MHOqG|emrFZ@_<=18{%a--um*QQ} zy6m-Y-%GjpleT47t=*Y2B)3CZ>FH%Dw{A=9NojEmst-scvKhudVy?1Zbsl97_v%8E|3(W0&Z+soAW``U4 z1`V8`-nCQcJ0o(EdW&bfYTAr{)U`R)Ds|~Jb@lmt)rB21)hmZ3t77$Lt5>vzskT0x ztFCQ7SB@E&)%y3U^8CzO|nD1GLkBVpV3}d)LWXq`?R!PQ{Vse+D8(4Q$2g@eV=1j?x-L3xa_lf<$d+8 zw&Olu20T*d{n+EP((I`^Y3~M~f9syBrw?A@BZzsWUL~CA^XKJTwLEgHProxC)WgmV z^l8}eSuL5?%||}tn|iUeo6m)TKh+Zot$cQSsMXQWJjtyz;)6p04%} zyXSp4D@*7J@z`IsXHt8F8RjM z9A3=xF3RLSI8qOALj>#*%B(4%oOL2}@w}~>1@K=JDW|x8H!^IGf%g|O#Q=iP|Ix1#Yb;EoBii&f=)f~lm;%++}V7^^ML0vjq99~p3|AdazvuFK+clMS<2@}?cWDmh4EFS#v`-Tr z+1>M2^g)gKo4e=gu}3sZp4xg|k3O#XamCQnb<$}~z)_*6Vd^=}&h70U{_`$sidOvb z;8k4FaAp^Hh_~I)#Enn!SS7rpnLIec!}IEW&9UykJ;r!G)@<~6?-3gCOk?2i*yFDM zE6ozK>mDi1Z#8RWXFOJ3{HXB~9`u;i?W^Viv(@8C$`4I!%LP&&+G+qMYJo5Efm7hGaATk^a-#3}Kbrfdg~%wx$KpDYs(asPCUQ>Ko` zg{CY`LdIYBt#9%){W9y^Kd&m%EY2!+pX6Sq8JUyrKBBTxQq!I8w{yzEQUS9;a*t6;fyZtw)<%-Ypj|NJ3JF=vC; zh3To(Gv1>8Y2~S0uH2!u?`^L%8?;9|d8V<_+W&xd@(!_b>$byM$LpPLE|-sMwLfaz z+`gRF`s5V3?aw%`UCT*#^I~7t?s18B^K!ecojY3Vc5w1-t^WE?ZtnZ;YcF1Y=B9Z4 zSX=q)mfP0c=US7J^KKSKZ?uN;BX06hAGC!%ce>3u@I`xU(OS30A3wCbvkTn{Th-dh zKc=}k_YBf*D;w?hbw`+Xqv-&*+rOf;Lx**BOX0<9t2ev4%^#brUHiz&t?!j|ZAgmT zZDmomwnfZ$E9+XI<@9ZJ{dTxSTePmqH6y)3d+%YM>sVEdwpT`ytL%7#_Jw}9t7B1% zwspiW*CT^EwGR8=x%R%t4p4l1fblbP*DDix2dt}>y55ZKAMmOR$F+9SkbvmzO^S0VBLd>p<%+#? z#s+*9{$VkMc);@&dm)Nu6m<*;@y3TxVPN7 zXr*Vfe(EjI={E; z9XR~yRc8yU0fB{fr=5e$hX(GvdcgU;`KUmd;a2BD%khD?POWsFVK*hvO+3$8Uoj)_ z-M>?uB|dWkyK_f6kLk8I-i)nI`HRy7w0o8HU#$JS~@4~*&6u$ zUzxN2#a)5D#5`x`SNj9MooaFN2|FCv%dpC6XYq-^?^pAjgo1N{{q2*T5*3#M1D}RF z<&VA|IHt>QC+`h+0#kmzclvqlVc?RHPn=E!Jqv6}y5V%C?sedqh3A}#>^}y&*Zu3X ze)6}#$o)H<`W*QkxY1y()3Bd`fp!lTI-O|@3rzHz?quo{6L>m&j8o>S#J~x22Rh|G zPYbkY?B--&l^s}hLg{qJr!X+o(bj49ma@PXKMb9w{i+VUHdW+wTGSADp|-=3^G|Ew z#Z$G8@9zH%yss>FyxqVJ`VpG$7&=@Wl(#g-(etKWkfA8hF}lGpXyVf^j?c%L2i+L` z(lOwfO;BU?T}M-~Q;`3KOO6khy9LGfIN`V^(kp0c&R)k2s;)uhhc`LCxzaP}wD)pH zS5E(+L20uc(^n4(5*(W37@RRODARkmW98`aK>?Y)9Y_C~67=)9k7I%F%%ISo&W<0R z&J8LlGk5&yusF#4x}GEJ){3CHW4VqyEY}5nWwkhXUf&#~_*m&+YP~b)`HDP;o_F^J z4Y5ylxS%*3RG%8|;P~c5(3f++9V&XA3;J*L2Z!>IOF>5jPaSNh-3U6bz3Fhg^ls3{ zz2_Y~c0CTN?R&(5Yw$8?Sm#a${b%ojKKxwgFnP$Apx%2IJ4ELG49Xrj(_#DGfS_yq z@eZ@>!h$x04|Z4|5FNDSY!8Q@%Myb&PxEx>BTo;yYwO_f=W9+-d8vs*^5UYP3Ga0s zY7Hxb68Eqi`UlnoZ5iEYk76*$&%E4zlY2*yNoltItbBH`@s|YqP1l9NU5|y@|DGxh z-Z<;0eP1KP-~_LC_LT`{!T)d{+eclr32sikZl5#5Dfq|hv-S>l%HaD){K*)Q z-VXcT@4E$O^jd2#-`6|X(`1po@%Vwk_v)tGkG2~g+$VOd{hRtR!R@aG*$)ky6r6jy zyS@1C^x*Qf9`>C(<^)?#vbVRLwkUXGHxv7H-BtwGnd{pBFXxSXRw79`; zTh`9tIniZy`vdm}@A;f<_vPi0;E=lsc2-wU1@}4?YWMQ+h2WI!KkZg-xf*XiV_(mT`8&MkfW=)eg4HpOg{&yt0SgQ~$i+|4KdWt}ZJH zeo^FL_ijs7aASd~UE|^U;I#!3yZKjJgDnf$c1K5K&o$?X@i3kWp2+ zwoh90L)3Liw%NvJA6-{J#vq&;nv? zvqILKpJY4GYC*{T$HQ%x|FbMa{;QAer?YE9J}0Sc715hQu2j3&{*dkrc`vfE-7nlT+y_;^cbXI+cOW|0X zn?bE13e&+hwJKKViqSo67T*zs*6s7OX_8Are|~nbd3?|?H0qD3&E^*KPE$z_ak^uyHC-=-o}N9> z`hCKU&?|5Jtbc8~A6monu+BGq7J6}}y|wkvH=)Pgnpm%2^f@#_EV0g%{tES9$hMyQ zH88aAuO_S3B@v;kEh?>^nZ$=yZ_TsX5SkjQPENL(uq!9Dz%SBjsBdxTv@05`@#U4F z*6p9H);_2Y?Kby?)q{C$p?3rCT2bX6v zTv5jG`LYGpBhURc;aT&n~9mWEx4ZLw^( zUK6GnQ*HS#vpH;Vc!8yD!Ok$dk!hA;p$EdIhecZ+d~+%MOc@TGnO`^-iOt#``2>7fNx>)4xGY0G+`%? zuCsjU8ydFMWQk?7S4`O5hqEllc_xST_M2$=&NC~lTj(%L2cN>Qv$OhG-tJlvHl{{p zspwr7w*0Wd^84V{uu^Ml%bDX?;h~=lEP1np;gX3W%dgAz!rxVPT5Q{49RA~2y~UtY zR^dw5G7IB-j^XVg*%tL*l;Nu7i56*bs_-b?aEq|Y9^p~1e_Lq91H!xf^U)%}b$B?d zZzivjs7!bOv}TCA0B2p`B< zZSkPj_VB`Y3oLS%?+dS4G~L4C`jPM@X5%bYM4t{H8a3GB3-?m^*@HbTbb8+mAKKg7 zV!@^d;foubEPlOy9$x#(!os%dU3mElxy2!mZ{g!z1r}ASHQ{z8?dCJyhKA35Tx%ZI z6ca94USi&-UrM;bBg_2Vk?im{HSy-kgre{#pF+(a*j0tg_xv)qTh|a?GVFu-Elqp4 zm;N(zYh!LiaprCFn=5o8^qyTbx6$fHJlS@_{I;ce#QPEZ&F#0^Mfg~3HNTgrh_I_# zW$xJ3JK~^bf%$`rei73zPd9gJ?Hh4#%{cRWbB0FD9X`a|Hh4_LIs0Db*Sx1hbno;w zH@rS8Vsg5(`Ek+0h{7+H=6|=Yh^V-tZ@#u{eZ;aILh~&D?GdwQcbbie-xm=&u-@#| z$fFU@6=i1n0cRrkvK+Iu{VqqOHYb{eeZLjqlpk(p-TP5QX_VS*^^cbkF5f?yeeVA; zBKzqJv-ZFr5%O#I%zBOqjQDxtirKoPh=`&+r_JupONcnS@sL?WReHqZYV-jSQ96iDWh1CXU2^%b6O&byg9a?nK4@)={Byb zS?5jD$gUHVW*L2KBY#b{Gkcxo5*a$(#B9etugFPrC1yRH{UZIBa?GkD`bL(lYcajD zX=r5q&T3OX+p&@Rj~1GSMNEl2cPZU;{0{#}$49ZI;mSpk-9HDL_Q+Zp858!y^y;~d zk>y$MOsj_Pj67EV#Iy_RVB|}k+or3&9gqCS@uKPFE$1T-^gUtvzU#Hft~2(VY8viF zuG+HI^!KNyk;;p!O<(VL8@cx5Lenz?zDD*=nPECtq=`J$Hr~`WJ~VQf?J(1ro3W7* zL;IMnS(zI7X|=CuN3YySly%W5OjJ|CMSe_8389z4lJO&`NH z{k&KhwP$y;N$LPul=qt|lM-vwsFj5UCV3q;QC%$3O+vF=qK-_AHMy?#iduR+*ktBI zzo?|ZA11t${i0%7?@g|58WuI9-%}H_x#ObN?!IkuaP-tD<6jp|QhLsb8p%3oVys*e zB^h$Sq>t5_sJX|snT(Zhi5e8U#$>o)Pt-@V#U^fl|Bd>(V3tXJ^QowDuO^y2s=pYu zseQP~fZCf;o}>DiXlfotZN1jjL|OMTYD%TjWP9VsC=|pduiJh`h5l!163z~enp+_? ziPVXXIzE_Z^4>T(YShg(XwzFOj17XOMNiP5Z!D~t8|`#> znsKJpvgivPV~x*_UKf396DAV7wnY!E?qz)G)xPK>%T>lD`A4Id6f2BP%+Ey^EV40n zns_z3qtM7$cH(aI`z5-@DZx*p#pP_{UA%YE9cx;Qm?7Vy&oovW&Hh&#t=?T^bR{%A z`kXM+=#?}fnsXuE=+2akXd}BYqg6KxqJv)jHZm%$h&Jp0$>>tohGCG;6udlP_~#5eR=w$f zVX>J`?5Mum4PV?hh&>=&XE@NuGIm+Q62phT9Ai7~%r;CN=Mmd~-4w&r+^(^zfuju{ zZ|WNxZ#c+su+FephteK~FYb1!@{Jwv3_f<4c~287CUm3k>MEq z^|4ZguHn14+hY&%Ifez355&GGYB9)ZJ|25G zj@+7P@c!z{*xI=f2DgWOiXAsfYw%Cwuh_YMUkwr-hQvBMy)iJK9vget@UekHk`^1! zyJgU!$&3Bk{GY+q?d7pkD^D17_}0fh%RgY?Qr#Z=F@3v%$#Y)Zw#0P?5zD1Ek~WhyScT{+T%Zv-L`8_#NW$yXfP0ipTG!kKZvKzpFle=Xm_?`uGgu z@mc8OGl|D%qmR!h9-oyyKC^gycKY}XxNXDi2N9FNahj?X+EpS>L4K|H<- zIlhy4d^d7@NAdWsXr@eC#4S(4+KO2D%v$1|3IXHAZ0E&*;8~XAnNGm7EypvSfM;EfXFdVXz8vpB0^S8V-iZXf8*;oO z33ylJcxMvu?#S>CCE#6>;hjpryCuUrmVkFnhIcLj@16|rU;^Gn8Q#eRyqhw-qX~Fd zWq4;3@b1d+4kzGUmf@XFz`HHOJDz}dU50l)0q?#HXFwv(0vXPPM4SyWoDqpQD`Yq` z5^;9OaE2t}ERo?%NyOPA!x@u^vqpw9ClP0l3};Xx&LSDkq(q!eGMrI~IICnhvl4N3 z$#8}x;w+QlOiRSsCc_z*h_gfy{y#M!HdGdK}vu^!IkM4ZifIHMDBR_o!+PQux(hci40 zXSp8E^dy|^dN|{gaMtVL%umAEuZKGz33q`W?t~=V4SKjEl5kh(;m%0H-Jyp&Bnfwk z9`2MR+%0;zW0G*!=;6*u!rh~XJ17Zvksj`(B-~AUxTBJASLxx-O2XZxhdV3@cbOjU zv?SbZdbs0~aM$VK&P&4Gr-wT*33s6scVZImMk(&dB;1u!+?h$ZJEgcolW>9d64Xd3sFftBnNmtD6r=s@PMGugQUO*Q;K`MF! zUGxa4=oNI)Go+$-&_xfChF(G!Jw+ON3tjXWY3Ma{(Q~As_s~TTl7?PH7d=TDdJ|pr zC~4?bbkVbonlrK9)LK@XUYUQh=;VLEz49rTFl=oNL) zGp3_=)IkrKj$Tp+J!Lw2OC9u>>F70e&~v7v_tZfTnvPyn2R&&zdQ% zqj%Lo51Wo&RtG(8I(l0j^tkEhb#>75rla@OK@XgcURVb`aXNZq9rVcQ=#_QQGpD0> z)^J#{*IYaR618R)fj&~s;?_trrVo`GImjGjCLy}1}YdIoxRF?#k4^zLHx z@EPdk#pvlX(A$gA<7c4P7o+FTK<_U`29SX)K#WWv1KEHW89@fJ0x>d!3}gplWC$6^ z62!<9GLS8ZkuhW-YY-!I$UycWMh20AEJBP-A_Lik7#T$dvI;RWiwtBJVq_Q@$TGyp zG%}EFh>>w*BI^(%^TWH(}DIGM29${`NQ6u%6WNdm8Br#(A`vp9Ok_tQWJsCFl0?XqGLbEbkTGQ; zYZ4)I%0l)eLI#zEEJ}n-Dht_^2pLrtvMLcWt1M(!B4k)u$g)Jpw6c(GiI8z+A?p$$ z^U6Z@B|-+4g)B^jOe_o8m1S;*2v$keist%;DaWg%-5A#=+@ z_9j9GmxU}&giJ0A*_;R&T^6!B5i+|hWOpKDcv;BuM9B2AknM?(@ns|H6Cv}WVb?OxH-sjg~)VsknIYQ@#Y}w6(aM^LG~*|2AqQ|ScptG2idR? z8F3D>Vj(i)9Aw8rWXL(ll7+~WbC4|ykum2WYZfAN&O!DpLl|d)LS)!E$g+jVv~!Vd3y^W=BI_0)^Ug)~EkFjIi!5A#OgtCaxBwY>F0yg~ zGV@$y=K^HtxyaH5$kcO@tqYK`=OSwtAal<}_AWpMpNlMBfJ{CY*}MQ5eJ-+k0W$ks zWcLDO__@gP1<3Ssk?jkR@#iAz7a;S`MfNYi3?LV?00CwKxtI+IFeAvttU!R7K`v$o z0?ZKdFiQ|%rjUo(f&epyJj@ydm^tKO_8`CvA`i0&0cH|;m`w;UqsYUoLV%e?9%dH; z%rNpW%Mf6uk%!ra05gs}%sK>^dE{aCA;1hI53>*fW+Hi*jR-I!$-}HffSE}iW+wv7 zQ1UQK5n!g0huMk%GnPEeS_GK6RGI^NI@G+yw!>opnnN2=sH+;-+ z@-fTdW2Tdj*$y8wo_x%D_?Y?RWA?+x3@9J7AUZ%&_t? z%i?3Em5$r_Ujb%)e9Zg`F#F?U23UYuARjZq0?Y>am=P9WR>;T9umH0|K4ypom?iQt zQ!K!2k&hW;0cMRn%p40ad*opTS%6t24>QR^%qDr5Q5IrW$-~UD5VK1jW|)PTW%4l7 zEW~V+hZ$!fW}Q6DJPR@VBPGtolKMtPW#7GhS)!_2f0vr`^ssD+rN@-R~^ z#B7y^8EYYCtvt+J3o(1;VFp`>Su77T*+R@_d6>}_VphvTIb4X@Ee|u?Ldl9%jBpnEmoF11`cWn1`8g5oW_Y%!rFHE9PNlT!h&%4>RN<%#wMSDHmb3 z%)^Yi2(xA$X3j;JJ@YVwF2XFDhnaK{X45>(sEaVG=3!=CgxNI@GwdSFvU!+k7h$%| z!;HHKvu++{-bI*w^DqN1!YrJJnRpRq<2=mBi!dwaVP;;0**On0^dijCd6=meW46x2 zjJ+7Mb{=N##hAVGFoQ3~ES`s%d@*M8T+HZ;F{|fdW?ziiJr^_lV$AZnnCTZ|w$H_k zzZkQAE@uA4nEi9X02G4-;DQM#1{=TyBTx)hfD2}z80-KS3_&qi0xp<>Vz32VFb2h7 z4Y*(qioqUm!5|caMc{%-C&$% z9!kJIaKS*7fQ8_Ki6{XZ!385x0#;@MMM+sOCE|`uIupL}59wlHsxL`g?z#W~LPE3<$MEPZ?Mq4w#-Yuss|wK4oBiIADIt!2WQ+0F{9S;(!S%0~^Ev zBUA=fhy!M*4D1jG3{e?aA`Y0MGO$G)Fh*ryjW}SA%D^6Rz#x@@MdE--Dg&Fu0i#p~ zR*3^Kalk;8gN5RNi7E#h#qrM{QVv#% z17@lm>=XwKRXJEH4w$NPuvHu|R^?!=IAE^I!CrB|V3mW#;(*C22b;wKqg4)8ivwn> z9PAbc3|Bc=E)JNka=ATD+e3K0V7rcR*VB?tOD#9 z2Mk#SSTYWnvI?+e957}TV9hvS&MLs3aloKefJNhgNvi;x#sQ;N0alFzW~~D38V3wp z1z0u?n6?VAZ5%Le6=2;sVBRXgzOli;Re*(KgNdsE8^;DCR{>Uz4Q8$a>>L{mT?JS= zHki5!uyt%Ob`@al*kJA|z}~UJ;8lXfV}r@71e?bOqgM%5j}2z866_uu3|}Q!J~o)X zO0a!wFn*O_{n%jsD#8A-!2ni*1!RK>tOOg#1|wJrR*(&5uoCPb8w_D3SVA_K!b-4( zY%qqEU=7(|4lBVPvcVu$f<>W$KC;0;R)K|NgNdvH8_5PESp`;-4Q8?m>?9iuWffRTHkisPu$62umQ`Ra z*NOv8w_bRSW-5a(rU1!Y%r$PU`^RzPOHJ5 zvcaHMgGFV7Nv#H($_Ara4OW#6X0;mZDjN)IHCR?QnAU2rt!yx^)nHxOU|y@izOuo< zR)d9QgNdyM8_NbGTMbs04Q93)>?|7$Z8cb0HkjIKu(fP3w$)&5*^78v+iu<$G}@wH&%SzzRA!OFA1%-4dQ zXMv%w1xwEYQ(p_Vo(0Cf4y-*3%zYi$dlne{I%i)>!0gw7-DiQ} zuLH}^0@Ggywx0#YzYeTF3(S8V*nburfI7GUEI0vma06Iy1nS@lu;2{T!5v`1A*h2( zz=Bgy2e*I)$Dj_b0SnGS9oz#J9E3W!2rM`Wb#N0{a1`p`DzM-z)Wcn1!C|O}%fN!u zP!G3(1;?Qtt^*6sLp|IF795CrxDYHj5%q8*Sa2lj;YzUJOw_}jV8NlNhfBeNQ&A7M zf(6H-98&9I2-kFHyAh^^>8^DI34wHI~X_~ z^>95HI3EpgKNvV54RApiI3W#iLl`(B4RA#mI3o>kM;JIH4RA>qI3*2mOBgsN4RB2u zI42EoPZ&5T4RBEyI4KQqQy4fZ4RBQ$I4ccsR~R@f4RBc)I4uouTNpSl4RBo;I4=!w zUl=$r4RB!?I57=yV;DFx4RB=`I5Q1!XBap%jc{ogI5mxMYZy2-jc{!kI5&-OZx}c@ zjc{=oI5~}Qa~L=}jc|1sI6IAScNjQ4jc|DwI6aMUdl)!Ajc|P!I6sYWe;7DGjc|b& zI6;kYgBUnMjc|n+I75wahZs0Sjc|z=I7N+cix@aYjc|<^I7f|ej~F;ejc}0|I7v-# zlNdNkO>mVMI7>}%ml!xqO>mhQI89A(n;1AwO>mtUI8RM*pBOk$O>m(YI8jY-qZl|+ zO>m_cI8#kn6gI8{w>s~9*|O>nIkI9E+@uNXL3O>nUoI9W|_vluv9O>ngs zI9p9{x0ol#o15TrF>tz?;dU`_yqe*9F>t<`;eIi2z?$KLF>u0~;f67A#G2uXF>uD3 z;f~?I>TgyvTrvhuSu@-+298-XTr&pFSu@--1`b*?Tr>twS~J`<298=YTr~#HS~J`= z1`b;@Ts8(yTQl4?298@ZTsH>JTQl4@1`b>^TsQ_!Tr=D_298_{Tsa2LTnpSe1{3QR zxO5Dhx)!)~3>>=_xONPjyB4^23>>@`xOfblycW253>>`{xOxnny%xB83>>}|xO@zp zz81KB3>?1}xPA?4~xPbWkf?D7PGH?W2;0iKu23z0`GH?i6;1V)$3R~b7 zGH?uA;Tke<4qM?KGH?)E;UY3{5?kRWGH?`I;VLq47F*#iGH@7M;W9FC8e8EuGH@JQ z;W{#K9$Vo)GH@VU;X*QSB3t1`GH@hY;Yu=aCR^c7GH@tc;ZibiDqG=JGH@(g;aW0q zE?ePVGH@_k;bJmyGF#zhGH^6o;c7B)HrwECGH^KC;Bqo>I@{oOGH^WG;CeD}KHK1a zGH^iK;DR!6LfhbmGH^uO;EFPEM%&fOoXb2&cJE^ z3%8wtHmvgmx1H| z7p^}8=l?I<|Ns9F{p-#%x(xmMZFXi1{pXwBIx+Om*9=lI^yif&^kwMJ&s{W%p}#Mo zaVkT9f572|4E;Q>P1iB>^Id+ji=m%)N6%vn{ruCyFEaG|c+a}W(C^2te8tf38?oy< zL%;tSX(&UV$LL#$41GR-z493Pyq^B9LPx@4MonmA==03a6|m^@UANwlMW1&)+m1z_ z|H|_oEc!lD9D1_o`|19ED2u+Y6N4wQ==+OHn8Tv)Q)kgi7Ja|n8c?(0`<{5{5R1P5 zIY#GL^gQ@KxXGgDV^r5?EP7rPfuC6P{4`7sVA1pRx*&!{&)4*gnJjwVsySsWdj2+? zZ)DN)m~YQv)AQN?tsa}6*CPWg+4TH=i&3!Yc}|_vl}*ogUey3LJ?{y-#BruR8xa3`DI?;&ww4!!SZ=a_Kl{r_3vz@hUX zVw*RI&WCUOJ{&qPj-DUEq4T4=?LQnkPXeFM=g|4$(_;;X&YK;9J2-Uy+?{ZQL+8<> z%nKYkpN=fM!=dwPXu}H*onP5|zjEk2o2(nmq4VwDrFagVcMujJDCdcVStOXuy$&4amg{*GZLaOphGJL=D+ z^LezvaxR_M$FFbZ()oSE=>V6`^8+tWbLo8V?RT9^=Y8<6$6Px9orZtl(tR*FM$M)B zVe+&nF5MT7IcZ$FKLVE&bLl?mT3yGb`(@*1hDZ0!{tjIp-9NJrn(^p966!ef=ziLB zR>hv(kkao+FZ(S0cFag0azWAcxS zJi0H}47|sq`!go!6_4)I=8@ldbiWoyh4ARUy*V+FNB6HqQZA3~WB=(@Ji4D3XSDL@ zzV@9X;M4sbm}|hN``mn?EuZf9E=BHqy6@Cpr|>J^6- z(R`|3zLlo)sh*K7E#XsrV_Q_ur+TM+0ZTyj&-z@6fa;-lv&{umAH7U>7Erx3f10m= z>Zj<0egdke>c@{3P<<5_F-<`A){^0i1XO>$)2enpi z6+)_Ke_q=nr22N0?4Xe9-2(^D2&w*E(tKS=^>E{gCqk-^y|X_Esa`gis1Z{Ad^;dY zNcD75w{#)Z*B>4i3#s1jZC)>=`g{3tMnv^^|8`vw)#u+=nu(}h&(3fXQT_gCv`R$v zyy5r0BC79Ql%qsc?`K|_Dx&(|PqPL4jnX5znDL-(f4)v=x_Sc2O>Gt;Gh+(+!JOa1w#xhh@i*9Uy;t4sa+1)Wj4)X%S;J5`tZ`>6K| zbgAEeCtRyb{lE3Bow}3vN>pxw}3${n5A3FR}Foxe*cukl|QBBA`|>YD@!0^t4I0Y z&-N2~ln3%XuIN!d_|!`uA3pJym`*i#d6A@lW(t=QyzW) z({4HC(*cpkTC|Os5zX7qv^yHn{B2)~w-L?bZolho zMDw|-lf#W@UblS7WFwm28T6lPMDx5-la)p^->azFVnp*ki@*a$H2>Rt^|TSq1KU<# zGotz6^MQ|yXkK{O=$#SG4^I^TG@^Op*Uw=_G+&e-O){c+xGP)#x#H3edDPy&0~-F ze>A4~>|0BXG0kh+(jtv%e!K8;sxi%T%O)2Z(|q@|tj3t;y%WOQjcNYtb4X}H^I(s@ zh9)#09@=PQLi6J7FO()UKMq~sXF~I2U$a3bG++K4Io5>c%~SWyFroRgUYErtG>^_H zTxUY_>9C8tOlV#mG4!Yj&993ZE|}0f+vNUj6Pj<&neg0%=G{L!KAF(`+vkbagy!Mj zCPkaje0+LGnhDLzbsrX)(EL1pOsxsc(_hwin9zLv`c;uB&D(GEGcu+5`|EsLQ<}#o z{_Ac^^Lbs@?xr-apAsqMtsM>T`6Y7duZG8&4~XPysg@dc#yz` zRx{#5hOFb86E6~2E;lEBWbh&@bK*&UXDZBzFX=U>1b0iGNXsJTxaBW?h%J z=ETRmy7j}Hc$q>`s5$X7`Wq6=iKp>P&o(E%X41fNbK-3lJ#I87{${0wZ9zQF@^umm z;&Wytm|768GpL)R1@Sx9m%J>9=c#DyX+eC?%PB)Gi1%6WZh{5zKVq4`1@S=lRxGt3 zKFA|zg9Y(IPi*#B5IUtp>Q@k^#gg%-p!6)pHyc&N!2tSpI- z`j)A%Bwk9_xr-(7Q^QvEvm~Bs#k-M~#8+)?o?=P7)vDg}EQ!Awxo4#%@mNyz7E9u@ zzOW8h60bFCz$r`Ow*vNDu_T_$?#F#g;=2~Lys{+T>tvU2mc)NuSsi3aJlL^Ev6jS# z&CbrSBwozOxWtn9u~(z&EQu#m?(MWBzU=5bkrnY~p@oK4#GjQK+gcHiRyI_Lwpc0% z-_*^Dc(oJv23Qfl<{mTJig>oCZBwm?ZxcE%up-`V(74rB#J|njvdxNkxCu88S`i=T z7;xH(c)7Tet5(F%`RhKkBA!m``NoR)I_~)IR>a%ctPQpz{?6!hoE7nS1<&+=eukwwkE#sj<=CD@qYV;*;*6-*WF)fO*~-Wx^C9Q2PzH? zuqIw`?xoSz#1F1|Jk^?b!f~JHTN7W%3tnYSyy2;Yt=7aJmggL>CLYnE;*>SqTGi1+mQu-At8&y4%WZHNaQfBvEk@u4U7-mxKG z^z6##HpGw4n)=Cxc+%?r8XMwEhr34F5O2CfmSRKvDR4s@;!zvZDs6~QUG%e=+<)Pf z+Z5pV3eKxIe#afxjoJK~Y&WDc_4yzLs;&j(BLzxf^!GN8cRu*p7H<&$_pE z#80og^TUpK>Lp`C?1-<{YmKub-g^1{OgrMQH;*Z?BObd;L#-Y0+4rt>*b%R-=`XY= ze*0X3zCH2W^21j4#CP{oDC~*%whU3(6aW2qaUXl)!Sgu7?THT$yEW0Cc=6di{q2b# zza78Co_O+8E7sc+U#?*9vM1hr^`*o1#GlVrp0g(&z4ga+d*ajkk9%ZKyt;Sx8++o{ z!&ZH_C!SrmEy$ku_U3R*&m!7h_`>#)!Tvid&BoV9f-$w@)_ble16*VaSp`m`?}0iklK?mahH*7xTKt90blFJU{2h5&+&w+e_fRGms*7d0glb$rNAe>go{VrLU*a!&vLpEu5i@2x zl24&}v(%CN3LpLkNAfK~rtfkj|Dx&HVMp>Yezu==BtOGq^mRw_HT14NbR>V{O3`aa z@;Scxd~+nfW6h30NAf+sYNH*=|F|knb0i-`I=;Y>{1BrHRgUC~yiRI%B!48^gyTd$ z$?d5UC-O_`{xfkR-y|i@&WZe!aZ-0D@=>M^@8(2)O7-6UPUNeYeje#W{z`1+WGC`j z%64?d6^UWE>r*A;6(n*=#RUc$cKq8IP64zOt$=-6ZtYb`&@S-f9BDWhfd_v z_@8<0M1IZfPhXwLw^^MT;6(mS2rJr&e4OWwsZQkQSPac~B45XFaitUaJC_bNIg!tE z_YTXM{2sp_I?m+#Oing(CjY0k+QylDAQyp~GxrDPo>Y(AygJfUwU}|vNQQi z@~3y5$#44m;<+>VPHSI(bSD34{+r*<1m z7q@Di$*;P1soj};E7Mba7xJ%k56E1|$J)Kw+=cwC)k_^+$k)o4=IKKIR>-jKF6480 zcOB?LewUHmXczLmHtYQ3LjKpp`Z+G-gFQ`O=0bkhF7*Z%^2Nd*>~bN0?EI0#F65IX zE<5W&e%YB3*IdXq3vhYhLjKu$?kgAa(Jp0wb|F8l%NLCc`D!E1M!1l_mbfIzg?zS@ z-Z?Jhw@s9lxsdNRAg|7a{I^GMJ6y9)S` zRFGeHd1H44`F3tS2P(+F^XeR>ARq7H?qaa_etp73v`FkHb*DJ{9tNXfB zL4M!uP5&y$_xs^_MnV4H$f7F>@&Silzo#HS@Xh!a3i1Vyb3Q4^AB=ndTR}eIk%eIj z@(Z8oCn(4_?DZ>CLH?oN@?r(~h_?-D6yzsv`qru-U-82{t}FSA^Y~I%@)@^0F>xio zv3aDOEBTK3Wp1wIKl&Z*;z~YbgHvBu@*^$P!(7Rid^Tf(EBTZ6YG=5TPsu*I(3Skk zP^;Ch{LGTM7hK8Ld{ueFmHf^0t&d#E=UmBt<4S(# zyklQo$@ly!3vea>bL)SRuH=JWF->+QKh*MSjw|`19P=_)@<&Hsu5%@yw9&A`mHbl9 z8NM6&rfWqqH}X&W?K5*DA9Zz;y&L(d9V^`3$X6}T>gq=RYR~cg+{kAw{x#f<{MI^; ziEiY(`d^*tM*gc4Z;>1Mu%lM5b|XJFDshV&`LZv2?Ql8>A)bF7m5hD#=%lNu8@Ce|e1YawYl9mJ>E8$#3p=Y^RcZ z=MU;bO7fp~HJwtD4}D2_SxJ60XZ9T>`O?2nJynuF9rfd#l6-29^6yIWt22#*l;m4y z^p94Of2~}Wq9h+X^mMM0{OphK%ar76*Cy8~$=}}D(yk<*dy*O7o&4@?etPcYdzVi# zbtnJ(>1sQ7^1(kIc5^2`TzbpboqX{(?|ZwGKYlx8h&%b@X=!8K$uFN>KGmIkbC1@! z?&O~j6)blrAN`5`26yt)r&#WECtrP};~{tQ*AKg$awnf%;&sWL{Pr}T+wSDMSF4`5 zlm9+i_12wy_-e0j?&Qa(Dg)ffmlrulx|2V@$2!TKeEOb7+3w`m_Y{}7|KGRo_~TCg zy{NjyoqYV{EVc*v`6UrL9^~uy`C{ln{(j;;D-ZJdU!QRHAiqCygO>;S{_fMedyxMh z*?WKo?E`paJ<@~r1H^Ss^q_qK-7;r-(Efn5FAF_rpTMsRt2}7GK;Ej&9<*;@$dElA zw11$){D=qbBM7NF<3algihp16pnU~{&))T*{RP=`o_WwdgOBd-J!ro{c++0 z_C1VVG{KYhKdhC_@Pzws5cXxhC+&xrF>i$@?TfG#Z1kl45th$(deT0LF=GyS(te3| zl_x!E-^7>`7d>hJgoW!ZPufRe9q`DL_ESvqf9*;8D!$i$_N4t4(~hYp*@llEoE)^vE%{tUlHo)_GI!&5t? zUbJ7s@UO8K?b`_3YvV=xH(oIcFWSeU+3oE``#Csm-MwgE$A(P?xYv( z6Iqb@pBL>H`PlEK7wsGIz5mdQ_K&3TUwP3!lBY{PdC`87dqKavXkSU7Lx>mcFVWi* z<3;;S_NSzH(S8$4?_4k1can9e)Qk3?1gF+`(LR(UWvdtMN73EM_NIL)%fiIov_GZX z*ub0ishpo@;Z6Hh<~()qrhO|DYLwoze`QIxF5a|{V7g(|(uq7mK`U-%DxXDsS5VVrseBoA$vh8^7C|_QPcC|JR%L#jJUE z%A5AbIOJXQrhPKa(p%oNU#7ChBX8O_!(Q;poA%FiJNC(&_R$=D^~;;~)3n6}d(*y} z6ZO&Fw7;g8VTw2Hvk|ItylKBp-Ix+@+IQ2ofd>`nV{=3QibXg|)cr$Qgv zm($~i%!l^pL`RzX!2LJgn_=ri`*lW_Dtu_)j&HrU5AEOS+R@#I_VJA84)CGvTk@XgsiOT$Iquz5w2$d_ zV;>dmXIlGnh>G?#jXyX>Mf;oj51*obQ#bM+MuRSJ6JHt_fFFv|sA=!MiHjH`UGesfzYbg=W7| z(LSmr$G)g&Kb0J7)@ff=P-=*Z_E#O+9iyUsR^#nbRJ7m9QIoBreOK&x#VXo=Rn}3Z zqJ3EDmm5{IA1l$PQ$_o-l0$gDv_C7~U*b#qv>N{y`qF+a`F=}Z+PBq3?&wSVw`Si| z`qDnG)2_b0w4W>JZBJj?*TwBQ(3kdi4gWR5m-cy`8#uw2_Iu@Nr}@&puWp0p`qKWd zGryPk(mt@NUTb`5KiGs1n|*0t*eCbhzO+Bg{_Y`P+9!6#=%g?07h@g1;7j|)HZ@-J zrTt?S3-0;C{Wo6}{nVHCljU@O>r4B}{BM8prTt~;Jhd%-|n`_-~fiM!Cg zwV7G+E^znhW}i~Hb%Ln&HppwM{E*>!hsQ}@)?VweQcd_u5Y5BZRVf1HqqA>f7abi z^tXM`DZYt5w~L>TG|}%?Fu!FJeQ&iFb!?*ltyz~IP4vON^+f+B`r!`D9NI)*T$^KK zn&^*v>7L0=^vSIpp3_9XT!WWlP4vyB75`ro{d3Rld8&y%x<9UYv59`VO|9N&qOb0( z3DcYCuWR_i$4&Iv-S^#BP4wHPF8ZN~zPreQ-<#;ai@&(Ei9Wnr?y7F0AMd=@HBI#8 zZ5^<@iT=FbGS)WHr}yZ?Tbk(CYyHyhCi?b{{qIl{{d@0!b)tzrzLvk79;csg$;|WO z^z{v?yd)0x|C*JvuZq*>*J)nEIQ@Pz<~54b_jlIZyW{l#b+3w#(+Bu$X(UcR;2*!Y zjMEpm=GzW&`UCfW)ICn0;L+Fn#pxH^^Td!ieS=GLN5|-EPjUJaH_iJqPM_ks>1A>H6=!G6j?=gJesp1+{>3q8uZYvfc;)=Harzm* zdv!~kzQ)MF-EsOGXEZnzr_b@C+PXOXj%m|Qi`Vz~T>o?9^*?@f>BaH-Ab+m9B3?h_ zmk&0G*BAM8{4MeNBYSPWGhUzM8L!?KuV3<=R>|@DCU4x+G+zJYGq1Oa*GIXwS?75D zl-F+R8LzLh*%N8;`YSu$F)Uu6Wwdfkynf5eM^B2^ce(iF?0Ef`vDXXZ^w^x*>kmD@`b4}w(P2raC+HV_^?&Ck=o|gw+=~-n{~NrYaYceY z(!zz;CFm!;FX83{eWjHz-;todwCVoF3HnT5>XMkC-?Z|hXo9}emGvzX^qa-8LCFn=(c(_l3zSJeH2PNoFZT8<03HnqYTRApCzv^cm)!G2g1**v6Q4`a-}>^$FDJnMU;q2sHxu-`{(a^D67;>k)A{2B{jdEV z_%cBs?DiSoCFqCkU;9gfzSwuq`#V8@?BDU_3HoGz8#FsXzwC1l*CgnhjeN8$LI3Q` zirNHyv< zr^hZz)Q3Cj<;xTGz~>r>gTQfrch6hz}0@AW=W@&vBn6>MQPY?$?R>i@#me0!2U=x0*yNzxDf-m17HebJAEDM|XH@4K#9l0NCrer}zlUwUWHj!F8a zk8kgmqPw3!Bu2 zO9#f1^j~jY^H7pL?D@kVPtuS5f9sw}(wAL7{{=OlgIi;w@2q`$k%sFEao-cMIoCh7Nn{@%Gs z`o8`?cQ;PuACd$Ko-``r8j5o{$XtfAhmvWG3r( zpA(mxtnYnU*P>+D|6Bf-{$R2`_}lM)G+96V%)(Hw>Vipe&_dBBc4A}_2<7E+n5ad zf9tx@+miL`ukO4%S>OIk_Z>*qzkm8=N0asO-*fOpvVQ(cYfeqk*Z=jGXQk-xKl|~2 zrRej&a>&Ig`u*27xjaSR|A;fMNrC;pb=u<5Ts+@4}zz&puzr`R9x z%gIer>=SsVG%>|~fh!)5q}Vsmzg_bb`v-cQ*(Sw4f>UR9NU@(Fy|8PFeFcx)*DD3~ zzfu3q{Zi~RSpWK<6#ETs>@YmVzJn`|j83utp!mJmpz>V``_r5FP~4bkKwJ>FQ?eg&}aGUDfTs# zOn5s5_P^1ly8orv=kV*3AEnsu(DL%nQ~v3DcxOh6{SOmw{XWG$i1R=DImLd6VgLCf z#lDEqU(8IgKcc~%d&q=jE849k?bm3PdwHsT8<$mHoofHai&tKsY9Ghnqi#yI zpJUpLMyas>w>LU^XR7@jLz*^Dwa=sV!*Qwhdn_wSO11Cf>eHjC_J5qyym_j9ARiRA zPKEuyeb=|`Q|$}cu(fll{UMKC*CW+FktJRFq}nf16H80AZ=~?k!KwC-%v(4-)jpDW zb)!@5CyCuSKGnXGMXe{N+F!DC^wd=QOdfkAH`RWVwbKhz?K|1@>;0+rpS)c2aH@SM zd$v553j2S@!Q)S*+L!YFzn)LEKc)Wams0IhIknMisrIXU)%dMc`&Q0MdN*MD{?8_P5<@|{KIX_%{al}5I&lmhVV!uw?7p{!h zxAR!%Ya_7#ca1-*VZ=V3gMZuO8(iP%3he`H$3KBE5~8Wgdg=-?y6BC!8=9lK;y1or=~|4mDe*k`o;mI)F2 zjTV14Ibz?@h_2*8Mot9w|35?TDTvsQH2%iJKk4OZ{}-`OY3n7A zN98$B*MeJ|-?TmLL_Bmag z{$9j>r!y-)jM(?|#x0*l?0=f`z!wqwpr$XI5wRcYlE&Xf?2EeT|9*_vA62vHmxz5* zH{9|^#D1v@GXIX)H}%GEB@z3lN=~nc!2aL;bcd>l{Z#v&nG>d>6|5&NrNJAYBc zKC30|mqzTj`tIQs5&N$0`E_-~{;Rfo)<*2Zs=IMx#D1(UJ-0;c%Zfg@Jp%iGcjf21 zBC!8=?_0DtV!zgpbq6B$ZC!Q4k%;|USF}7Hv5)KP;q?*wxwhPYO4PotU*0%93j2T0 z?cbgiwa=?b<+)M&y_T*#KWg9C)w?c=+W&Q^?$W4zV3W?dB5FU_gO^?%wJ+?RYp#ph zAC}j!Vbngcfj8Y0wO?%cO}9qv8{2=w?NR&3KDzF%sC{GyFTW>hKiR7D?~B@3HssX! zsQqPy2NI+9ncce~C2GIfgY%Ja(CCLeQNpV^@!T9_Tt7~QTx`~{N6VT```G5|E5LlW6K^jC~803zWAY0``XSt zeMHp$wr}T-irVLP^tJRT?0@6ML&it#d+T`fq^SLG{WfJp?SrfPU~1HUxa1KzQTyWl z)gV7=e_Zb3!YJ(jy#-H)QTydCZT4W)zPVO=ACB5Tciy{?M(v{;+v$m@{d9v5Jr%XD zZrikHqxRSRtK|z(`|L_Lz8JON?%$8T61DH{*iElT?Z3Up3!&}XW+Q-*$);Cf6`La5H zAGNP<;G7?$_V+FC^h?w}za167MPdK%d$GlzQTzVp{`_~;{=awbE{WO)c>46RsQrK^ zE~<>$7x-jY6@~r3@AIv*qxK07?=dfGzu@OTEr{AT_{6n~qV^9Sk1dJXM|kq8Wl{SH zUr$~cwXd-3#nn;!3m@ISCTgGIvS#a}_8b27;>M_bhshf@N9{jsbKkb8eTbW4JEHa@ zURAy;YF}dQ`Fo@GCnomTAGJ^M#+MF8?N@xa=5Q4DzsZb?jz#TX?Afs{Y9Hg{57$TS zXYBg($$@>1AMZFdu)p!8>&^)5bG*3IS%LkI4fDcGCq=C58G*gskSX@kH%%Fe$v z4D6@;Pt}cqeU;Oe+#J|n`S#jd1N$r+Z@n$B-?GQ9I|BPI&)9ocVE<+Ny>|!pVP3nt zabQ2@1KaKkVE^N?*T)6+XC7Ua5ZI@A{+y)1e$8+GObP7U-1KE6uz&N@H-o@F&iY51 z1@?2Uo7f_-ud{d0R)PJU{Sw*)_IYl*yj@_w=f4iN5A6H=eO|}F{?8MibPntTt$v_u zU_a=cy}JkYg?0jsJ1DT9 zH1XXbfqkWK3?3HPU;6abBLe$O|Fv*rV87`#PmK=jJN>a~dSL(Qy1ioq`%vGUK0dG? zbzPTY9{B&U7?8I)*2KLV`D}OGqk9L0Kg}{E= zzF++}fc;NQzy77b{@OF2c{#Ap_TD3}1oqo*9{O4U`=5Ac`Rf7ff8wz_-VE%+?fvvy zf&IAA?b8DLa=&i-PGEoT*VEq(?9+`LogTpcC-v&`USQwuk$2w@?B8v)_k#fTKWSa? zQD8ss?N5Fj*w)2C)B0ZLglezppfD zaIdce`+-k+`kTPM;KqM{8`vMbb^mvPeZqI&{6hfypIqPl$H2bf{;{6|`-hu;_;X+% z@r>$U0{e+S-}7r=UvZO5eh=&~Zhh|`fqlm7I{z8iZ+uSrUjgiY@~`**9oT<--_G6F!YHeU&_QR9b1@>p(e&_nYKJ9)R*9Z1%Up#F?VBdDn9vcJuw;Pi3%h`?z+p{LS%u0{h9&-M1&Oul&@Uy@CDZ4-=90}}eziaf70QNtc{MV5H_CGr3ilc%3?%O9E4PgJHFZ_8lfc=mD zb>XqVKKR^0#{&D|fBg7Z@K0a--eZCN@$(Xo2lmN-Qg}SDU;ez`j|cY6A3T0Muzx;1 zsV=aOene(nU_bq)PwE2u>i4a#3+%6d?BWxFefIA)KM~k(-+uCmz`pyOH%rs?0@j!-Sq+Nf6%XUeE|C({4};cfc+2NeYie={SPjFvp#_R z56+!YAHeVc{@5BB#^?wih-_(B|?0-}L`LO>@{rAECH}&5S``^?* z5A1(a|9r6jP5tx2{x|i{5BuNLzYpwxQ~!Rj|4se-!u~h)?+^Rm)Sn0Je^Y-xu>Vc{ zdBOfS_2&os-^`yU?0++VzOetz{CUIvH}mHY``^sp2kd_{e?PGQ&HR1A{x|dY2m9ab zetw^@|IPgU!u~h&_YM2s%-=uke=|Q1u>Z~ce8B!U^Ya4x-^|Ys?0+*qPq6>Z{CvUw zH}mrb``^sZAMAf~Kaa5g&Ha4B{x|pY3j5#O&oAtMb3f0p|IPh;!~Qq-^A7vp+|NJk ze{;VNu>Z~de!%`W_xl3--`wvH?0<8=Pq6>Z{eHpzH~0Gn``_H}AMAf~zmKs0&HaAD z{x|pg3j5#O?=S3sbHC59|1JD}!~VDM`wsix!tX!qe+!=nu>UQ5KEVFB@Oc6I-@@ky z?0*ZNC$Rr5e7?Z`xA1ub``^On5A1&npGUC&Eqp$~{UQ6KEnRD^mz&U-_qwN?0-w2r?CGmeZIo}xAb`n``^;% zFYJFypU1HOEqy-2{UQ6 zKfwOC^nC&Q-_rL7?0-w&C$Rsme80f{xAJ`h``^m<5A1&{-$$_jt$aVh{Y-mKf?aE@_h;W-^%wV?0+lYr?CI6 ze80l}xAJ`p``^mY++AHe>%_PhZ5-`ev7?0;*|6R`iSJzv27xAwdN``_C02kd`q&m*w^ ztv#Q>{Wm5AHn{&@w^24 z-^TM3?0*~2Q?UPSJYT{7xAD9M``^a%7wmr<&ttIvZ9JdB{Wm5AHx2(@w^E8-`4XZ?0;L&ld%77Jzv89xAnXU z``^~{C+vS)&!e#aZ9SjD{Wm6AH)8)^}G!G-`4Xp?0;L&)3E<-JzvBAxAnXY``^yQ+JJ0j5|Lr{A!~VDPybt@|&htO)e>?93u>bA6AHe>%^S%K4-_H93?0-A& z6R`j7ykEfnxAVRM``^y{2kd`4?<27P?Yy7B{bA7AHn{&_r3)C-`@KZ?0jd`@8EqD_P>MoQ`r9w-dAD&J9vME z{qNv?7WTh`_gmQi4&HZR|2ug9h5hf~eHiw?gZE?D{|?@lVgEaLe}?_<;C&kQzoYkS z*#C~+w_*P~djE#~@92FT_P?X|bJ+im-q&IOJ9>YI{qN{~9`?VZ_j}m?j^6iS|2umB zhyCy9JOK8;qw@jS|BlWJVE;QhKY;!3=sW@TzoYX7*#C~s8({xCI)8xu@8~=N_P?X^ z3E2Nm&MRR5J2}6A{qN*F1NOg@^9|VlPR=`E|2sMVfc@{}JOuW?lk*YS|4zTVVe?Ie&ru@8moN_P>+!8QA|$&TC-*J2}6B{qN*F2ll^{ z^Bvg#PR@H^|2sSXf&K67JP7u`v-2U?|IW^fVE;QiKZ5=5>^uqfzq9it*#FMXn_&Mt zJAZ=x@9aDZ_P?|9DcJwc&Z}VmJ3GIE{qO8N3--UW^DWr_&d$4F|2sSXg8lF8JPh`~ zv-2_7|IW_KVE;QiKZE`6;yexZzl-xV*#9oh+hG5@IDdov@8UcT_P>ksIoSU$&g)?R zyEwmt{qN#D5B9%{^F7%AF3$U4|GPNg#GV&5A#si|E|tQVgI{2FNOW@>iiV;zpL|9*#EB1S7HCVI&X#j@9O*&_P?w1 zSlIur&Szo&yE?Ch{qO4h7WTiZ^IX{fuFiL1|GPQwh5hg5{1^7WoAY4U|8CBQVgI{1 zFNXc^=KL7;znk-9*#Bnfc@|8egO8ryZZvz|L*P&VE?Yw3fTW1?k`~fd$`Yl{qNy^1NOg%`wrOu9_~M2|9iL(f&K5{egyWvhx-!P{~qp7 zVE=o#Pl5gK;eG}7zlZx4*#92xUts@xxQ~JT@8Nz1_P>Yw8rc6H?r&iKd$`Ym{qNy^ z2ll_G`ySZ;p6-8O|9iR*g8lF5ehBuzr~4w<|DNuTVE=o%PlEmL>3#|Jzo+{q*#DmH zpJ4xcx{reW@9BOD_P?k5D%k&??yq3~d%Dkp{qO013--UK`!3l3p6|=I@teS z?(bm#d%4ep{qN;|5B9&8`##wJUhe;3|9iO)g#GX3eh~J*m-|B4|6cA7fBvzum-|H6 z|6cAFVgGx%Z-o8t<^B=&znA++*#F+{Ct?44yRU@(@9q8)_P@9LOxXY4?l)ood%N$1 z{qODm6ZXHi`%u{b-tI?X|9iVHh5hgC{uK7VxBFDs|K9FbVgGx(Z-xEu?fw<^zqk8X z*#F+{XJP+)yRU`)@9q8;_P@9LT-g8K?ssATd%N$2{qN)c7xur;{p^Eb|NFQfhW+p3 zz8LnukNacT|32=MVgLKMUxxkfw&YuNuj z?z3V4`?%kR{qN(x8}`4C`)}C)KJLR||NFQfhyCy4z8v1VgLKOUx)qg z>%JZKzpwju*#Exn<6-~%x}S&r@9VxE_P?+Dd)WWJ?(<>)`?}wU{qO6(ANIem`+wN~ zzUBd7|NEK`fc@`lUI6yLulWJk|Gwr4VE_A?FM$2;Yu*6%zpwcN*#Exf5n%uOnoofJ z?`vKG_P?L`1=#<7<{4oB`uYmpUXWjz#zn}RF*#Ca!F<}4una_az?`K{E_P?L`4cPyF<~d;h`9>`Kh69N?0=eh9N7Of^Et5pY36lc|I^Ix z!2YM1=YjoCGv5RIpJv_%_CL-15A1)Mc_7&TH1k2Q|7qrhVE@z155fMYnJ0q%PcvTx z`=4gs2=+hC{1NPbnt3GH|1|SSu>Wc1m0S+hQ{^7+HNboo?Ee7sRZ z7VQ53^IEX~1I%y1{tqzE1^Yk1d>8Eh0P|k3{{zf_!Tt|04+i@`zS+h zkHP*AFi!^iKhS&`?EgUXX0ZPQ&7Z;k4>XSk`#;cp8tnf-^J=jF1I@3&{tqiclK=W>}{{zjx!Tt|44+r}{(0m;1|3LF{u>S+i&%yo=G*1WnKhS&~?EgUXcCh~g z&ELWP4>XSl`#;cp9_;@>^LnuV1I_Qj{tq(G2m3$Bd>`!pAoG5(|AWl`!Tt|24+#4| z$b2B|{~+^%u>XV155oQrGEWHmKgfI`?EfJ1hOqyG%pb!34>FGk`#;EhBJBSl^NO(l zgUm0&{tq(G2>UXV2Ps08WHctur zKiGUF?Ehf%mazYW&0oU)4>pep`#;!xChY%U^O~^#gUxTk{tq_K3Hv|Td?)PxVDp}^ z|AWnc!u}674+{G~*nBAL|6uc?u>XV2kHY>BHctxsKiGUJ?Ehf%rm+8m&7Z>l4>peq z`#;!xD(wFd^Qy4_L(H$j{tq$F3j06Ad@Jn#5c96E|3l2b!u}624-5N0#C$C5{}A)C zu>V8M&%*u>F;5HoKg4`3?Eet+wy^(0%-_QP4>6Am`#;2dF6{ph^SZGAL(K2O{tq$F z3;RFBd@t<(5c9sU|3l3G!u}624-ET1#C$O9|4{S7u>V8N55xWsHBSutKh%6N?Eg^n z#<2fG%^$=54>gYr`#;otGVK3Q^UARQL(MP4{tq?J4EsOSd^7C-Q1i~P|3l3`!~PF7 z4-NZ2)OV8NPs9EXHBSxuKh%6R?Eg^n*0BFW&0oX*4>gYs`#;otHthc} z^V+cg!_05P{tq+H4f{XLd^ha>F!SE9|HI6G!~PF54-Wf3%zQZP|1k67u>Zr%kHh{C zGfxitKg@hN?Ef(H=CJ?6%%8*l4>OMr`#;QlI_&>2^Xjnw!_2S4{tq+H4*NgMd^_y_ zF!S!P|HI6`!~PF54-fl4%zQlT|8Vp2u>Zr&&%^!?H%|}yKiqsh?Ei4{_OSoM&ELcR z4>ykw`#;=#KJ5Q+^ZKy=!_Du*{tq|L5Bopdd_U~}aP$7K|HIAy!~PGK2Y~$_E*}8< zKU`h__J6qi0PO#8c>>t~;qnEr|HI`CVE>29AHe<(mq&p8A1T|E9bo@Q{KG$V2}a06!2XYrkAVFjAuj>@KSF*2_J4#t1?>L_`3l(o z5%LzW|0CotVE;$RW5E88kk5eqA0e*+`#(Z{1NMJ}JO}Lm2>A}!{}J*Yu>T|EKVbhy z$b-QCkB|?6{U0GO0{cHwegyV^q&x}i|48`~*#D98Cb0h_`M_J5>2 z4eb9&`5M^&k@7aM|0CsZVE;$TYgve_;Pd$pgXukCG39{U0SS1p7ZqehBt|lspma|0ww)*#A-TMzH^* z{*RJRg8d&QuLS!)N`49Uf0R5E?EfhFCfNT`@=mb-qvW4p|3}F~!TyhukAnRlB`*d0 zKT3WI_J5Q-73}{g`6}4|(ehTX|D)xvVE;$UW5NE9md}FyA1$v1`#)NK3-*7sJQwW$ zX!$PK|IzYZu>YgwzhM7I%Y(uGkCqRE{U0qa2Kzr+ehl`1v^*K?|7iI#*#FV;X0ZRG z<ZuLk=+T7C`of3!Rs?Eh%_wq|Shjh1(V{U0s=2Kzro9uD?@ zjC>sI{}_2W*#9x|bFlwo>g{*RHjgZ&>Pe+TA0vMV`#(k=5%zzKd?M_By1XLnf4cl4?0>pEBkX^=d?W0Cy1XOof4cl5 z?0>pEBd?f6Dy1XRpf4cl6?0>pECG3B?d?oCEy1XUqf4cl7?0>pEChUK@d?xIF zy1XXrf4cl8?0>pEC+vT^d?)OGy1Xasf4cl9?0>pEDC~c_d?@UHy1Zz|SNEmMkHY?^ z%ag+Xk39*#6!w3tyeaJeSou@f|FQC@u>WJ_Q(^zd%B#ZukCk7A{U0mO3j04+z7_U= zth_7i|5*7~*#EKeu(1DQa%alVShI$t%PDkCR`9{U0aK z4EsM$z8Us^oV+va|2X+)*#B|z(6ImG{*RNNhW#HWPYwG&PQDuUf1JEE z?Eg6VYuNvB^4PHd_ygBUuc=>bK|MBwZu>a%b(_#O|%d5lw zkC$JE{U0yS4*Ne|z8&^|yu3T?|9JU#*#GhJ@UZ{m<>O)h$IHvZ{*RZRhy5QfPY?S) zUcUbRy4~aD?P34N%iqKPPmsrl{huJ85BonsULW>Tv|DT`_fd6cQegOWv6Z8e}zn!2zfPdBmeFFTmC+HX8-!(zs0RQd@`Um*4OyJLS zCx5mH`U&{6PS97tpM8S<0{$)&^cnDXo1ou-zv~2j2mIY9=s)0RF+m>!Kbr~q5%^h6 z(3il^Zi4;sd^;z)Qo~Yk~&-z4t7ku_7 z>c8N-Fi{@{-;Ig-G5D@b)R)0`XOjL5zDtwzY4F{eq+f&Y+9Z7&eD@~l-{8AANgoH_ z%}M$>_^wXU*THvplKu|9%ainZ@ZFxI--GY^Bz+%z_b2K9;8`$99|+HeN%}!}R!q_t z!n0$N{t%uelk|!3Y?-8AglEkpo;kPk?3tv0glEwteIz`aCg~^PSv5&t3D2%c`b&70 zP10w=vuzU3xZ8QwP11M5vu~3A6P|^W^r7%rdfXI$56z&(_KM zRe07;*0;j5ce4H!p2d^(vG8o3te=Hv^<;f5Ji90J48M(M`DA@AJliMhci~w-S>FrK z{>l1Zco$682gAEzvVIue6_fSF@a~wbKZbY7WPLKcTPEw5;axLX-wf}b$@*t_7fsej z!@Fs+ej46Yll9f`?wYK>hIiRyeKx$?ChNE1T{l_Z4e!3m`fqp_X7EnDjdx>)ejMJF z8TxW~cV_6%;a!@+JM}i+tr_}tc-Lm=+u_}tp?`;WafUt~-pv`jqZ{$A&d}GxyE{XF z5AX5}eLlR~GxYoLuFuf-!@EC2{|{$@41GYH4KnltaaPFC7sS~iLw^uwi41*0oGmi+ z3vt%S&^N@{BSZfXXORqjM4U}B^b>Jb$8&eC(eRX^g(epoWdFLR?do3 z^hI%YoT5L9v*Z+gQk*TP=$GQGIYr+TXU{46r#OpF(MQGEbc%i|&Z<-NRdIHm!Ws4! z&azYVS#h?VqThusXvRebf!Kn&eoaw zwK!{M>f7S%ovD9|vv{UHF3#qe`nfo(XX@+X?4GH=i?e*DJ}=Jpnfkpr>u2iw;_RQP z|BJgoramz42ATT7xGQAp3*+vPsXvUnM5aD5?iQK)#kgx^a_6|2yGN$}G43Ln`pCGO zWa=m5u9B&*jJr#w{xa?|nflDQ+hpoDOkj?ow0rsd2ZOs$Y$})>M6K+`XpiU*j$|RUaF7v#I*oxT{Uo*T&s#s{S_aa#QuW zakrbQ-;KN8RDEyU{if=F<1RQ=9~^hXsruo#D^ArH_tHI+r*en9iM!-feRA9_r*g-< ziM!@heRJGBr|O^ME;>~o9e2~I`suic8VIJXIeacjKwtk#FLzJXK#Fcju}4^SDb-)u+eZdMbD98@X#w)wjppdn$ME8@Y>T z>Eq*Wo~56UyLy(sKJM;W`un)cXK|;$k-L4Cen0N|S^ECC`)BF@V-}FbOyEXl16le3 znH6N|3uJbXr9Y5aLY6*3W(!&R1(`Ku=^JGBkfnc+SwxmTLS_?L`U#m;Wa%qpc9EsO zkXc5SK0{_3S^5o`b!6!~WcHDz|BzWomOeygBU$04y>lBIuUc9W&Qky%cbK1XId+01xuVAhkZ?~&P0 zw*E(ELD~8snGI#@hh$cituK<yu=*l&xQqSyQ&YNoG&k`X`x1W$UA4 zHkGZPl37)@zDj0S+4?J)Wo7HLWVV&9-;!BZw!TYdU)lOEnT2KR!(=v=tsiqypXajm zWimU<)}P5NEnA-^v$bsfn#|g=^=&eH%htciEG}CgC$qV1{hZ9|vh{T`yUW(!$t*8h zpC_}uZ2g|h`m*(XGW*Nc|H&*cTOTO1!EF7Y%nGyhg)%$L)*s3&F-M;$v&9_!qRbj| z^o=rm%+Wu}EHXzQDYMBO{iMt)bM%!myUfvF$}BTSpDDA=9Q~%uI&<`$GW*QYf66R0 zM;|J)(H#A#%t~{ZnO@KAG)I3bv(y}BsS#gfOSZ2pL z`eT_T=jfAVww$A1mRWO-zFB6^Ir?XrMd#?FWj39opO#s5j=oxE*E#xYnPunbvt_oO ztKXJccdou$X5YE`Z<&SX>ceF=o~s|1S$VF$TxRFF`g573=jzjCww|kBmsxwRzFlVT zxy<0NV-}yQkC)keu6|x-^||_bnce5=?`4*stIwC&ey)CBX8pPPewqE}>i=aIkgE@v z-9WB>V0Hz$`hwXV=>iW*3pGkC@#=u6|;66}kF~ z*OW=|lB*Ay-AJx}WOgOF`jXk53?Pyl&24x-B6x>Xm&+;`l8t#<>`-Rmz1YZn%z>Kera}1dHSZ=J>}`2W*3#G zkDA?79y_XQ*j44}t7dnVr@xwAR-QgAPn4mB$Y38g^lM`mouJ<>|*} zSC*$Qo84KS{%m$>dHS^3t>x+0X4jUdZ=2m)p8joiae4Z<+0EtY=Vn)zr>~pcU7r4K zc6oXFyxHyL>Gx*Wm#6QW-Cv&mZ+3xs`oP%@=CLEZnq6U@zHoMjdHTcICFbc9XSbNA zUz}ZIzP@pGkNNt?*+u5-BWE|6ub-SoaG!nXliRU1z?&b9SHk z`p?;g=IcXeH=3^>on2|ZzI1k{`TEn@rRM8XXSbTKU!7fRzP@#Kulf4d*~RATV`n#; zub-V=ZN9#CcDMQZ+u7yjv(vqb-EO{qcXqw``rg_7=IeiF7o4vTp51W1et34p`TFA7 z9p~$hXP2C>PoCX!zJ7Uj&H4J~**)j$pJx}HuaBPHbiRIicGda%>e*fA>#t{*ov+WH z-FCiydv@LV`tI3%=j*>`7oN{f{7QD?`TFtMmFMfrXLp{jKc8KCzCL|+>-qZi*|q2E z+h_NluYaFie7-(@cJl@L`PtPM=<8>9U!cFAU4DT+e|Gx?`u*AU7wG$E_g|p@pDaLu zeE?(w3hW0UD^Orx0NH^8`vb@l6xb&~wxEEF!4+f;3hWyodr)Bi09k|r`v}M;6xdHd zR-wSY0_~zA5oAdU?2{l{QeeLX zS(5_$Cdi%?*gruQrNBN4vMB}jQ;=0Du&;vbN`d_qWLXOAvmo12V7~=fmje4P$i5WV ze?bZF@^SHkd-O4FN5q%AsL#>$kG(rr$M%+(0&cFHih4~cAKk^M+yC5!A!B0E`Re-c^BBKwrcRuMAov%z9q7kMfNX| z#VoRqiEL(({Y+#vi|lJ6yIEv^6Isq8`<%#j7TNDa*0adIC$gVK_CJvYEwT@aY-o}F zP-I1m?295hT4a9|S<)i=q{x;Q*)K)bw8*|GvZqC4P%k8lT4Wy;+0-I3suz+~EwZnQ z>}rwyRb*LW093DvM-D5Y?1w0WNC}+ z)B3UQK#~1gWNnM=+ah~gWd9af+#>t9$mYiE=OU{cv#*QnZp{8Jvb-_-yvX*($oO7B z);DI~7unyK{a<8(WA=fO4UX9lMpigxUl`fpnEhd7iDUMOku8qdFGkilM&|eevd1y| z$H*eb>?0$a9J8N{ta8l0GP27t`^(5O$LupB+Z?msjI49azB97VG5gQRLdWbwBO4vF zAC0VZ%)T_T(=q$g$Wq7bQzKg)vtNy@b|-OF9kZW}tai-4HnQ6> z``gHJ$Lw<>+a0stjjVUfzBjVpG5g=hg2(KGBO4yGAC9be%)U6X<1zc=$dbnf(kDl@ zJZ8TfS@W2Eb7aqBWYGUb7CmMk9oh7l{d8p2WA@dNU60vcN0vQipB>runEiHS-DCFM zk$sQZe@7NRW*;8e_?Z28WaVS_<&m9_*`G(2K4zaD+4`9MdSvZm_U)0qkJ-OR7C&Ym zAKCnv{d{EgWA^ot-H+MdN0vWkpC8%&7#aWb$oj|Z`y=}wv;PkkAZ8yRY(UI@Kv;p8 zeSxq8G5Z5y31apM!WP8r7lbv4**6G#5VL;}79j?ca2{+z%zi>xg_wPXunRH!3t<^z z_8G!9#9$oGg>{J8cL@6sv;PnlB4!^VY(&g{L|BQKeTlFWG5Zr?DPs01!dAp!EY5|s zh}pLYdl9pL5f&q6A0uo=Xg?#YMrdCn>_%vRBP>T~pCfEXXul(@M`+(8>_=$-BP>X0 zA0%u@Xg?&ZNN8Uq>_}*TBrHh?Q*sV$NeE+d4y;KCb8-&sNofBhEJ|n}C2UG)KP9Y6 z2(xky>`G{VB`iy5pCxQdXul<_OK9IE>`Q3>B`i#6A0})}Xg?;bOlV&w>`Z8XCM->8 zpC)WgXul?`O$c*yHtbDk|0XO>2$OR*Y))uDC#+6rUnlHNXn!XxPiUVfY)@#vC#+9s z-zV%(X#XcHP-q`0Y*1)FD6CLuUnuNQXn!ayQD~niY*A>xD6CNkb96TBQE2}tEK+D6 zDQr?`KPjwIXkRJpQfPlEEK_KoDQr_{zbUL!Xx}O9QwRff7A#a~A1Z8AXg?~fR0uP5 z7VK1Le=00hXrC%*TyRdkneY~)Fq5ZtDdZB&2 zuzR8Xy|8?teZH`LA&lP{uzsO^zp#Iy{lBn){QHv5fDH`o2Zj|4VFu5D9SrRch9wN` z6NW7e?H7hM4DB0+Jq+z1hD8kRBZf^3?I(s+3}F^ehg}TqFNS3d?K6gL4DC0Dbqwu0 zhJ6g}KZb=2?L&r*4DCmTl??4mhMf%UPllxo?Nf%W4DDBjwG8cBhP@2!UxvjD?PG?` z4DDxz)eP-xhTRP9Z-(Uz?Q@3h3}HM^gY^vUdxrfC?SF;^4Pio0gAEPshlUjm?TdyT z4egJHB@OM9hAj>4mxeVB?VE-@4eg(XMGftvhD{Car-oGx?W;chlvN=N>uIp8p?%h{ zts#u-X|S%Leb=zBq5apeu%Ug}u(6^2*s!u8%8`{qes~g(a4Z9oK-wn$f+UE`18^ZXW3hNu%_YM0S+W!p;9NGsC z8ywmX4l5kO44(o!9NHfaOB~uK4qF`BFAi%Q+BXh+9NIq)iyYcV4x1d>PY$ab+E)&{ z9NJ$F%N*Kg4%-~sZw~7m{?m89VSi}~v^~;80|N5tgL;KiavqSsYVYNg1+F`dt``cl;LzwQ9VY@>Z?~`G@L;K!g zzeD@qVZlTD;9tWeL`|M%cL;LMv-9!8CVc$a-_>*AaLzwuJVB^`jdVdTOY#Ip9EVU!q}e#Yahbgp9Fg!!r-3-iyy+|p9Gs9!swp_s~^Jbp9H%f z!tkF2%OAq@p9I?mS1WpHyF8AHx6t^MB(6sP{j|5m4`cA7?J+&9}b5T{yuR!obdOH@biUZ;soq}h;!nEpFbQFC;U9(q^R@riKC*<&nwP~IzPWS zEb9C`N1fkCoE&w2KXG)_`F+LNQRnv;hew^?XPh2&e!p>i9QXT<^W(VR ze;gpkeIDQhIqvfTN62xX7dS(X`~1Kma@^-hN{_dW`+UJMa@^+)&XMCje{hf-_j!bq z2l2HJC2uQKJRh99P{~)1Lm0T1Dr6&d_UlbIp+HUXUs9*A2?)=`98rZbIkY4 zQ;*jl^?ieL=BV!<95hFLAK|1q>iY>t%~9W1IBSmj{=#8%)b|-qo1?zpaNHdAeTVbr zsP8`0=X`w>UZQQw!(|2E*L?@t^$M}42-)H&+=^~%NxM}6Po+&Sv|7YEN# z-^Vz4j{1Ja(L=E8hY)Aa5#Qf9e2(}&$LVv#_dAZCBfjr({v7fBj|1q4=K-8RM?4?k z2s+|<0cX$=&ks0+j(DEHDRjj11&*O3o;Pp~9r65ugXoCo5u8LvJfGkwI^uZ+XVDSQ zFF1^jc%H#&bj0%wj-w-9FS^oJfZ~AK^$k?0E@i(qYd}jqmvLu;(e9 zN{2mP;aEECc?;*#Vb5PUm=1d$!^w2m^BIn&!=Bf0HXZi-hQsNw=Q*5ChdtlncslHP z59iZi&wn_e4tpNN33b@>A&#iSo)>XO9rpZ)L+X&{Nt{xLJYV9NI^=m1=hPw3pE#%v zc^<_{b;$E6j;ceRS8-My^8AX!>X7GIoK}ZC-{QDB$4v$n!Cd ztV5ocab_Lz{ES2EkmqTfT8BJeGGq=Xso72R+~8_&Vr$ALrLW&;K~U4tgKJ33kx?0gkYP-WPC&9rXTyL+qgU37ldF zyzxO^pA`Js;Gp*voMi{Szu+)C=zRvK*#Yl2IL;1u z-@$oy!21slv;*FUaH1XXeuN|KfcGVwX$QPN;ZQr^eF~@A0q<8h)(&{z!nt<9`xg$j z1OME|J{@_$`x%b51K!tgwjJ>PhQsZE_c@$y2fW|mcst;I59iwf?|(Sp4tO8L33tHz zA&$8H-WPGk?f3qOLvFwKNt|-~y+u z_x_5*Zol_goOb)Y-{QF2?|m2N-G1-CIPms+AI6Ed-}^C+y#3ynapvv!{)|I!zxQdJ zdi%X!B)C_j#Ot`@G-d_}k}w zALrjb@BcUe_c;&13AoSs0FJRj=iol)4>$<- zIgh|exX<}SQQ=wpoLAs1-0S>eZ|$zV&NFZt?sdL_<8ZI@4xER3oqym!-0M69C*oe` zBRCTGIxoSQxYzj!4#mCBQ*bKob-sdQaj)|hoQr#%zu;ip>pTW0<6h@8I2!jluff^4 z*ZB<&$Gy&Ta60aFzJud&uk#+9k9(c};DFrYJP0S`9_K?iBKJ5i!Wp^8`4JAuJj?Yt0Y=x*nSI7D|lPsAy@+xa4n(cR7)agOeG{)mHgxARDxq`RF@;watayb@>W zF6WmxOm{iY#A&+A`6iCjUCujkp6+t~i34?)^H7|qyPS{WNZsYU6ldx#=chPScR5eR zsk+PgDvs4%&RcP=?sEQ$gLRklSe&f8oX_HD-Q~O%XX`HKw>VsPInTxEy36@4j@Mnz zdvU(*bpDG2cBk`ToUl8c595g4>AV`v#$IAnJ^PsS;`)A=%v*`3atan9~^{)~fm zr}Jo>v^$+o5`*Hs6aQ=@2c!&D{oWMKW58w#i;l2Q8@DBF}ID~h&Prxa> z!~Ft|;T`T9a1QTq|A2#dhx-Ve#M|9Z;3(eiz5-|QcJ~)JjJLbbz-heQ{RWQX?e05p z9&dO5fdhHF`;bNZ-`?(i1V{3A_a!)!x4S>Vp}gIF3Qpzi?pJUuZ+G822V6N$_g43P zIKQ{L|HA>k)qNmN@U89#afEMmUx+h&tNTM7;#=J(;uPQNei6s`R`-oK$G5tF#6iB* zeI!out?nmrly7lgiL-o*`%4_=Tij>jG~eQW6UX@$_nkP;x48erfxg9kC{FY(?niN? zZ*gCWGkuHuQyl7B+^6DH-{O81$NCoctvJ`WxPQgLzQuhkPWCPCXK}P|abJtGeT(~B z9PV4(=i+qV;(iy$`xf`TIN!Ip|HT2n*?llh_|5Kzal~(SUyL(;v-@Kl@|)c!ozj5Gib{~!tf3y2>9Qm8wm*dRe?EV~w{$}^-IQ2KXU&pb($$dM{{Y~!Qaqw?) zAAd*Qf=%w{arAF;UyrkYllyxd{+rzAp>AHkl8g zBVdzx0XhRVnIE7-V3ThdIuACQf1m?lqj?BA5jL8Spd(?Uc?mibHkzNHLt&$N z3OW@wny;W^VWW8qIu|yYzo3I*qj?NE88({Fprc`E8_cWFS+T+V3LO?3%(KvGvB7)`9TywSyU=;D!Tbvy7#qyP z(223Zd<-2K8_dgGeK3B5`58JiHkhZOQ)7eq8ag&Mn75&GV}tn{Iylyw$DxyBz4;tE zI@X)lp|fMX`5ihu)|=;{(__8)9y&hOoA;sfW4-wwIzZN&2ci>Xz4;(ILe`rXqBCT@ z`5`())|)4yQ)IpQB05Ian>RZ1|9Y%9e?$k#dhhnX=CO6dfw-%u~^+vd(-J z9V_e1ThY0)&ioY}EbGi;(aEyTd=?!o>&$D>*|N_379B3@%yZG{vd(-L9WU$5d(ru_ z&iof0Fzd{N(FwE8d>9=u>&%PM8MDs(7#%X}%#+b6v(9{(fkX3Vbk3|be?|w*TJvah z(yTR~Mn}zB^J;X~tTn$zhs|2^Y;@YJHQz?Z&06zrbl$8r|3(MSTJvyp;;c0vM@PZ7;g74=nE#^#XpMP5I)T=h52Pb#jd?*jgVvZIq(f+pc|tmc z)|fA(V`z>I@=1J+4sx@Cq$5gF(Q#z+=&7aaiRcjuVPO4h-sdQA;npdT> zYPI=QI;>WkXQk6>wfR;$u2!3OrSodF`ByryR-1>V6Kl2kSUR#+o0p|CYqj}VIE9n-``tY?b+8I>c6)C#F+umHFb8X-ig_H>PuJ zmHA^j$X1z0rju-y`D8lER+(3(vuu_5Wjf4OnP;ZcY?b+DI?h&^cc$}fmHB5n&{mm; zrW0+I`Di-QR+*QkGi{amX*$$anWv^xZI$_II@VU1x2AJ#mHBHr*jAaxrju=z`D{Ac zR+-nPvu&mMZ93dmn&+m|ZKe5cI^I^A_g(;2tY z{5TzQE6tPBDYw#mIURE=&70FXx6=GM9ds+rqti*Z(tJ7{bt}!Q(^asknun(oZ>9NoI`USUm!~sth530p^j4Usr&Di*`Fc9` zR+zV^b8m(Ddph`5n8&A+Z-x1MI{H?a*Qc{@h53Ct{8pIfr_*nR`F=Y7R+#sv^KXUu ze>wnH$OF&`xI#XFj=&Z20(1thkRPB!aD_Ypoq{Xm3+NbJA#XtE;0pNzItW+DBhX2> zLOy|x!WHrgbQUg`U!cQqxjX}%hRfv}=r~+1??C6_a`^{35SPnC(22NQK7x+K};1%Y)Dfxm-Skj>zTmB6LPBmmi@+a+y2{os!GsOX!$f zCT~LLOE|cG(!*iKD&!9mkmdf|g@wrsqhtAKX@;`KdE|mwO6LhJ35FMdQ<%Q@B zT`E6Bhv-syB05Ev$`{cwx>Vli_orT4Dt|-==~8(lI!TwxC(%*5R9=bB(xviCbeJxc zXWG?k;8OV}I!>3$JJET%RQ`z$)TQ!JbfPYmkD?=Wsk{`OsY~Uj=ullMPerHdQu!)6 zR+q|K(Yd-r{)!IPCGuEwvM!O&df}DjOXRiaY+WM1MThGWc`iC#m&kX~@w!Cbi_X_2 z@?UhoE|CYL6LyJw7#*=oGG zc8Po%9kokNg;%4qc8UBN9kxs4+32)gBHu>G?Gkx6I&YWAztMraL>`V#+{N;7bmT6U zm!mUxvHTnzx{KxM=+s>-Uq{F8VtG3{cNfdw(ZRb|9*<7m#qxP{^e&dyqqBFh{2m>? zi{<&~^j$39N5}7Cc|SUT7t8&FP0aiGkCH5ARWSs>xe z$v;+P&sro8Nhk6m`A9mF7s*S~nY>7Tk`CoX@|1KcFOsjMV|kIhC7sKQBN$HecBwtF$^g?-4I;R)PpZ*owxKJLIPU?m7sdQ8?lvky*dZGL( z9o7rwS?RQ1DBnuQ^+I`9IC|2* zUrWdKLU~&{w-?Ia(!sq@9+yt;h4Q&{bT5?Gojmuxh4Q;}crTRarPF(%d@mi}3*~+3 z{9Y*kO9%Kud0;xhYvhCJ2(OVBrZc=oewYsN8hK(m#cSk?=@_q(H>PvEM*f%%@)~($ zI>~F~lj$h0kyoa(yheVR4)Yp$W;)GlnGW$bZuTzd#9k)U-%iK<0(o~j?-$6w ze_P#Yfjs<0b6YNukH57hWr4i>p{4gOke`2G&20zd*je^uXl{{^9LUxnP0( z{h;|f=F9KjF<|X{dH$}MOXth?-}ltq`SSiXAC%3P z|G#hM@ALHmbX)V?eEk6bIr;PX`T{C%cyGS`fLmI>F<+lRvvDuX*DrA03y;s&H}K2P z_s`cqaK(n4`T7VFFPb!8Kf#s3sQLN|ew{dQzW#!S@ARCn&!GK+4)gUJ#GTb*zP^L? z(d7C14|?Y`p05w#=^2gY>qmHOM}ztL658Hz`F#BeRb$VeuTSCf&rYAOU*XnW$LHx= zsJn0fJpBu==Wm;*kD>1Gwe$2dH2T-FdHNcz>Njtm{)U41~56|s-f1W;w_||XD(+}~%v=`^;i>N*Pw7*lPoKm$U+2%$FVX4Z zDf9GAe3O|zPyfV*MMLK4qgb2Lcb~;rxozg@ulOh{I!~X)(lv4O^jj?L za@Rb47a#m_(>(nb%^P1cPanqT?_DxaKgOmj&z+|)WA}5X%+sGyarV)<`ZT6Iyl1X{ zjqN9GnX7LjKCGRqf1_Ld;<@@bq7TfOtDmFpw6eMSI-Y*w_qqBz_FVM+Tzww5yz%*5 z{T_GU^8Q@d|8eJj^X6RrAHOtvajrg)VE&VH^@F@J;-R_vLW&RP&($AN`plHM`b6Hk zW$ax2BJKYiI#=IFby~l<`bTa#(siyrlHRYjovWW@U{ce$`btt(B+S)cvgiK0=jt{U+<@TsK$W$qo6J&DDRBbj$g3^`YEebNXEUDEl9(o1-t~mAC_Q^r!rL%l0|? zR3=PYKS#gHyS-M-(YNyD`89L&ue??H9DOjaeEGl}{V+Eb<;~F-^L)pQIr?K( zUYkBgpUhc%hRo3~b4h96Ir?T!yxDb*{+Y_GwsZ8+T~DJ*1t3Bl(O0Sc)mLJ`)t_%G5H6-pRKRw zj(uOu*5C8@o)2d0^J%ts+HCzkAMSs7w!WYJho70P|L6AlM`r5-YI|llTR%|ei*jb` z3yNGjX}12L%kCIGTc6O9nnQmue)dKFREB|>uh~SYwH@!)^D`=x+`YuJ6hW8!rA(dejIhyY}o(N4?lgr<*rSyQcFY0~(m)%up^PMcS)f9d)K71jEfhMfI(wSK1O zn*Cg@uj#9TudDSp{rSTu)%u+NJ}|vnztgvIZ&d4hdNt?2)%u?%{PJYAKBy)qKU@v_ zKYC}|!fJg{ufH(0T7Oj1s`1tOq-NbQvRc1X*Mfo7`lc$YdR6P6O1QprwLYrXvRYT` zr`lB&t=3nSd`m*L{;Glp?ylBn_0_6dtMyy0h+JQ-@9M;~E2{NhU3SVv)%vh*9({JT zeylrYpIogk>$ZfWRr<58oxZn9pVm1SY^&0*wX0}dmABk9V^LL= zey-$BB~|*mj+gvarN8UPrr%fT^P2eE7ghSbu1o!}O5a!IuWwiB|C$`UTBQ%{;^OD3 z^n-ob{_!e(VeJ+?P^CX?)xi8JePWZhPN~u_R-Zer3if~GlV^{p(m!_Tn**x!k-c$G zuPXgy*Ozsw(pUDs!L6(Gm)(3cTBXnI{g)G}AU;Ok6n9URzO(-=Y*eNH?1tQiRr=80 zx#p@W{b&tlUR*_Ut8s&xwG`Q_5ZqJmOi(g6aSv2-|heI`el~Bx9fL)GfV&5A76bo zOCQ|utoLW>hdVcQ+AMu>Kb`iA$Poku*ym-m>}k&Vv0PvHzz#X6ehj?0+}S(x2DjnQLe1)5|NkY!>YQ@Sn$CFiYRw z=>yK11^Yidt;@-?^zr@L@@S=gzDBA0D)sff6Suumf8ULbH&p8L`{qBZD)swy`Oo4? zeSe4Vo?EH^?~D5?D)j+oB>i2fAFx@oUn=zlHt6terT)P4`g~rgPw~JYT7g@ZlLxRO%(K5|lar9Q*s*G;O_Z}?C! zrc&SG)x(BX>OU-gq<^J8#MtLOD)l3FSk$pnU*c^ix31Kmc;$bBN_~pg4os}nuXyh> zjVtvnru}t$rT)cN58ha*k8#so*H-Fh>@fPWN_~wpr(aO1zp+d0S(W-6cQrVrQorN- zLyuMHdz}3K{tEq%UAOJ1&587=(GGg?v)Dt zmRnwZu0r4CZ6_YD(0}>h$cHNQVIG)WSfL;Dq2%leeVMm^G^s*==Jw0eEA(krJU*;K zzvf?cX%+f5YchLP=-)hbd*=#$oSjCstD)`Z^Parc~(fT(qW1g+9+0M*OEj zzvs9uw^r!;95%UOh5pa%BUe@E1O4dXODpt)9=hoK3VorY-aWHIf9T$OPp;4>I<53* zxqi_x1NN8e8|}V-N4fsdv}ZPz>mz;m_BG}DNvq43mFp{wPp>K0U;5{{v&;3Fj{B;t zT)%02pTElWo!)rTFXj4A@BQ@Ka($@7`hHQaANAWaKPuOk+UTcu%k`)JG5(Em*#9B9 zH@sA?U$y75XUg@h_I&ZNa{a40T^}sh$NJm(h2^mSgB#7sD%aQg!}F8M^|y}gon8+6 zKe+j|!^`!%MmG*9*Y`SPM(=X{uOG&`mg|GPv~&A%{jeW2Xj!f=cJRJPx&GK_MMAkg z*%t3MF4r$Rx!{g+eX}$B++41IHWJ^UTp#V~%dRZfPy6wai_7)ZzOm}Oa{aa6m7Gzo z&-Tz4Czb2B9rpUsGJUrPAKhQ3|Mr`lon`uPUr*m$rXTl{fose3<*w_oqD+5on~sah z^yw~YJ-1B1?z1f_%k=F|Xt*_Wzj*Y;GX1~TzWz*^KH#6ec&to6@Pj1}mgx)5TUA)5KlrU9 z*=72KcVCuKre8QCeq5Qp;p_X3EYm-HqF`{DKH_tx_bby++`6(ynZDu~`#Y8CFYef| zZJ9pf%epo%({Fsy1F2>Dj#IylFVlbg%9eY|^daBa@QyP5$hG}%F4LDh`{f2@`jdCm zTv?`1Ir{HQ%k(S%+2{N+eal&Io>iuQdBD0;%Jea3-C0+vpZTwxL#6tfo0jY;)!)4L z((R@CoEMMUSgPN7_s_MZ`ko^fEicvo{CoPsQhm@+ee|)wkX8k6xwvw|8{xTB?t`Y(@K0{oKnZwkp-vecP!` zOZ9ipcrCf~V|?D3_r{g#_nuUJcd5Sb560eJs{i|nb8arx2VVSXgHqW4w9mR+RjMz1 z&Vfry^@smw+6ATh#4FmKQ>tJ5odc(p>Kp&&z4{XUv|N9qida6Xfd*jMSOZ2_p^5ugi`rik>TvVbDeo>fPq96Xb zahWCh;-Bg_u|$7-WxMneee&&7N0jK7|5xL|CHm$sZq&a-|9t<3y-HyJ`)##x4HS&2UTZyTnT=(m5qQ9_Bn`)?ZGTcZE|ipX6hu>bvLwr^CT zA0HEZiN5@e-&H6@Va9C|HB%sF18O~QvYSe z_5;j(W?`{?0YggW7TX`t>cp&K`vj&Wl@-JO_uZWRcd>l~AAJ8?vHb&|AO5k}K7zW` zZ;S0Gc;%rli|s4Oull4I_P@^umw!-fpTRXF-z|py@3ZpTH;e5%*mTCL#r7Yhrv10r zK7{2no+-8;q4=C9itS4{GV=e5?N7*?d4I8e3N3FeEVf^v|NrF_+qdxRmMO*dFQj*! zSZp7|@SoC)?PvJ-rjf<=HKe>Sq}cw3D^D3vY@b8RseOv=cldR4_u_y09tL+Vw*TRU zCGCpsgV@`nRk8gL)8;iTwlCtfZmGrgN32PT%{A?Uxv^`ai|?O*}j1_G0@d zF5G`}v3(S^4>T;cpQ8SvYm4oxnDE{e#r9X+@&By7cUTlx8~1-^W_yRF>{6Gqu=L(V zv7p!x6?;KcR4jmiianOZUSls&V@>QeMiV`=OYa>7lp;+L6c7V?8KF{;JuHXB| zd#-%vK5b5$v$L~iZa#i`$(U#1lP^xje2W9o{AA3#2x796G5@09Suz>(Ft!f&6}p=4D8BbZL<9|HM%Db`9ofR8_vxV7|t~EzKIt+j!|!ufhC{#f{Y(%;V^Pv{Hll z9J52qG!GE3qnuf!!TgTXk8?Gc=kZ{5rUvspZ2VI-nD^1pOKULyZU(6 zm=B^e@~#H?{!cL0zp26ekfhox8q5<>-MFN|d=bYD=QNl%vN`;;2J=T;>`!PgkHm#M zqQQKUja5HuFt5b^&pjHNlk$7k@FJ`9FMT30*$1m&Wpus$uh6%PB%$K>g)JlVSGkJT=HJCp${D!dx z`TmbLDKgYxK26AbsRr|Ea?K?g%&)mRT%f@`n}%f^4d&adILFXn-p!m6puzl`-#DMt zn1?f>e~%jTafU4KQe$4u(Hre*%+DF#+N#Dpo$-z@)tIkye@UYn^LCPM)~S*2|F{F) z&(xU5!wafZV?NK*?PY4r>*19bsWHFjfNj1S^L$pW%vNK*&%>N_HRkuSsw%1FMf#=N1?&X?4f zKjeJuoEr0pmT=CfF`tOH@}wH`ikPpCsxiN4M&uzi<{9Zd*{{ZYBfIf?)R=d4B5#Kp z^N(Uex2iD@=~UikHRdBZkKdriyd;w+Yt@*av@mj&8uOG4UZEQg;wxFMOi*Lq(r!+i z8uOPXA6u-(Jf=;~(Q3?R5~W0`F|X|isx^0n8uOy6Rt-~Qew3r#5H<4s4}10`NR9bY?K=b2m^T$Q z$X|_o|HA@$z15gUm2k&HjeP&ZgiBr3m{-Mhby8z~)%dd_ zb{*?{N|}=4lD-glf#!3L$xF%-d>w z%2H$gR`Wwjjd@(5Cx9CBxeV8TqA{;4cy2F^`CX+WyJ^hx%JzCoBj5iqwwCQQ=6y9t z+Gx!G;*u>i=7H_&YN9b8Y+Xw|jd@}D&ueMS58LwW8I5^jXDcgd%okHumea`he~jR1 z361$D9=h2u?X4#%iV_wy(U@nJYm`i5zS%k_n#R1d1A`vX zn17}-^&yRUXk7{SY0O6(u=g&Fd1-I1-J&r+jh%m;M!x@{KXqQAF<))5{C67j*8UuL zk;eSBn8oL4%wyYr^bC#pY{HCRXv}Nt={-(ke%mOQqcrmU4`t0eL}R|2-Kn2x%zL|2 zv6sgDw~MmfH0HrkQ+Cjp50`p;D~)+^oi#twm>;)QwTVW)|D%75|AEGQxmS)P^-;KsR!IM{GB()Km`C`gQ3Wxta<**+#Qe%g({hM>|3~EMmqN_9yecV%n0MJL zEQFYUc~6)RF%R>(I2U3*=6bzsh-_!l1Bm&Z7t`-U%=6T5z6UYivy*!lV&3N<=i3nT zKgkIqLFD^C zj9EMfVjk}A@v|Z3Id_kU>UjF}MgbT!Nw5c72}-yI1gAMp2Am#}dRD?jx7bdO_gP1pbVZ%^}eE);t z>H&wcH?cu64UjbFMbhL}G-!bA))k9_XW zB8d6qT>=rryz)<5g%I=0*RX{U^UUM73Lx_RA5_B^K+HQ&-p7ZSf37g%L(D_(Jja8W zj~?jGgP528h2}!cPxlSyLd;WdZstJDR~P@lfta^`P0oRszn*-T4Ka^>TsRwIKKsNj z7R0>vq9ZJb`R%FwSrGaD4|Ho{Lgf2DP;WmIV%~eq04Buz_W`dN5cA--o?$@DhYy*^ zfPK7pAp>H5yh|DdF;9NtCJJJ{{M&&P#JqVPMM2D;Kb%TJ%%eZClZ2R0FP}g{%&QkF zNQn9MNv#CLJp1W?6A<(5@9iNV=G||bOF-oNA5;`TK;-)$bU>eg$oD@ew;e#_`yaF} zA3)^$A9V31fXMehXxKpjk?(&{#A*PM?|)F+8~~B;e^6H_fXMehD6t=a$oD^Jp(B9E z_dlrI3_#@jAN02rK;-)$WW)y$`ThsJW&ntM|AYDw0FI&nAn_jn01RRx0RS-(N|2Coq(S989OhQl+!Ew0ffxx9fmxmH_Q!1KV#b)2t*lkh&`@Gd`d|w4!3cctFHU>`+XBvV_qn zLL^A=Ormfa&xS~p;MqW&#^WcJ^`&c3T7;LASl*W=_W`jrPOg;T>r0}Vk{}duK&zC6 z@^y&ugqsdAmRydaVN@qE7U<5>mTSw#{dWZ*#aH+X36#%Lp-Lt~bOE%rnYcDbj9S4F zuJpUQJmJ>{Q59bvxF2QrwWv_KgG}dHV*Tdb-~V0FV;I@V;_A3ou;j!URBH+Xxyq ziRv2IpnSBx-!+YLW&b(kegd?Z%)W|fS<&M4X>Fgyn~el(B{=_E@I?^Y_%seejQ1kD#!7>~`j3giEyf;%c9f$J%3z56Op7=lcg zHXB=f+a2dL~^W!6zDCR{kj!ICdl6<}Grq7RArbvv9U7VnZ zj9;RNS~5Fo?%b%k(>-MnuO%Cq^vwaC4r6N1u>57k#-n zFTjg|t1O93T!2!2AA4rs0#WZ2gwl%QI#a6@lt4ixI$NQbr;VwV6(!lIv{cQcra4mr zXIx{Vf^t;2QT%z-OlN9=GbLA8Qc=#72{N;tDRTwML<=`?+~|nW1H(fiMg@lsLne6K zxH03v?C8XCQOl#^6QYJLj+{RZ#79Lg9vmArZ{S!DHxL)TB6{xJ#Zd#tp`jza~}S>PgoEepZK3yU#o+EMjReIK0IRRz~Q4Nj0*!6^Fgs0WT4HeqydXt?&ef2;TJs`br2F*0#k!q;W_-?dqWs`#RX{?9%0 zZx^8hLx+bB1>++I4;>l~zAjtef}`_1+|h{%(W{~oSH?ws*8%SJ+cpDz7Y^^1Iq2kw z_{h1@NuK|FaQ^LQ{Di@SgU658UMt)J9+{gr-UHvd>Ki>S>WgTX^85YqzukPd;cy{J z;+G*k;VU2BcS}KcAO)(X2-eS%_VgidW1e|L0?k%3{A(#C7II&0aPiUA=j+==8pLIo~HE(Pv|R zl(vtrHU2keadZs2(S9vOg9OfVVwWt5LRZ=uT?6OH#KidM*~=3Dvz2-1`v5=m{a*%S zR1d8RK+h$8!BcC$nXlhq09c?5T(9r8jqHEd!(}+wBB95s|KED}(e1zc{r=mKfy!}k zMB?_vz8+*!0w_=vUt?Sc3-=d-gxmWz-uo#2HK#A~&v)?GFYK>*_;??k74~gXDE)07 z_{;tKetl8DzNm5BFB|Dwzq3&M+c_wT9@hyF`d!AiX#9WGo5&=C_;d5Ey#pxz?Hm*Z z4^Vr!-na0rY%j|AzP&f!wTB+F|7q_6ihnx?w~>k38~I(vx9G2^?EChBA<=g|@%V86 z-^OS^ZJUD0`c>H)C`bgjAp@ZVz4I8+k_L@-MxA3hmY`^Vg zT&B_?z+RLoM{z?W+#YTp_xXK$_jL&{3*~(a-`e|@{${_=XMpxE-}14g{$s{C{ryOA z`uiSnn$b7Mf7@X6&3ny18Q)gvYX*hxHh5kB4J?4~Lw(@~yxuH;Z~g$qv2gnPK=pkB z|IMNPW99L9@F(TpK=tkP@6&jv{u`+O*y;Fu-M;bR_5B*~75q0)|210*pdVM?1q$c^ zFOyctOsttv#=`SG4xF);`eMbgj+R+G4H6pI6*Z zjn+15?JKSA)LOjZaXkgPNZ7h)ZGWvDt+ms&c9GVu(%S7>i~m^$pMOnj|JK@Ut*zAB zms;DSwH)-3!snT3t((>cV#`F&ELt0kE!wV=wRQ%!=)48m^b&14Nt<4)O>fnvcWKin zwDzJl{|dIKpKPuDqAlm6k2c;X`q-j=EVXGTZ5l0G-+2tJ?b|=79lWP;dkU?!)>;Rx zbU!nHiXw&!~%y9eY>#om=v=-f#`_gi) zHPu?B*4k;UtJZpIZQth(R~C)!W-!q44na_WhbOi?=>_)X=a0_<$Nifk1a-G@O5e3@9$MLs%4$n(D_ zH$=w&$r(ymxefi&{rSs+TMPdF!Kt$#NSQKgLnONG*uTjqEIC7^L;o!&tTeNLvaX4N z>Hy`lCP`nq;_KIE5E@JnfSm&XY(lC)%0;4)?jl`6I*zmlX(Q6|0R)Ujnt>FCGz7^9 z$sWmU010)Fm`LyYlkgQ%b$<#LBBdhziFCC;1D-}YfV2f^RevUoL5f70(4PfEkoqCH z^k+jWBm*RFe-8W<$boMHxv(Co3@Iy+2OlBb3gpA{NJjz%a3|9GKp{*(ninX7Q;|jo zieV6vXP^YyA{htjKoJrds0+LLN#P5ms(yMfA4$_sAKvR{0Dnh1+0PK}>nDSok&^n! z;i7&WU>;Bx;!80|j*&hQU{Vg3W* z5dT5Y$A2(%@E-!r{DYyc|1ik(4}m>?!{IBx5wON@BrNh91=IXO;RC-h@S0y3JmWVO z9`qXzxB7*{HGUIdtlva9$8R#6=r;w9@S6$){idV;UpE6<`^|(hKlGZsUnKnEI~#WR z&V`M>QSgcHe3;|A07Bnrc*l1Uyy&|a9`{8UVc%G|(RV3a<{J;AeG}ny-(@h&cLf~m zn*@D)S3!H<)zHj$E!6Q{2bsPRSa)E6P1=o2!gYjN9aGqBkoZ?jvM|(BFAg>qD)2julyjr2L*J~*DYKN3pCw%Am4!-n! z51)GW!UE5aFvasTyzdF)of(W$rWSEcZzIvHKkQmis*Vg8KscnEN7nw|fk|!99*%=AJ-DyDz7wyC>0M?yKn` z?(1k@_aA5n_f539`%kpgeH+bo-$D1f?WWt@_R)222j~*FLv)7QQTlJU6ZB2DQ}j8v zU+E)m=jfeo7wI3|ey0=NuF~_}ZqU=*ZqsAj?$LwY?$h3G4{3Y1N3@w6P3yWP(@eKC zy2mw>ZgtI}YhCl{64xR+-L;hd%k>F;!?lV&=UPo4ajm0wxHi!1U7P6y*A{xdYa2by zwVe)ieM=8=?WVn5due-D^j?}Pq1JU}sF|*8b&m^A-RdG#*Sbj5B`#8RhKr&4FBc>A z4Hr}OITwZch>Mkar;Dxn2N!#FqKlJyzKg4Rnv17;jEj$Yu#3Oi$ECm8!DXP@++~Pb z>M~5tav7=abq-axIgeG>IZsfRI!{(-I!{+Wa*j~na-OZe;5<)#6ul$3%Xx`VCM~LKj$CSPR?7^7S21>`p$dQT<4$FADs@V-#8sp*E^k5 zmph$NXFHu&L#IpXJ5E>Bmz=JvPdMFH?{)e^z1iu3I?3sgda)C&p5>IH4tL5>hd5=c z`#I&SU7d>6)=uSWnNy`&;8d*!PS4eE9UIln=$+0g$2N7oV~0A~u}gj5u}6Ky@ss+r zBcVCq$kc3g2dJUv^oT6Y8?h>N*o4jG8~3!{&pCtx#=)QbKYUR=BUFY%`S&&nhg#Snq>}iGz%T( zYi2qu(u{M6)eLn=(D*y7&^V*_aV;IzYYZGVX?PA>G+*p@YC7%rYMSg1Xe#Z|JHF_B zUyc1~%^&vXHCOC^)10=ysySePQ?u3nu4aw>15KR$BTbaOS~JByRWsT?Q!~&$Pvd1@ zq_MLv)0o*;X>{#tG%WjiO|RVxO`Bb-=DA(Frp)f0Cd;l@^VsgQ=8heee94ZTe8P^O zyw^^WyxC4Kd8M5^d5N8Aa-^MQ@&r4ZM=VUk4kz}RnWU^d!CRwDqkW8vBC%?13k=$Z?C%M}8&*UQ8 zN6G27>g2y{(~@u6W+$JwEl56UTbjJvwjz0>ZFTYr+xp~1wl9(+Y}=BK zZ9gWv*%B#ATULsZEk8wMD@mbj^;5cSj8b0Nn5ER%Sfv!(s8TX)oKpU_aZkBrd9K`_Ql>ndlC4C35y~?uca;}Yep6ma`9*m%Wxw)X$`<9r zlr>5^B~F=|5~a*anWD^3300P)3{qC6_$X^q9F+|z3gycbedU`JuCgoTvvqGur!`1z zvSy}MS@Tl!ttF``*7~Urtc_BySu0Y{S}RkJSlg%Ww02G1VC|K<+&Un2p>RqcNslQvDOg&|FHuZqjrPQrf*HYJ7-ARqN`ZIOD)#KD@Rw=1rR+*{6R{5#^ zRwb#h=d`P1# zi1hagc6zHqm|mxlrk5$?>DdbNbXuWIzo&3WzpQXiKdtahKd9)RzFjdSeZ68tdZHpM zJz6m-eWqeYdbnav`fx>bdVfV+x`$$Ux(fZdPE*CkbX~=^bhcto`bYDF>Fwsn)0@nH zO|LS)lwM$dEj`uzZu&#>hv_%W>GbpF>FLMKbJO>l7pMPdUYWkiyf!`7yg5C}ye)mI z`P=j{<{#3Bm=hU(=9~-{b5Vx1xqgP++&DvIZjnKmt1^1boHN?YyfU7f1!R<)4a&$h z3(3%!jmfxgHX-Ax+4PLFW^*!*m_=voGKG1}~K z#vrp_GJMU>WjL8#&agDQl_4{`pCL4RoI#qUX1q7e&S*6)%BVA~$S60h$;dHn%Fvj$ zW!yLI%D8I!A>*tmnR&#No4MOmlDWy$AT!C-G&9E3I&+SxL*^7y_smdJ-^?MV12X+g zhh{pPj?T0;4bPODPRkUVMrJZh7i9LD#Ad!WS)SQovNp5AWOHV|$&Snvll_?wO^#;X zFgcZZ!Q?{bag(c=`%La+{$%nnbB&2QGu|X4bG}J_<_wdv%yA~qGDA!nG6PLsWqO!& zX4;wbW}2B0S$Za%EUt+->x;2LR+q6^)=Oh$R*kV^R*A7kR+h1U7HvE*>z;8)))nJ1 zS-%=j%sOm5Gi#S|RMsZr#aT(l30X15tFq=AZ^)Wrye(^t@!qUpUv`cBNOr0GbauA5&c1c`XagX_QUOsgljeDU?O!q|27%Jd!QTxg%SX^Sf+w&S}}s zoI|pob9Ty(=WLXn%}J77&WV-X%88Oa$eAWn=ZuwQ<_wb+<^;-~ z16AH}1J}I$2EKV)4TAF48-(O7GZ>q<*kDTDY=g+WDF)GbV+@w&1skl)>u0br&)r~q zo}Iz|JadC%c?Je&^8^N$^C*Mcc|H0M^WNwu=QZkQ=RMUg&MVfh%FEPm$fNaJ^ZwB9 z%DbljIq#f4EC0B@D1X1cLH<^K^ZfPtw)xBSUGo>~`{vKl56YjSKRiE7e{B9R{VDl@ z`m^&r^%v&b>nG$}=&#O~>2Jyx>F>;E>L1AesCP2IQ}2BK3%zUkHG22*%k&=S=jf&7 zC+p?sKh!JFzol1`e@X8}{wckV{6l)Z`MdO}f=zn-f>nBY1xxiz3Kr-o3nKKK3MS}z z7mU*DUocp2Sb@J@Sb>|~Kk05Le5<>? zutj%&VV&;r!Y8`t3JY|v7N+aoD}1c`xbU8Cdf`>wg2HpUPYRFg))ns8Z7JNY`?hd{ z?x(^eT~<-7uDEEPuB>Q=u0_!VUHhU@x*kP?b^8_h>joFO>4p~B=}szA=*}uK)Qv6@ z>BbkabXOOB(%D?}R%cgHi_W2<=Q^i~Ds(Ot73kb7%FuaG1a&k;f9PZvUDqiox}Z~C zbW*3e=%7w}(N3M-qD?wf@oF7GalDRxakP$Eaior_c(RULahQ&O@i3ji#r<_g6?^MU zD0b3`C|2q$C^peqTCAtDs+g~{shHB)Rop8%RNNssRs2G7sklaRtGHb9usC0mT%0D! zDSj*|E50YGDZVCoQG8y~S$tCRvG{<5S+Y|iD%m8Fm8_Onlq5*(OBPBzOJ+*~OQuMM zm5h~yl?<0mDG8FyDe;voE^(DCE3uWVFEN*FEisVnFA+(Om#`$~N!C}|bb zB@N=tk}7d=NwN58Nw&DLBw75XkR z_^5n|FugoVSXe$oSXDkz*jOGad|f_N*i$}0NImfp3ZJ+N4WFol7EcsHhbMBO*ApG# zfG1qx@F%2j{F7e6j3=Ff`A=E|=x_N6RzIl{{P?6;u;)pR;MkKC!MP`o1lOM26Wo7t zU7&t)QIP%Qw4n6K5kbw9eS()ywh7)o*(mt@WR-wZksy#(EE1Sj%oW&H%n-O$Ob`TA zgbIQyh6=`13=mAM@DvFz@J;WiXT&%z)z}N%->WQ#otvqlYh8!BLCOQG5jl)A^dxl1Nn5NKR>I| zgI`kV$ginX@?Tb(@w+Mw_+Ki;d~OwouUAFz&8m8Nc2%7`kE&O^z^VpbNYyjmxT-SV zjH-Oz{HhFIe3hEFrs^T@r>Z-=eN|U^$Ez;zE>xZ3-KaXsdswxfmr}KZmtVD+S5dW= z*HE>b_qr;U*ITuK$9Nja6F;5ClRpjTSw9`kbACFM=l65~Z^%<$Ug%SI-jt^fyg5&; zc`;8-c}Y(Vc$=O|c)Oo+c}Jd-yt7X~aIZe?;@*GS#??G+;^sW9;g&zG;MP4Y;`&E)jSK~<~|$5Eq@lkeg4dg+xEbIP!)oq-p>Sj)CbuDLAbtUJ=>SE5` z>Rit8>U7TeYMOJS`XT2bqC=)uU*i;1U*c3%|H^5qKF(>cKFIl4y@$iD*~ZbW*~l@i zS;JA)Ea!OC#Buu9M01AM%;ALB%;3zdnZ${%3F9QzjNq)V8N%6K)1Py&#+P%t#+`Gy z#({IMM#-UT%sJ>0g;Q1|<r^4d1Gb!{`-rM8akUt7fv zt}SJU)#kIO)n>Bi)h4r-);?mdslCtMQhSTNzxE3IWbFm^rP|Z%+qK8ok7^IHGi&#- zOKP{VYic*KTWZ&`-_@>Q6Lm}3g1SX)!@4N8WnBc@sctIUuP&TDq%M>_rY?j%wQdkQ zsxFWnSLefCUFXK$Qs=t?;H z>tGSjU$KPG8(FgFwJfXWl`QAyB`p8v`K;jQndt9ar?93yf6SWy{7+W=^E<4y&#$qz zKEK2|@cb<6)bo?9-=800-F?2FML*xg%6`6uRrY)%tM2(4R@?Ixte)pfS&aI{EJ^)5 zmT`R~%cg!B%e{UgE3iI{6;eNv6<&|1k@Z2Wh4ld}ME7BBsCQ-UthZ+!saLYj)+<=o z>Wx?r>h)PE^%7QoJ&#pY&tx^#16F5!FY|MK7n9rYhKVraOhrQj)3Kq3>C;fj9Mn+4 z3~k6~PHD(uMm3}|;~Hq@nudqWEe-dW`x|aDe`&bF{H@_4^KQc#CTuvt%x*Z$ENj@$ zeBQ8&+19X?+1s#*$!uK5)M-p&nlvUbRgE!BkH%=`fX2DZ5seYdiH%d4k&P3WOB%zN zNsS|!n;VBR_cRV<9&hZ&ywK>wyw&K={JYVKnbD|X7B^ZkYZ}d%uNsY*-HrN8s!75W zHSw87O)RFeiD0@lePjeSbu&VmIvC+iZH$Pf7mP(s^^6rw)r^fz6^z|YrHrFZ1&s4e z*^HY_X^g*`)Qt3|M~tGTKN;0ccNi^AHyH1lE;GpH3k*^78HT+1BtzMJgyGiwGoxSg z9!5y>c1C#fkBo@s4U9$2YZxn76yp3cZM5t4rWj<1~SAi`Z0`O_%du>cre^wxG?&^uxE^TVZ)g4!jcjB!j!S( zg`BbSg&t$`3khTI3qIq-3pV4@3yN{)#b@gAi(V@0#XG9(MLYHUMJv_z;sw?FqMl;C ztf6#YR#9dz%P6~-MU>aeJZj*}OltJYRBFmgH5K*p5f%6H0k!7kU25ygo791qSES^(yn6F$Y$twrSRVi zaj31YnACw+1ajjVe0l5Bp}NWOjboCK}aq@cBul(m+V z)~&^)YimB)uQi(tY0V(RTT{qctu(o~^%0rW`heWr`UknU^)`8;^*VW}^$K~X^%4nN z&y(4$XUOu_lVpACG4f68A@XDE&m^~P52@d_leB2tN; zkkM@k)OVWZEc}sZ`(+c z^?Dd7eLaLUe?5?Nc-^1$dF@XQe(gh!dF@F~d+kcjf9*sjzP2ZScx_AWd~HP@d95JN zy*4Fpyfz~LdTmH%yq1zBuO(#dYa!YCnn(7$W|Pb}3{v+EL7Kh!MA*OSCA{Bs6NBEo zB|_h{6Vu+b5%b@)5D9OZiS=(9h#hb0h$C;RiF0qNh#PO75P!WXCD0$=Budc#RI7cH zL$tohBzoSY5zO{vLbshJ%-SCj_U#V|@Amt|;P!jOnD*PmwDuds{PwFvV*BsJ5A7F; zo$cp{BkjKu=h{yZH``ATf43hcGTILjCG7`@y7qlUTl;RJw|xh}?$}01JANX}J2nvx z9X}Ah9qWi89jl43jwE7w$8sXNBY{}f5l3w3h#_`&EFz9|EFdm)%p-1f%po3kL=ssY zGl{Z}X+(X;6yiW2>;Gu#L&)QVqE7SBBC>hSkxIv ztmq6NHh20Gdpo^}6P=#KZ=G($-A)&R?sOz_JMD>zP8HGEsU$i(t%xt33WEREjF7!G zA*|oZ3D>uVMBrO}V)$DrG2yL*nEh5n#Jm*{tKV{oEpOSx&u^K;>9-Vd z?|KH-bya~KT@~PPS2;M>RSIr&6@$OJ3PDC!J}BwR1$AB7psgzt^me5K_PbOdeU}Ur z@6^EY9Rz;w9)aL@e}l2_9)g+g{sar({Q*|Iy9+kGyAAffy9rLbyACeBy9VyQy8`HU zzk}R&mq5k43!v%UdC>XpEco*73=njm0`gb1zBf1ZRN!Ke*nz)>wwPt zwZQECYGD6<74UhV1O~rf0m9xd1JmCpg6Q}0VA=bnVB`B(fOvu6`1{4+;`>G5&iiNp z-!A|;@8^Rj@1sED`?;Xw{cP~%eI(%b%mT8WnZUYd25{?{4g!0of)PDaz{H-(U{23O z5Zf~Wtmz2{TYJWXgFR!xnVv9kt!E5)&=U&MdPaewo{^xYX9RfFGaU5vgaBsmFreET z49t3m0Egbez^8W*7}7fsg!Kl28NCBQbZ;P7-rEms>jz z`#}Y^eXs?GKG=X?KPbWV57yu>r1TF~pyY!ksQq98+CC^iFB1EsIgoxd1B#EPz!Ays zqX`K9Xbi@EGy)Mwi$2Oh(nlHCjI{5gAvpQb0Q`=0@1s7@eAENzr$4CrC+H2RYWOhuaaNeB{<)_)R!ok&MM@xghdTc3E~5mMGCE+|8) zM|$ n>fKeK@Wk`*zNjYxZtjw4+{x{E|3U(?123d5a`us{pB0Cu=3TY|QI`lrncBI2dXOV6o{e_f)REpkqt3!H?^Z|)O zkU)>1fCZ8>l0VWgf&s=O%|cp?w31+gpOE$=og!G^GSYpdWP%L}ke(vFBsicOi6Xf` zf@FeZhrDyVkOq-_5Q;R76reYI1RxQ;nzaFG7kc&Q7}5n&3~nPq^h#DX(i8MbRs&K8 zdPV0mDFu8=3JfVdV2$KT>4QMz?lb~vB4r5XP%;pUw1$#{t&|Zsh;)WB2G=MP@Q^YE zX-LJC8K|MmK`W&IJxDBu1<++!0&|8Ha6sNtzDPqDO2pf?0W%r4U?D>VRxs?qCWbxO z%WwcEkbYx0g1ZbSpk_FOT!ss%WVnJRh8uXxKv#k3f!v-vff3US*f70;2h#@(VETel zOg}K0=?|iq0bnV!A6Ul>1lySdz+q+(ILjOeZZHRdznFtT26G4~VFrUb<}lF43;`dQ z!vUK$0_d?u0tIUnaAJi5Kh_v9lobZXvBrW3)_Aap6%LYE6ToKHM6i!F8JuKI0l%}R zf_tp#K*O2=@>nxL6>An~W<`Q7)@(qq=K>Ks3K+5H16%e2;K7atLF`3f6nin4!j1t^ z>{t-bUJBN+5W(3E7IF51B+h=Yne#K)$2ka2at?#vI7h%e&M~0o zoB(;8UqB`26lmt00dF~Ir*h8&A@>51b1wlK?(e{zdj$;OUIQb!*TH1&O)!^x8^m$% zg0;hW4wBBk=F!n^IibRYXRB3R#1+- zDjRt1pql1(Q4G9fjPUQ1Vh$_Ar(acv6U3@Eo5GV1U<8pW7)2Bb#t_wlu|$g? zoOmyoNHBy`2#IhSVIrJK*a;&EFX0?wpl}`$DqKKJ6)qy?31f(OVH~kum_Y0hE+-BP zlZbP|)x-_qI^r+k4@A0f6Hy}kiKrEBBU*(!h#ui?f+gBV=!y;yW}-ucgXk#XBRWA0 z7M&u-h<+uei_Q@XL>Gxf5qh2yT_tvkZV*RBw~6zjd&EuAed2G?Ln2f3h$t1&M4c#^ zXcMI&Kd?-KEzTjN;(WqfTtqmCO9@}`6XZErMTCi~iRt1xVu84USSD^JHi%n@UE((4 zsJNXtFMdnh5_c1i#JxnO_!ChoCdfK5gKQJC$q!;4$(9I7sYF7WOQfU&@)Pxu7?DFH zrev5zK~9%gkqacYWTFH;pGus_of22_sKk>zFYzI7O8m*cCH=_^$w0D1GK8#^3?o}5 zBgtM#D9O?pOX})OAkB0pllD5(NpGD9a*)n!GE`?CIaMc`oUgNlOwfrV*XtyZJ9Ji% zhjmtwXLZ(**L60K4|RSd({#3yMLIjlYMnh~i_Xtvx6UDwp?i#!=$<4^bkC3~-SecU z?jW$Qc`XKe8*m?n!RBr%ft~Z!+ z&>Kei=#8WX>y4qt=#8hQ=}n^M>rJB)^dhMBdUL29dh@A6dW)!E^Y{!obz47=daPeWW$BkuW%^ZAoqi3~re9C>>c5~^ z2CbB?K|5t?@Q$)G=%u_2K2rk?D8?uQHe<2@pE1`!!iY1_W2`ZdGqxC*GJZC&WSlav zVO%z_XWTPzVWj5CJY8CMMVFzy@v%t$so!pJi` z$*43u!)P+R!00f%%=m10gTa&CVd%^LWLU@^F`Q&-hOaD*F+`Tl7$YlSOp}!|=F2J= z@v>^hI$1qqo9qSSpsbB?M%KZ&BI{<{mwjYtWCSx$#$r~=_{>I`gxMj}XMU0yF}ZRx zrk>o2sgSFfj&diakKCO(Snk6NmG@&#l@DY_$%itR%11KS$itXhVWyqY38tsf8D@~t zMdnDOE6hnoH<`1I?lEJG9x_)N(ag<8sm#4bS{IKF%DzhH=fAS7*Av68b`7!jOVc$j2E-s7%ydgG+x1C zo2+5!nrvj5nQUR%ne1YDn(Su{Fgd~+X>yV^(c~;E(&Q3rvB@=7lF1#`CX+u|yGZ-;`o2Ou1|a zQxV(SRF6H#)QCOWRKcEXs$`@8E6k2Dbz`qI^L8pz&jI*5JTG=zP@G?abQG@SjH z=~Q-_X#~5-G>ZMqbP@Z7=~DJv(-rJ5rfbnB8ZuG<(F}Y?jR4W0uK2W|q%BZ&u2_VOGU{XjaEgHEU)Un66Sb2wMbqd9+=$8pr=%Q-pbYdGcR8#&L-5n9%K52wfc zAcvti&Jinq<;WG6IM#}592do1j=$m|Cs;vq!W8M8X^LDNwtR@8ESQZ#e+ zDcU&46>m8g6dyP@6$JM$1&5oa5OE6>`rImoF}F!!!R=6}xStfxT(*T5SJxtdYicow ztFj2;x?7Cl23kzuhFDDJj<=Y@onaBpU0@N%O|V$bU2CzHyVYV7_h*ak++QsAaW7dM z=H9mWh5N|j95>zKGPlU$7WbLOeQvYGV{WHKD)+NRHkV^r#FbiBaLp`hxGKvgu7_nC zH_)<+8)Er^JKmDy&9LP17FbGn@swU(y5t(Mk2^p*$jq@_FWqNOkImgNB6UzS68 zX_ljTg_hyGD$8lSCd)`(yX6AjN6T0q%W64K$7(Il*lIJ+#%c%8)oMR4!0IS3*ywiyHskZHm3#whN4~<^gYRJN&-bz($RA)G!XIHhh97P{kw4RV zCO_Ibil1P;n7`IKfxp#y6@S0=2L1`_ZTySYd-*r55Az>d|H4nPKF`m$zRIt#zQeD# ze#n1qt>*VwXYwg!0bi&r=gX8ed`o2$-%;7d_f~fC2P!}DM=BYD2}-^oLMatQD~$w+ zN(;d{rJZ1_(p9iu=_@#)93Z%$94fe}3>7?7P7tIhX9)6?a|KV7iv-V=34&JTD#3f@ zMgeKFO(3w@Cor%%B2d_z7TDWd6nNTP7xcHeCkU~5Bp7FtBA9NIBbaAXELdt&C0K3q zT=1h!i(rpUr{Jhfui&f=DZFaK75-tPBcyHQ!Ymtwu*60sthR9#zOeBTcG?UOezF-V zWZQ-cb!;aJjcjKKt!<-(&bCX0zP8JRgKXCbN7-%`PPE-AoMrp7aG~vSVWRC>;X2#P z!mYNqg!^nC2#?#Uh39QEh1YEhg@4*U5o&B}g*mn_gr&Ca!W!Ei;Y(XW^wyRm`fMu^ zaa1yqj!GdiR;ffvm8-}_tZ1!jh3F^M zdeL6h7SS=)9??0~VbN99DbXLQiy~TeU6iT%LsYDKEPAF&6E&&wMD40F(Fawvh+)?x z64|{L$?UpC7It4m4t8v@mz_l1-%chDu~Uf0+Ns3T>|DiBcD~{myC89rU5I#t-B|Gs zyD8!Wc9G&=?4rdN?Ussf+N~5nwA(07w%abwwc9T)vpXiPwL2?*X?I!t*6z0Wlifox z+df$=vCkG8*%yng?5o6%_6=fh`&RJ)`!4Zt`_JNW_AJSCdyyo{-ary#Z!Sr)x0P(L zca`k0_mv#550ad;A1=9QKUQ+Xev0Hz``HqW{X$8$eS)Oaezm09ev_oxey60v{($6z z{YeSK;k-oXa7|+9a8IIecr3AVNRxOtuun86akecOYciB+k2m@D2j-5 zlqw*-EiBvH+@CdQf-M@XF~(jJOVrp)EWr-an^Xa5BA_(Uciyw-^C#??J7@0qc@_x? z4U2*Z?Tf+)9~Q+CMi-?KrWfTA3@oJt6H7h8+Hxzw*>Wer+j2jFWOSUx4hS-v5pSvC-IEjtM%mIDN>lf2k&nAgT#9>448^@7#^UOT$+$LR7Osz2g!@EP;iicja0aC9I8)LdoDJy^&Xsfm z=S%t%M9R6^D!sY9+t4T1l?8iX^vLC6N29(#fB!^2yUyGO~fSo@{Ep zg=}NJgY0TuPWH1tN~T$#A@i*-k(XNEB!^o6OOCaEPEN6|Cg)f;lO@*OWR3M8d6V^L za+&ok`B!Tr%28``${A}r$`xxo<+imS<*_xD^2(Y=skdH2X}1oce6Wt9j9DjAzFMbK z3~dT1<~A~ly^WsYZnK3FU{gk6+Wblp+5ARXVRM=iVRMlZZ}Sf&-R1$Mz@~yCx2dE+ zn?_2hO$TLVzObF5*4oaYwb?G9_1Rj|Mr|Ev zUv1rKhIalm3p*Ok!H!4suvGCuyek-)Xk?#&o>B1wFvtj?S=mql@f)=_~BX^hkR)J<%SaXWB2P7uko=Rray; zjrPg(pY1d0zuFhlf47&>&)MtfSM4{`@7e!Eudx4x{?`5wy~X}Gy~q9>{iFRA`jq`G zx`D$(x|zc>x}8HM-QA&qPH4lax> z4ql9%4n)R52L|JWgMjguLm=aZLkQzvhe*athj>PvLn@=)A&1fLP{bH_P%^$bpp5yB zTNzf4WegX`eGFg6!wj0^afZP0JR`{Q3M1U{79+v&AtS@Ff+2RSWT+hL854$hnC~3%%sxjy=9nXeIqS$~8ap9OOQ#^F zvr{P3$0?dgbxLFkoYpggoN}4rPQ}c4CnYn(2{Oe_TbU}SGUg_yz05MFL(FogKbU_w zonu~by3D-pbc6ZO=|1y?(^F=x(<^4XQw_7CsvfR2P@gxpOx)QWtBK{SUP8fwbeO@wc9zAb;voIb;>z`b;&u6 zb=x_c^~71ss&tmKnw)j4_s*MGADy?erk!`Q=DF-=S-2c!Ik=o;dAVF*kzM{~@my}P zmbpA+g}GF);$2>|(p_p4HpykBNrU| zm5T$r!3EFmbn#&ixsceCE==}ZS3cX!bqU+vHJI(;8pbBM#0XD^Ll+AOSWG{33&JK4ogT6v&GGuv&)UhIpjv?oOI)IF1Z2DZMPuKQ@2%|Dz_+3i(4G0*KHl=lUpX|t6M(D z7%$=A@Jfyg9_9GqH**;H?HmNZi?b46&WXVv;jF_S=j7tga%A{R9EiWp*^a-%*@yp^ z^EhZmtPW%vO2tUS|#7}Vy+`n_o-3_@8?j~F>cN~}E zZqMbryK;lvy|@wX0o+7)DmTlW&6T(dxjOei?vL)l+&%7L+#~KW+%xV8+`rvZx%b?& zxX<15xwY;RZo9jZJK(P8esSN#o#U~MYwEF+Yv-|#>)~;TOY%6z<$0XqF7vp+4fnXh zP4KwE&Gfj(E%tcC)p|VR{^;?ByT_xJd&Hxed&Z-k`?p6A_nyZf_qoR?x7K5V+wL*T z9q=&Veeqbpo8xKDGxN0O*?T(jJU!ibWKVA%-;=-#@}%-2JlVWNPXRC6a|y4+a|KWD z8Okg5jN3y?|A+L?-c$^?+kvu zcP_unTg)H!mhz{)ReVDqJ>Sx2Bj4Gll<((L#%K8K;RBy?eu&Ru{u-ZS{4}3a{6e4e ze3j27{$`(R{GC3x_=kM%^H2Fa=3nu7#=qZplZ-ij3U#!5~FG1komm=`?OBc}mas)!Z zLP4;fL=fYr5Ty8N1^IqZp!C};*yvX(*x^?uIOw-WaMJHr!DYWgg1df41<(9W2x|P! z3flet6b$-Z5lr}97Z~{87FhV-7dZJp7WnvA2|V zsQr5doBam`yZlE4hy6bb&iGFWuKLdk?)%RbzVJ5^*849McKKTfhyAUD)BbisqX1_i zE&!|a0=$I&0scZ(07xI>J6-9^rscPBXA7Ot>t(OSmR{Mz|@gCEOKu5FQGL z2v3Algl9rS;w#}IVwKRDSS$1+HVT=u@RL|f4~(NXjR$wg#Jau?Z?yhUClKM|Eg z6bVUGQ80-qiXm}CsU(4@fCNM;QlMxvX}M?@X{G2eX|?DKDN=Nm6eD^-iW9vgC5jqI zDWYytx@d%yCHhLr6D=SYifqUdkvmx?B9T=h9$702B12Imd7~(qyj7G--X@Zh%S0Q< zyF_K=UqlDU<)TyMgQ6?s-$eJw$3)M`Cq#ARGonuNdC@TWqG+0YMPx*|CbFX36uD9E zhzOMXA`azW(NfA&Q8?w9D3S6~lufA=$tcyL|555hKT{e-`zfuW6O?w*B}$j*4y8x* zjPgNLOBoV%P)0;Ulrhm1<%`IWIwitUzlvO`-$emb1B6XALISA^kT9w#l1Q~cvZ**k zO0_{C)gJkY>V)j4x*{j2?#Lyo7jlQ{i&RhpkXkAU>7Y`PAu0ozqOuV~8V|wIgorB* zAOW;MgiQ-VmePWea9RkGNL!6$(;^TVEgJbBZ4L4>EgsoVOF~Z2)*+W^X~a_QR{U}mT{{!i!pF~FJr;)GpbI5$g1;mDN5pic+ zMo5gS2%m8sS<0W#9@dkOws6t*d zYLF&I9n!;SK*ku&$ah97V!~`k?3ta27qc6oGJ6pb^8>PyIe^46hmiHm5k$-!MYPOu z0SlG|aAH{kKb93> zvTVR&mK|8lascrxXOP8m1tlyzKv^E(Czcl|XZe5=EI)9G6#(wAh~OEE3~E_a(8;2M zVHOiiv)I6x%>`C$KEShufXGGwkG&WKu>(OQdns7Q4gz`X6+p>e2{y4;fnDs?;4nKJ zoMA_TYwRfSkR1bFv)6zob{yzsCx9__BKXcu2Bw@8V9!Yd-kkM-#>oH(Ckupda==j)zH@&ACcLA-p7%TO;{5?=yyHN`I{`v?r@$KCX^_r41B!U( zfR1+_l=3cseY`)xG2TV+7w;0d#k&mt<6QyOysMy{cMS~ku7fGwKfsWG1K{{Kfh+$u zAn@-14*xD##=i$5`1e6F{{hJ5KLiT?Be0SG80_Rf0f+cc!5RL4;3~fYJmfzEulUbF z6aNM1;lBi9{8!)y!E0bDcmo^+mB3q21?Yme0DHoKRe~C9lyWV|z!VGWfL>4!wh0=* zuYyMKhoA{u6f}c7f)-GLsTH(>4#7JxENBDMf_7jmYzJ1t4uBVS0-~@B@GwEbZV)AW z4^o6ZARnU=_JYmAKCl~eMEC)m6ZV7am`B0^P$?V)Etn6&A@CV9S2PUFMIV6^##b}~ zn3%<)Phd4BK{N`oFjCPNfS8{}<6uALr06rag1IO90$yP1MH8SKGlH2FO@al;B(O!M zfG3865hBwd7!!+0LuP;&qrv=$d515zZmQN7h~Q3;{X4d zVH_|%7&-=ER$<~WnHUKM#cW^v9h75^V=iItV4h*>FrACPfsdFO%={(afHlT_$t)ma z_?Q)#=p|o4Dy9IV#%x_O1NLB!V$Ls_1~)K|F;z>ZKr5ynGqGe67z9p&MS&B*8RL&( z1%3g6n6SXlAQ6)jI1Xf(4S{2z40AAW6r95R9ry`6z`P6`0gagVfgiyr=3C$}Fj+bT z>@Z$S2LTl$S~>timiB`+nDnI|K+)1Zpu?0d?FIXm_JCuUzm~oSx0iN<|CV-v8ch4r zPB65z157P#2S&@<0d83va9j2c5SFz9?y?rJ3=_Gm8LV5@1oDuxVL6*tM(< z99~un&SI`Ds{#Kms|K%^y#>w7szC3uN-)0c4frAGH82Z$1ssE30-vB4fD!Z@fS_j} zG^hf^1^ovygPsCO&=Y_LJqFu@9)a?phv0b718^zmKDZNf4?GLH3u=SzfX<-XU^wU| zm$ff<>$bW z;v&D_JYh6dqByG-2h#&6a2Jd2Pj|hGdQv0Cva)SHgI=EDR{PGE2vws1$3_1 z1U|0V2xeCN4;TkSU>&Rn_+Tv{1#18=SOt~`D?wDS9HazGL4I%vPz4u*&B0=@JGc-W z3C;&+gLA?4;2iL8a29wIoB^7H*Mq*`G%y~V0_Lnt24*W0fy2rK;IlFg&{wVjU}X$g zwK59Ct&9X2E5kuCwxvM7auwLNawYh6La2ZfLI%r1h#(>)03?O@f!q)uAP?~Z8$&$6ju1RJ7~%>} zhd6`3Lma?^5IgWP#0E5kSb_H;mf%x}1(*#n0}EFz1h%W@1J6}PfU;^H5UiRDf>-?j zVph!}sjFs?!c|jQ$YkgRWZvp?$fDJ!5$Dw>5&zYHAgt9# zktM5-AYrQyA_=SaBU!8WAtkH#AaM0A^v0~jT{JzKu(6OMlOeiAa}!pk>_DSNL^SU(isMj;V>aG6UIY~!`X;cI0JDDry_)K z62c7+K$eC3A`#(UNK&{vk`wNV$itnG4dM1kS-1^yARLFB47Wh8gqtGw!WSUV!;O%- za08?>{JUs4{Htgtd`e^-@kL}6F(z`07!eU7hD4l*529reJ)($+E>TiMyC^53RV0gO z6#Xv(JD)~Wiw;CoicUtn6kU#ZCc29y#LpuB71c)E7j;D35e-G$6ir856B$Kb5#b^) zid-Ylivl9gh}e-QM1hgVL}8J?i4r0Yin1fiMbgM$L@;uf=%>gsQF-Jx(ecQwqKlCm zMYkiN=)XvFDgaEj7k(Oj*1h7M#YHY zq9R2ZQL9D8Q7c8dsO6&4s6f%)C?NVhN+7xr#Sz_zVu~I|QAL$eL{UqWpQta&TQnZ! zF8U!Fdyj~A6xm1HioBw6B5Jg`NEmG*3XV1w#Y7v3Qlq~M3!-O)s_04K=IC+ZuILfr z;pjo(ndm;@)#z^FgXnhQ%ji~NLv*9CJGxdl5?v*niGC$Cj(H}uig_Y*i+Ly{#M~8f zVr~kT##|GI$6OXB#{4PFjyWro#+($wm}A19VvY!ZjX5CvBW9oQubAD!TQOzAr!m`v zZ)3Iy-^FYY_Q&XjUt-k4Ik7UKS!}V;A+|v19h)Ph#byXav8lq9v5CT%*tNpc*l1xv zY`9PryGpn@cDZm@Y@qN^EFwG|%NPC~%NE{`r3qiel7#iK{=&{!FX3=3UN{}=EHqkU zC&aC>61uFh5c;oKC}gcM5-wRYR~WixRuH#lN|3SUv!Hm*h(NbyQ1IiLUcoPGx&%kp zyc3*X($O(|__couh-=RZ zIBQP`maaW22w!_hkhu0&LDt$mf|9jm0(5PuVB6Zwf_-bD;MiKN;KEvk;Ko{s;PKi* z!JD-?g66g9g5I?$g3+}Jf^TbM1qox_#VD>d?z0t-^wS(H}E;})%>OLulZr|&-e-PkNKJL_xY0eTYO#oHGXOQCH^n* z=lMtDPw~&iALCz-Kg@p^U(SCOzlYxtU&il_FXexX-^ibd*Yk}MRD4{5l<$%t=KCk) z@|g)4{KW|={8b6@{Iv-&{PhXpd~reuU!4%d-<$yWyAt^PLkTSY=>#hON&yKDGwxxd8?9gcx#fyn>`So+>Gdw<#%< zwxrI{0wQp<@=dCf^p zso>N1N)+ z*_!Ic*_~?7Ih2ayoJuw2TuwFQ+)4e;{x5ZsU6ne@Zb= zmZo5zNh@OiotDeKm$sf=k(R`+PK#x~OABN7r3JIc(w4BlrSaMG*E88x>q%_a^*(IB z^>{X8y#rgc9>)$|Z^DjVZ^%ww|BaQieu7o9euSl8-_I&t-^JRqzJ+yUeJ$(s`q!*0 z>nm7y)<0zZxBeFE?fSo2E$c6^de@(1eOiB%^>zJzmQng{mSy^OmQ(sBmQT74+j1>u z3DU)^p!953M0y%4Aw7YWnI6q5N)Kge(t}u=(-GE=bPnr4I+b-i-JkVWx(DkJ zW>ZEqvpXY{`7tAiIhBDh4KmqGvrG!pKGTosk%?y#GaZ=hOdNAbrU`RZrU5fH^D84I z^D`qibBH0!>|vmpZH&^)dd8m2O2*;L3dX6-hm6aaw-~oGuP~luo@cztJkDs$Jk03I z+{YNoEMrV&Ze`5PLK&u6N``G#5d)uzLHZB{$IEvte4A*+%; zmi3H2oAr=xoPCRKnSF)sn0=1!m3^E}&OSuvX8%GD%>IcUn!TC6CR;~O&6d&gvJ2_5 z>`XeEolGyyj-~I;4x=B+UQR!mjnFSMz1-(Dpm_DBU zo%Stzk~TkQgl3u3M{~+)r+Mcz&?q^TG;U4>EimT+Ei~sQZB5Q)T58T&T5irUnl$GC zO`o%ywl!xPZCB0)+QA$(?L>}*_GeBm?Vp@9+QXc9+Vh-9T20PM+PfTV4NVS@_9=%( zo5}H~&C7MCnddst>~k$?*hLr`A$Jaql{-a6a!07axqZ~g+;(bWZUZ$lw~{K(t)QxM zA5b^s-k|=Jdy%>~_cZml+@sXfx#iT$xjU)1bAO~h&PA!Oa~0J3TrssHH;dYzn@k zs=N-$hP+0~PkEJ;y?GUsBY6)fr}O@yT*|vhxtVvG@+j{&%FDc8DRp^el(xJrl)gMY zWi(GlnaL}l%*#)wnB^x@?DC^1`1}xxfBq5*BcDeR=2Iy_`F@nJd^{yC-;R=&Z%)a} zH=;=MXUY2f&*ZK7gXEq0-Q@lG&E#YG)#UT}&&gNw|0Uneze#?Ye~J7i{|vby|0uaL zznnafzk@uUzlA)TuO}N7$jBB2`DFWobh3Lv0+~<{NoE$TB#R0blb088$l(PPa$JEA zIjz8joL68&mKKJsX}X}4WKal6riBWUO`(|NT9`@lEleU&3ZqHf!VuDu!X>1T zLM|z~kU~l-^d)5$x{}0&HY7!%DG3%DkV*@uiMtCw5f2vj5sw$P5ziOa5w8}$BHk^0 zOnh2+oA{>i3bDTMEU~@tcjAY_a^h&=4&rp-7NUU|n*=465^cnJL>F-y(MKFdq=>_b z9Px7EVzG$0Qp_YqiV4I7u{$wcY){M=TM%VpBcfhBOV}bFC+rXp5X!}!grnjH!Wr=! z!X@!j!cFmA!oT9Hgy-V(glh3ILbG^3pB#A|ZiS#2_pw@+X88;R#Vic7((tGeUaNJVHUyOn|ItG(ca}7qF$MEugHZ zF5uUqmjS;OJqkEobTi;$(WQWYicSYSC^`~QQM5OpvgoIP#-a@Y9Yv~u{vvU}Xi;Xs zbWu{k+~TMJlj4;DR>dH|shAz$RZI*Z7JCLTiyZ@m#ft)hij4zS7ti{~7LWTU7x(*T z6?gcHi|hRr#jpL*;>Z3!7T@;YS$x^Qy!f>L(c<6yPZ#g?zgYZ}|Bd1e*uX%Qe?_s_ zzp^;fzo9tMzr8rpzppshf20`kpDJeg&yf)P7f9UwEhYB;4ia;JcgZ||f60s=P4dZ) zC+YQDB6;VxQc~j=DS7S}FL~&fCi%xNSMsNyL~_DUEjj47L9)wln`EosZi(LSfJEwd zOp@z&R+8#>S+d6OrX&N_P9kmX!J?m!Q6xB{JW_ zl008oNvf}|WR36Ul2G5DN&d~BpUeO#nle7vMuAEH#^ z!;ohA2&73qfzl|S5NWVaq!jUqmoj})r2#%UQoK)*)YeBSHT6NIbA7f-C%wz0L*DzO zUEYVKjo!zlZ@kY-pLk!9-uAvFz3lx^ddj;(df2;Cy2ra-TI$^nY ziuYG(tha$|mA8p(i8oHh_I8jFz40;+Z$Fv6H$`UV&6XK>BeE&4AlXN+P+7NEw5-W1 zQC8`-UiQQ*S9aU0Sa#Vx%VNB4 z$U?mC%YfHY8O!UHjNnxx!+SN$Y`r>VCSLurIbNS+6P}Z@LC^29PER9wy{DP{m8Z4* zk*AaVhNp-8FHe8@aZjrJfG0=3!xNEj_6(A1JVWJ0p3(A5&jfjbXPP|1Gg}_yDV7U7 z<#MX0PVVEmN$%viU2f^QTW;jJU;fqOsQi=1NqMiw1$m3d-}1K}x8(m}%QWwJRLHM* zyq2H#sFfe_Xp!&n=#rOu^vm@gBk~fD33-mkH+iy$p(5JDL=o(PQ;0kq6bui%!q3A; z;p#zBSa~oN^F8>AZ|+MJWA4F<**y7>~hF+kAbafk3TDeUr=evDZ&bk_^MqN!*y{tk=%GFi%)YVIM z+ciLS$(5=)>B?3ebQP+0x(2E?y9TS&u3;*%Ym6%0H9-~UnyOmunxzVK%~!EqB`Sie zQiXTbt8831sTR6!Q+;>YsTz0Lr~2S>NcGO;n5x?4lZm3SV+*2KL zd8FFq@=UeG<&8@1QmYcXG^^5G+EsBbJ*w3%gQ`H6Q5D-|LPc)HW^))C*nA z)!&`1)nm?%>ON;Tb*r&T6&4GpcrV-mJzsZ&MpP?^J(v+N&OMI;ei{bX48s zbW;7=>74qJ(07dnq7`Sv)M67qjn6@h#kW<>m6e>YaQb?s~l4_iybpGOvhY}zoS^=;waVN z990@4N4;joVWZ}wL#d|Qp-j`@ut)RCpM1MpEW)9 z)0$@c@0vIE^R$ob7ie$Tn`&soweKS-LGlI&M#-R(oQHue$Ph4!)9Z*~dVQM(jvuU)#f*)B)>#;#EN*iNFoVW-eu zu+wUf*+K0-yUp5dcBNX>u1s5Ew?~_0_p3J1?vOUz?x=RD-3cwn?yQz*_oo(bcSUP$ zcU`-{?zVQ;_P+L$?PKkG+X`)y?JMnT+bZq9wsqR;woTgew(qn@ZM(F;*!F6Fv>nvy zY)7=kwx6{bwo}?T+gWX>?OfdwTO%FIcA?JS)u>F(RGb${FNb*F6*-65Mm-7cHuy3IDLbSj&0U4c!sF4bnOF2*KNx6&q6 zC$h=V(QI;b-Zlj~2b*G@nTL~}iwo43;+E@mxRv^1+-iLWE>a(di_wST;`EDgiFzh3Mem18 z*E{2~^owwL`gyoQ{e-1NKVT`-w^^$6)s|ZQf0j^x+j67+qUBcoam#J`a?3LPPnNs% z(DE0()UsTkZFx|iVELOq%<`B%(DH*2R&!eke;w;MDMm}OmDU5i{5zAlzztItA5zxyS~%H0IjnyLZ4eKK<`| z(32K8^nis8T4rI7Zm@7dxu( zo`!~-XP`^Xvr&$D9!fATKwZs?P@H)QYGf`)r_7Y-keLSUFw>*8X8%Jg%r>HT%(kGH z%u3M{X4}znvoiE2vt1}O+k=*v?L)K7_M-`A2hlLIBj^&dqbSSl57gi6B| z4xMLq0i86xhz^)uM%zrUqSdC?(Wj<2(Oags(Z5XZp~p-gp!-Z8q1#NKpgPkEwAl1H znqm49U2FOVU1eH@0@E6lZd!->m^Pq}rp>6CX)8L%v>p9y(uww&bfYaMy=bM$2lSE2 z0Q!%~5PIHZ1pUoq6y0Moj&3oTK-DHwXrajrnrbqO#+dv7gH7f_fyq2bF)@OkCi9`K z$wIi$#0<_Zw1A%$TEh1Wtzg4K8~Ade9el9R0sg(v8J=F~3J)&C!yOAf;KqesP`=Oy z<}UPuNecsD#6lumwvY@t3#pK>kPclJG9hju8yYR-!l?y(IJ7_r+ZQ0PX2D|k--1AR zd%;q8aX}FLW5Eje>w=YV+k#b4zhE^iUJwp57DU3h1yOL-f*1%Etbz0eanNT$0(4lA z2+bBG!#N95;Q0JB*f)PYY@VM1-^|Z~|IW{W*XQTLv-9)ek@A*7G4Wp8r2MW4sZ5G~NU|jkmx$#EU*kj2(fBYl zH~tOIF+K`E8~qOZjQ)TvM#teBqZ9Cv(J6S{=rlZMbOvJ6bKq{H^Ki4#1*kIm6XqLT zgegXsV3g5ixZLOpY;*(87~X`#hPPp-;T>3Oco#l1ya(?X z-iMbAAHd^=4`I3CBe>o0F+>fYK#Ac~m}&SQj5Dl&p@z?}D-O>g!|(<4F?YT;ST;dym%*SvbTX!CQ)KV~rW^FbHJA{C0VpyUgj9@|!4R~=m>3MhZ*xDwQOx_fBd`(ka_%Si z0Q2|UQFsb-aPAl^!)%y44rQ2}xu0PoCT#8(7>Hrboq+xrXUw9xlh6P&F=q<)V_Gp) zbEe^A%ni)>IWzDmW)EiToUc%gDZr#+qUX%Q6&OB-jB%gy4O(O7V`hH%20vmtfA|jT zFwZb|FqbgLG3A);7!)JHWMbklt1tjV$M|3zFlHER4;UQ#{vGyWnlP_14>8v;XE28_ zJ24wE3QR60854n7hT&iWzJG(R7)y*HX7bxNIQVTAwqf34o?>o(`wIWW{Epd+`SIHf z)L_Jzv~SZe788sSew%_6j3>tS+az3onVp@0BbaVX{p=U`0&{QnGrWR1IXe#bV}70; zgAgN~9fet#gxODUHD>Yb2xMY>XFozGjQQ*^oI5)NKYty9AHEL47EI;W0r==^KfI1P z_w@rj^0g1{#%%uD3sqlxU_K`0>w6gWwHpR~?SecE@oOi9ehGV~U%;m6=kV3^Gx%`20$!c|51yHR3J*;`fjg%k!;RCA zpkn$V%$)i0ON9+4Nn=nZ5%F)3>4P^i7DHz5xxV|AA9e*WuvQHP}9N6;@AO zf&WcihPS3J!M~<1!edi^!hKU0VCmF(sGB+mi>A)N^r_Qu&D1FvGIauqrjA3})F04m z>UU^AbrhOR{RY2J9)_cnhhWd-0oXXXAHJF_hYu$A!K;&d;pxde@X+LLxMOlB+&H-d z$|rw@xsyM^q{(eCVzLx2o!kmJlUrcGjc8 zNP(sk$?*G^L^$>(0rq~0gH2!7z}H`5;KMIb@YzgFXQuJ|F{us9iIoQ#^=H(<3GR~>ipjb{mZvyNNCzyN>e5uA-!|%c%R< zMbu{O0y=-}9Qt+iG&(YR673%S1FauDioO^D!v zL*=8}(cIBeG--4T8Zo*NT{ikZlsl?N38Na+ZB&U`jmlBu(Gqm}QxQ7+sQ~T#l!w-S z%0{1k%0TaaN<%MyT8Ezal!Wg86p#M=2|G`HibiFhBGBwltI@} z>`^#kgGxtmX!eK&nmA&LhK(#h14oQd_J{!*F!EjRI`UPI8=2A@j(pKieH_ydeH_tu zd>qo(e*B<+_OVBQ=VO=t(#LlFiI1)N{U00kKYzr|ryr~JvX7Pe?2j+?i65Wo!#_UN zFa7whp7Zg(p78OG-tFT}z17ESdZUk5^wYx^^~1yG^_|0K^mW50^v{Qn>F*8yroS?L zP=9K;Tz_Er7k%0AF8zk#GQE6wn?84Vt3G*nqdsyN>Vt;0dfu=~Pa2l#-G?Q5o8dzJ zg5f;<*P$%^$WXezdniTUFqEi&ITWXVFchP|IuxltGqhTNcxa`5*U)nP=Al5nY6$2H zh6MW5A&x#~h^Y@AqUwc1L_KxLPwzG4t+yX?*P9Mu?-4_e`tdfuN*Yd zKOQvJ-xxH|Ul{zZ`+aamw|8(-S2{SZ(+!U3iU$XE8H0VgxWR5+=wQ2U@nEZtIoPQ4 z8?4ni4_4_G4ZhMD4nEUO4Ls2e4LsC!4BXY#4&2l|8@Q&sJ8)TddEigo$$_)F0|O^@ zWdp}_8wQT(jrk~q6W%z%LlgU_yb#X7{TaG9{i(V~{fWAN`q%0%^hfJ{?+@4Q?O&xU?O(3b^#|&T`w?AcKlZ`8 zpRHTnPtz^wC+S%I{yP7DFP&>YUWe<)BJX}X-Sh`5-S7tsUDt<&y7~`Bx)&ej>h6D- z)n5HDr9JcEv-a?Z5$&!IgWAm>dbR2gUE0DA@3d(jnzXSW>a-yrs=$}eS5SA`^vOC z`bxDM`!;KpeNdaC_DNv})RW8ZJ3(1gAB)&#!CYdG(nG{pC|8vOf38k_efng#ETG~c>^ z(2RA@sC&D=s9U;6)Ro->>L=Yj>Ra9I>c6_1)yKQ*)cdW2Q0H~u zR;P4dQ^#~)QU`aRQ;WJ!s_ETF)jr(^)lS`e)r-1!s^@iYQ%`kmRu6Zf>dr2;y1q-Q ze%U2fKkUj;U+YR&pX*9iAMJ`$@9m0Gmv)7!^<68}C0$F@*;vSs*u_>ybWznoT?93j zgs90~ZfegiN40&Iwc4!9Ts^02f%;3QfqI~GR@L4)p{ng1RXy(4~M)hOoGnKaUk*c`!o+`8RhAN@+iYmPGf@)dkDHX5tn2OYSNafMFPi5D+ zQ)Sw@O*N-;lj=){UNz96RJC_VRJ9%Xs^=Y9s(T%&s=qrDRA)M3R7X0(RC_vtRX=tF zs&pMfm865M%Icu15<3D^5glHtpbl3Rzr$Wd>A=eq6b( z{fIKAyzh|Z&v!Xqe_={r4rXJQ5v`BE5Ej7DnGTY!^T#|DO=j2lvQo3 zluz4&l(*Y}@=_aDd9sbJJk&;1?rQT^ZfSEViq-GdD+1poDY)-q6{L4z z3XgZe3j23U6lU-Ein;HYipf@zVyM+e(bUbW&Bk6KL>H(Cu9f3|*;A8(zI z?{6KE?`Z9pZ))w5t6E#+;?`Pudh2U>d~1a~to5OMS?eu1uk~*^x%GnFtM#PZq4lWT zqIJJ~Uh8i8bjx=6$Cgd<_bobkQ;S?)*&>!dX~~w~Zb_40YDtivYKfK~Y6+F^ZV8fa zZ9(L^7LL56g(}Z(@s}sJc*vt#oaDhR)^bscnVivLB=>LmE^}>}lv%fYk}YWImwj*U zlznb)mi0H+$l9A<$!eRQ%3d_zmpyF0A-mpuS$3iMoa~S0KV;?2hh$~Vdu5xN%VetN ztuk>llw~w4W%13$vhe0ySy1zOnV>mQMs1Fk`80>hoSTDWmd%LFxS1`RZKBA=n*3ya zO?cV6CI?wf6HfNL$wYR)$v}3k>8td7(`V_irXgv0Q;+oLrZ(xurh2KWsZuI#s*q+h zJ(MOi-I9hkU6BSgotFxlj!S7xho!zv`=l;SWm2oAt`DR}EK2YV#wE55-zBCElajd&Ba+GbKFP=WcFFtt21#>$ zrKGC9LQ+xxKyt7CrsQh1H%N->)sn1wi6p5$ zR}x*HCRte@F9G$D5_bJc39){O#G{@kaj2(Bus~m8Snn?RTIV1ct+SN$)h&>;)y^OPnp&sg=e1VF4{J?||EZl@{8#OC(TUp8qC>U)MSE&Hib`u6i(qYKk-WB|sG#;i zQF`q^Me(&4iy~@I7pb+YZ0@ytSF#%OObo6zR12-R%BjVP-Iw}Ui7slv1qI& zs^~*aNKt#ulA`(=UeT)>Y7w@Qr|5PKzUWGgUD25u^P;0QMn%8Y%!I!D7qy^(uc?APiX$4(XaRp6P;RRJy%L|@W zi3+e4X9fRM5ehC=xfh(OvM)GNWl^xN%BbMys@eQaRpa^Es)78Hs?Pk}s)qcusyF#@ zRZsIHs_y2msJfbuRGrUfR~^eIRqfCBuG*RJT(vddx=NpKQYFndsLIQqu1w1xt&Ge6 zP#KorUKy0%P$|r>tYqZ>SLvUBzY?E+z0xlKum5B1t;4G5y13y(BNk#~VPgSy&Qdz1 zyX#OQC}4NDg56kPfMSE9i#fqLG^i+whyo%d-Fe=F1J33&1RT#P57?LUJz!hTr-0C$jDUa~UVvxLs{n_b#{m{O zcLNM_t_7^hIUBGf=U9M7&YpnjIhz9}!9DJtQ~&AS)qQuS^j=*S?+#zS+;&=Stfq^ zSz3OpvX=NQ$x`>z$eQY>nl;8xC2NS^s4RIu#jGA*`K%^iiL6TB_RJr?^_ic1D>5^E zi!yn>Uov0$zR!&FP0Nh(e9vUM`yS7<_1&Lo z;=4Ul%XdTO65q9%YQF5uDZVb5%D%RlLwrp$<$U!ryM0z>Hu@~itnksu{O+Tg`O!xu zGu>x&CdX$;X1q_o%!fXbnYVp9GA{WvW}Nb=$~fRtlCjOFAY;8xZibIfW`?s*a)zZ3 zW*GRq%mAObj0HY-GiLhS$WZaQm@&d9B4dEhkqk+ny%}xntr^wq(2NrHnv5@O?~H7= zOGYx=CL@t;n(>6Kml4fgnQ@i9B;zz&BjYf8M#fI|#EdYua)v*9XoefRe})ZPI>VUV zovz7lPG7{XNuSLwOP|F4kv@w3Iej4eUAh!IExp~Fn_laknEuoId3wJ0!}J{QsPts- z>*p3s&n&+&v)1Fh(4ttJE+u=DPEyPnX&Cj!6nv17onw4i~s)1*7D&<*|I^VM_ zRn_xH>Uhum)S;dqQsq4}QhPiEsf`{NkxzAsn0wvq~7z0 zNWJcHH1&+fzSP4WJ5qOeY)lRHSeNSO;h*Z_;gxFT;hbvVVUtREn5EA1Fi2JP&`KTW zu{>4DV_~YChgxd4yJ~8K`^3~T_c5sj?!!~xxerPey341&ahFJa;@+7O?cS7f#l0pa z!o57@pnFluHutY7>)dlw*zQ>=PVOlw=I)#nUH8P4W$rIh)ZHJYOmV-LGTQxC%3${^ zDbnueQrg{4rPR0`NhxvLoATLhdrGF;#uTpGx|Db~|CCrauasMEE-4q>>{5=qnWyY= zGfLU$rjxS94N~0QmZaFY%}X(Io0YQCZEDH_w+SgT+(xI2cN>~A)NNpjyqjD~x2r@- zgKMX-%(Yoq;94Vm=UOflxE2c&T?>SdT|WtF zjTPFvMhjQF-VkcJUKTELJtv&ydP=C`dPF$fb)Qhdb%#*ovPszFvR+u>vPM|w!WMpT zaT5w%9EEROtc6cpOoh=d2Er>YTEcJ_N_fC!v2csaTw##QETNanRH40#ig2}yvQW!q zm~fHHAmJ<*@}eylDdBLJZh?YJt3c%3AZT>{Ehu;XCHUrCBzW)qRUmNwC`fe95j=KI z6GS;D3obb)2~Ik{66|w+F4*k+ND%0JPvGHvTVU&aO>jiaAfr3&eA3?s8hak(zNx*Zm6(l&B3u2v&1vi~^1?Qbs3644~ z7wmFcCCg(bqCZ{_7NJhu6$xj_WCf{|;NxtHko*eEdNZ#+rN#5d^m>lHzGTGDd zNwS?|Y_hTA-Q-n{H99HZvqNZd zrbAFN$H71OrGt0!0|&R{NC(H{GY&S%haJq5w>uaouXoT(W;tnDx_ zd9lNs>>{&4%} zdwNciZan>uojprM4^h z`L;{=S+?`}Tw8ViOWT?J7~5(5NZU#LGq&UShipglx7!Zmud`L;d)xNs+uO?VO>Cw3 znzlW>g|;2M8MZCFaklk5CEIGAtZfCa!{#Ti#^wjF*rtG&XOqWExB0+JvdQK>vq|IK zwGr^H*l>B_Hpts=^P0EW<^?a%<_XW;<{{78=04BRCW=Sd+~Cc%xyqYrbCEaN<}7cZ zO*l`&<~Xm#`Vg+@z=Yx5>pujCE2Ue1%VUd-#Xn$N4VQs@1&n#KEU zHJz7XHJL|Ssqmg#jpg058pXS6HH;T-rO4ZFHGsF-N}d;JCBt*KlHgfeb#o1@+PN#N znzd*a^?!$PBS@fjhQsJ*i3@^$*h}`X4b($vsTVivnEcISv}{HSq09Q`@&gb_K7pg>;q?lSq^8YStdu$EREA?D&*9d@;Sw( z9L^_GU zm9yCN5@(j_dCqv#vm7PU2#&1jNlyFfW1Q;MM>s{R4{|=P-p3)&$#LGS-pP5qdK>4? z>dl-Bt2c6vtq$evTD^`FvO0+4vw983akU@EbhQshbF~*|;c5@gjMc83v8$apimM$s z(yMJbZ6?;7DiaINcM~(t2NM&Hz{H62+C-o8$V8WO(?pAN&SVwmhzZ5nZnB)S&SVM4 z+hh^P&SU|{*kmqerHMLcp2=*^G?SSeWfN7-K$EE)36sg3W@8mjx$$^Tf$>;Qj`3&? z&v+y!-gr1C#&{^_y0IeXwDBO$0pkIjEyn#gYmMbN?#414Yhx)6d5)2@+_;BUH}0Y* z8+XtnjN51h;}*KxsFAKWs;5hhYU$5L)pUkY6-^se(9ev@=(|Qg>B~mN^hu*1^j@Pv zdV^5`?QfJ%I~#qb&5b_MI!3wlVx#x;ETbHHyipddWRyY68l}kOaK-iA+Td&4-|*zgg((lC~uXZV1g zW_XVtZ5T}tG>oDp3~$p-1~=()gGl0-*Bm`fPfTzBetQ?@2f7dC=v0?sS2kE1j+9Li6;T>6dzr^aDKy`kJ0S9ieAS z@7J@TH|tr`YxJyWH$4m5QqP>$(=(%&>Y37W^h{_KJ!5*9o)ImlXGnMI8qhVm`gF0b zF8xtghfdYirr+pl(T{aC>D#)i=nJ|l>7%+7y;FAuy~#gD|Hvs z^K}=|({vZo%DM~afx7c)mhL>dNoOuyrlUcB)lsLjbku0B&K&xM&TRU=&Mf*Wp>Um< z^gf*#^d=ouIzVSS?W!}4w$PbM>*!3Omk^qzGnt;CGl^ExnMlj(sL<`&Ds;8>1p0^e zcsf^m94#c2s6Cc`q&+OM4`3t384?B1CBqr!};P(NhSG z)E-LrC)A^*L^o&+p-TyU(Nd%{2+>-D>1TwZwFc3b37yayNbeyOrZs@}BjlvjpEf0= zrKLbGBs4>-A3c_kA|WX)dAe0op03oCqrVY)M~JT}OD7PDArz@8L!TyekkA%QX*!UQ zJ0UAV`kGSoGD2#ECK4K^DM`x{>RcsB*Aglw^l6m@ol58pp~r-76S_d?C?WE^K24t6 zr^)mCGGm1n; zVZNDBNXtnv3VE3|j7(lmnSivkjDJuVqZ`NwrR6*skdWWoYa)HJ*OPPt(_CIUlL%!b zq%0&F2rqkqa4gy1#A27MEUE64Jw&!UWDgPfcG<;bvBwPG%`c6L(T6avHs?q{32$O%=0J3R@U9 zO-_Ndk(?~8aGh95rOPSyvhoTJ44WZ#H9(<|VKc?-AeP){HrBZzgsu~JU*BZ)Hw zJI14n{Mz3BSPJb-8&@$at-xaj=O+JWH1Y~F7_GaQ?Wds6upVOL0SZeQ)>Hn^;1tPA z=n3m3W``;KVqAImb}Bh}6bS}1d-CRfB4x`n`5-Snj*O*$Z`dS4<$I$}w5QG|-$>BsTOqWxgUYkeQ9d#@-Rp49|>TVpA_)MEF5WI3+g!8F2(_ zZ~&1>Y?o)&SCUvNt|FCLBueSTY>0%F#M~hg7LprD)m*Ak!h)sbF4l{6mj7+Q8p^CN z`Gf{**cDO{O<)ZlOHe|e3B3#<7Hb4Ei;*#m)KPlcAMq-&c$7pY8HH4iT<_c^Ml%aE znn{e&%mVaoNV6dlQwI(0FEwb)ARE~s5|$E*BpW5Cu=@80A|%a6u%rep>%Y9e;ZTzA zV!1r&URt7me?3dC7lo z4>HpS7!DmGp(L?N_JY;`#_a$ZmXtixhv863GOB@uWriYV2mQqoM}rsqORIQfuLPOf z+@Xx4AxHO0up|{Cw1}NjpMu32Dj{Lms~5GRY>%+M&qE`^pkhAzwdXK!=btt5L!{lBwDMQ83{B zkAkV~|Dzz=f659{lVDjeu(G#m&H&?u@n_NN&$(A&!2ok;BYiT^=h`CjKdvo^{GUQ* zNNg<`U^-^}Sw{Y&B^5GXVqnEUpMllC49K@Y$gDLY8C=wBY@4ced*791QHs^Sr{R)xLRlkM%z z_I6&NwpeAJ#@u=97dU(R2RRd$f&QNAzFuDH#B5Gba1eVA+r!geo!F_(S10O!{{36; zALJFd!JEzcM{Ot;u!x;oh>uU0n}3jhnA`ff3)Q@s(T9e4laq^@9}^75WUWV-AK`j; zdzsz&V)!dRM?tKC*>S{t~T=$h&i(6zKQ zvt)&^Jp#3Z**=;Ua~HBa{lhHT8`&YDY`s7aUrW|H>rMXN-hpgQOJcsq*oM%*r%oh6UTkLi{~3Ulp`)(bYC|hB8f^pCI<4Mbtvx&g+5Zej ziy4kjV6aEn-_HKTk+mTx)ZaIV?XBYF=Mf?vw4R4oSa8TcBi8C2F^RqjJ4kEGJXTOe^Yh5dAH$6>56B|oimcFTtindB`I`k&a+<6*{Ra8UR zfozXZ_6!v#5?=Mb?3%N{ZSfpWlA>OIDk1ER{-Gp6Rpu^TFkfS#3(Grr12a?YWzO2G ztqiUHY~8HbVH?(oB|28-ZYKVo&Q`%2LcG|{`r6toe=@c|Yr^D=7n4>Y9^U?&7yOf5 ztaaK%`k%pTTI$=Z)-|;juXCS+{{)W-LT_09H#QrHZV5@5f9C^>NarphVkRqUR63|rB)X-G#KSQ;$(bm?rvJx)|(~ucJZ&yrZ z{yfrW?;sgfZ$%tKveW(Vfq>b8|7XYhJ7NAef`26`qZDWHKjXDBG}X5;(X?c-$Wkm* zQDsuWy7!PmjzB8JOhs3GSWz(#3HD-#h6aa(&iH?kE1Jx))`K|^u_RPURYsd6Eqn8v z)$_@>f8|xsP;b*Cc5B1 zhK!9j+jE02Nlc$$(!96s;ps{CgFhbrNCJbs{$@SM&f?1!_wmQ#eWgDI)Hh2Xk`&yWb_G-zCI3(=YSu zrLSLiQtxX+sx0~aESBkCg1&0Vf7#g{AeT9P%D;3$r2com>&~%Q>xdoGFLNo=*YBRc z+K?*i^1(lGVd_ljbG?Jq|MvIeJh`AJGR7aX-}L!AOX_`XNR{=P_+#w)N}n#A2>$k0 z_m@9%nf;HyXj1QM!}v%e{*3<;^i^*W-QWIL7yhg#Gd`yOzVSUJb*7C5A*KvJ%wie- z*SazKw}k$-b3OLwD|$>DrZ75&1cXTQbp(1#HnE%E#}H&}n37MZug>t&$N%IcQ)db@ zKBjyk^!Gf-$IC1LLsYTxB*@AcvTwCTN8{QtZ-T0uHfAVGE(BeNEgTm-pHEDAW_a1%jb#_#HcMsb1~Y8(Nm26Vq}hM zjNffy+$+W-VkEmuub#Pg!`MZMF;M}^u)n1G)3=%s(F~3&KZx-`A#Qb3~e?rV(72{p8JeEPyPlgypVts$I zYcqK=oI%phBr!in%#*P7wqy2arhRYz5M*+i;Z?*qMU1n=s4hn4ZWv=niBU(424b`n zqpcX(V(iT$(r%rY4-;c=J`wpYG2fd{gg+tXne!Uc-$gMpKhGKdwiq9Z@rf8|G4jQj zF2-yz7KyP`jJ$t>uVsIrvF8OiU(xu@JlQ`!8dV~t-l zvv%>^#~91FOL<6NIk#a=$Ytali@d$%je zHt9{K2s%X~^11{O{3f`-Uj(@X>lTUN3Bg!t5gZ`s_r3>A2~NGy1A_<_t?dDRj|i_V z?}2p$9sBjbP=X`!x*?`pgdgs7!%~8$Lb?IFL};>#@C5q}>V^lMA{2b>f*}O=-S2{+ z4iT=})CHV&5q9fzL4SgYN?l;oM#lA{6LzO>f5+5u^`BAhk01Mb#{u&SaRwpNQUCcYiC ze~WO2xX$4lH2s=);f^&fg-#WKKT)qhR%xs0W&mz=mYk|diWd4E{2>d9* z%rh-;;e!ZId$ho-cOtY`Z-IB&A{^J<4278@EJvlb`yATL>PXp31%jV&|yszRJ;-4l?RzACJTQCCHHB(@$_Un1+jwH`K~Cvh~Whf8P3Iu5UgC*dN@E~x`N zA;Oza>VSJxgd29%LE<418m=bqhTTu*JEjgI_K2{dycX8(B=dP$3#+z?Fmit_$Zr@27=v17|>V^ z70x2m<5Yu#1Bu6}YDlsXp@d5{jIk8q_nFnO)>MQ^ZNK5A5$R9x8=CaUywCoI8QLQ9 zioD-oy;6kQ8oyz~a?)>46&znILWPVfxIABkwU?^knz{&ceXHQYED^q5SOtfslX*&2 z!P?0rF7GPAZ~|Gk$VwPHMubjlE8*t|5$Z0lgxg9Y)aX|U_Jc$?Hm?Gt6i8k~Rlpq? z5w?U>zzPYn9;+%KwW|kn2UWo8wjSgcl!LIb2VXuYhsCu$cyDt#T&wKCD|+S7UfP2v zhn0g#Q4j7bE`xIgJ-Fp@8RX{m;JTe<(C%FL9_k8VAty&G_m{zTVC{_p~^4tf82uxHKkx4(}VhNN?}ek!K0SO!OW}0z%lK?!hm9E zHR!?mCB-mVy9Z_Dib0R+LFJD{;JUa6=iV-YwR6e1*B3#^tRD1ON%*Oxzkx(Qp$E@> z{Q-KTd+_P~A24NT4`y%r0j&diutxU>aAkXN(6Aq{m(_#n#ou8`M>kqL{tl&$-MC@r zcQ{<#jh9Tm!^E;~Oj7<1PkwY`S$QEW%J0U(@rCg8LpLrxPzX~pyOC{G2*(B87%{OB zs*;F(?KfEUsvB$GeuJY=yK(&SZ;%nwjpmNuKq{&m_o;pZjqBZ*&{6=_7rL>UUjRYj z-8l730qi`|jV>MqaA0pYUQjQ9z1zC+eK&a&A&m5!@fBRxcH`>HUxD)J#uI*DVW?X- zW-j^)g?8PjDDxF=n0KSqhkS4_B;&uC4{}=F_&qouVwZK}bjSz&`Q5mFKt6n))s1iR zzkvIcZj`_O1-^~#M%ztaz+!keM(KWmHv_w|W#|_eE8C5R#h)Rxrwgw={tR?W7dGtt z3{tgSWWW9lE6Td?=9teA_`M4|EArrUUKiRW%t}UC%Au?_&xavjz)H&w96;(ywHV#vp&JxQ(gF}{UbCV>_W|ykMMYB z7d|@w5j-|_;W+k3kPqs@6Z1bpG`kB$5+7li3-O@%F zQ0nQ#{J8fpx49ENcfJSx-<|l|V2#*t~}Tg%yJ^X zl?6R>J8{nXEHF^*#BVFJ;PCiP3?GyQIII(OzGXs{LML{_WWpecPJFsG6I5F}Fwig) z7FTzm>ZnYhN;>e@uMAlBr30g1WWb#44)oif0V9$-aJE$jG{5e^hKU)F{d+4K z8Jr5z{W{RBFa;L%wBxdeDd5`Jj?=f3_lK9a;|Svvi1^ly^2+2pBJbO=vs?(*gzZ=# zFNAY%+OguG5cWN3#}XSM_(iwl_bEcqzS53`jRF`JPI#^W3ih{SQG@_4Z)wLecLA6N zwPTIC0NOp*g)i4R7dZTL)&59eyzFn2f~K9#g#%TFE*`rL+Np7UUNMjLAF z%ZYv|2WF_Z;mCd*csHpH-9OV1JfaO_ z?$RKw(1vXrX*kv0iUxW#DAu>)<>53O{@IGPKa-#}uNC#4CxLT%E8f_b1o7C4U6x7E z?`bPKO-cfbs8)Paj}U&b6;(J0$;VppU^qhkPSV~DVQ5GzI;tbgVz**S&s$h#--=7J z-oh&5R*bp!7FIwjPF(vI)aJJ0r4?^sSmjrslqa zG4on5^v)|VpVERVVXt88h!)Jzeg#+MTX65tSMaQ(85fr%0QYw@);>)DL18mK*h~1F zX7sg8fM?uhoIWW5u0C(Z%KCWN7Tt`GIq_hAu^Bf<#KYL5&8Y1W4~5&Bamd_wxUjYv zi&^oY@79bjb6!HVc{3ir@e+<`HKWhEmoRQYGit4R3DHxVaiZc&m_D)@rGC7CYx2!l z7WV@BcQj%4t``to)r7CiUO;L=6W*Qh0+h3w@Ivi#@JwpLqe;)<#^Wa3ed;-UyxD|X z+@1sLOcQQUe-4xOH({vg87$jC`0Qt3=+lH-BcFkpT@&sJeg?({O?Z6eGk~Q{cxmu6 zm_D-!AAElba$}nCZQN7%*1riq?0O0hx*D?s6QH)21Pr=VKch^lo@;7e8`8q-f; zPf{bU3x5I=9yj78_b2fDMkDeyp1{h8Mr>p~0nVOAobv85EDdQyhntV#o@XP5uYU}K ztQs+0^D(T^CVrJ31I}+mqvAM_o6?9UpT>dyutxm2Hx716H{t}VIEZa(z`)6Ikn^(v z-!?vis@w)tJlS`3Wg)Z?BjF>vy6Jq`+tf!4@+yuKm^>`v9=+<`Ih zXlFg9e0u<$YwOYT(F0iNQje@%4`8cFJ>D>T0I|#KQAgzgFtV%;AI!fGLq64^r}TZ0NUp>u|l(UC5nLhsLw-g72t0 zRPBz22H867mlX}6&9zv4JsPS?YB4uB8XVu(V$!N;NTO@;(U52u6IY9o#ZeG+trpKc zi-Lq>wRm!W6tr!r#iKS+py5YwS`@h2*5ZlQJFriu7SE>Kf$Q^X@%p7Z@K~i5V*~EM z>p``M%L#VX;D-T3URi@x-)_V8&ow9)cN_K!YH<4Q+u-uN28}FkgZix+TtDeHw4JKK zD~-1xen$dvp(Ro57 zOlkRzd3D!8x#Tz6aIb@0&TssD<~mfq`HimZ>yUi^Hmt2MAoGLt|a20MmtU|4VE6{nV3MC$00h5DO$lrAZ&V^Lraf>VP z(X|R~Ctra9##K1A`7$hBT!n3d%iubh__=r)whXSq`vI5XcxNRZUU3=Dl~rQEAc7w% z(fr3HIG$9A%bs3>Z84QNWB(;^zfg%|Y%jrzeU&&w^%4vYuEhQw7vYOzCHBj>2$%H; zfBhm@&LjGD7eQh?vDdl?cl(j{!!Ck$a|JH{bpi5zRG>w|1@O$Mz%@rNz|Z&!JmP!- zTy9rjjM@drI9Y-3SQlXa)(Y%=e;y*(6*x2MJp3}RK<7>8Vcv=gJZ*R$!lqYX=9u&F zNT~w**PMgz-Q{RXp98syay)nX98AkC$M4?fU`0|nsx3YTh7ZbdPrq|ua;_Xde?1HO zyUTIGqqDGdO*x*~eHJF$mSd~sS&-5!N7t!mA%9jmrnR1ddn3wmS=t#`D^ZSdSI@wV z-(@&G_zZmeREBpn&%hy08BQ5SA{x4J)goDPJUs!c99Bg*{!q_$8u-^9ex8C;Q-9%? zm#5(H;9nSb

abFC}q41+FEf=%;=PmS>itvE(UGj4#D`A5TKTjZz$c?WFUmb_UGe2?P@#8RT$4|WHb{yC~Kk?nX;}C216Gbw| zp=!xbocHAzOq}!+{bP@TY5$*iXV)EDyoOWUihl=9pkO{!hHGf zSgX1h_S6>QtnNLK@~IHlzS{#bScuP}_Q0~JLhRYH2YingqN(W~I2Kxnww4dCiN;Q_n)3}kzU%oyR26yV4y+d$o*0Iy_j zg_CLpIAhaR_%*BmIVxLWLFZTWO4|Zki@u^_*cM0-enr8!El~aND;^YX2IaF~(PI5( zfURF~+L+DY=>8RDk~cw+-dC&%+5}r>f5oCvn_!#LSMvL3BW!5P$FjhU;9HoF?ISjV zIX@qVb2h--2l=>S%?9Wfo{xdUH^7$-`FJlW3~o5(W3_)6xM}7iH7pE9OwY#)7z+FW z`Pk_f3IPpYFkomX$bJ5TC2vFE>f0~q>lXquZhyfhr4V>{_zRwRyB=l)eL)Ss^>Eed z3w~2t5AsXD;Muq9AYl9#wDnsD$x>f%^3ZiKqT(}lybT8Ttk3w>FBon<`;5Y&!H|FP zGa?2-|DB&P$v+6@dws_AVL@PJ@EMDe)IO>DAJF!W8wihlKtl^R2wVFB4SHN*l*I?MjB$k*3qGKa zy(<`w`hW*zT;XHqdwlxT1suM=$8t9p_{e>aGY7hWVf1_4_}UqsA9;^izRoae?R%Uz z+!;d6-{TFg6A0$NN9A=+Fl6L=j2!0#)*bIqBi#{BeS3%Ln;n5mzr&Dej!=F39Zt=4 z0L4S^uy~IH%nW#kG3pLLt$v5QzuAMn#yfO7W)DU~-=Wb`d(dggLCrEdSo|diwa?kX z#5Xx;u5AZWkvZsJZwue{9 zGI7%&Q&7;&#G<#Wp?g{;+O1s;0AT_0xtO2hJP z`mjrwh9yHuR~L^4|;E)zP`<#MOOSRy@s}x*RsR^c+Q*h%IO;FsHf*cb~NOMZT(LJkR`-&9Y z5w{Aak4wQC_f?SAEyOiStAJf7#3tTKXh$I)*{~A!M+$M)^pzmLTZs9efy6zGNAUHC@s~hz2_L;SErEADK2Djr1fp*9v7ulw zgzV#E=BdT7*o%+PwH8CO79a05FM^m!e7t{e5jaZn@ukxuU={N)XV4(7OY@f=j|)PVT&9Mp)@fSe8F=9HHP6j^i7exwFe&gbCnbanWx#KGsg)S;}N#+Lc& zke@@NZn+vH$I*D>sv6usNn<|?H8{AI#+@>1;A}#p#OpaQa~6%^L35z4AB}S+&w;q| zB+Sd34Zgx8Jb8RJjEqh~OU>Cp?@z+XEwjMWD+wiHWmz` zm8ml!@*85;&Y3Xg4dU1ZGa=$KqG81h5N$@>e|-k{*deA{&4A>Eh${VNz_?+Edr%dE z8s1`Es4B$gyv4OMRH6ORTWl$u4hv4a#S>?zgYTNRIM--8oH2ZhC8BANF#Rpwd@&6^ z$q@TB)8Kc>8`PgT4LUh*a8BM-kh<{(C!Qd<^9@eco(f$~Z*Xq=6sTGH22JCpz?YG4 za1)z+r@A>2AB~v;7e6Fo!@J3__DLe@9G(ozPbK1Qm<$qY6H&2w5^#(X@o3B>*rJ+< zN}iKohHN6<9W@C)l)Og6?1|(&{2JR2Oa#Tq*BHNIBHY>j8uvD;z+A`I==eYd;upWh zRURs^aQJInFiHht8(!hU>lG%x8wc!f2{_}(IJo*c0i#xpgY*jtsNOafn!*xL5H}V^SSH{a z-?5;fo`B;fj0Noh30U}P447BMW9-Q>U?Ygf!+K-D>UKP??@)}hZl^YGZM_=Njq){O4`x1w3 z9!36s@e&VfjDkRwm)NgjBn20@lVrhv*h5s8!;%zlY({IVsPVGDHvlL zg9|OB05xJza*z}_^^d{AG)ZVEeSoQlBw;W80C_r+(ErKS zE&;n|KEM@AC7@RN0q$yHf!+7}`0g1CUcI`H^VYLq_}Tk-Q;h}wLHBXxXAzZPa33A4 zL=NJp)|YiVVPkMwLR}1Iwp5hkDuJbs#V=o;jw#o`Aruk<8u#vmUL0mR^3DM z=bh9l<$Gwa(Mef1-Nl`;9h67bUF4{CP=5FB;-si{%5U#oyg9L*@^rq7E3davwu|m! zyK)<)t#}vTUudOfRz_p$uvSWeAB}|(EmX<1XjB~BLd9>2Mvvpo)P9R-%<0!m8O@4D zmqSgIf=o2Z$uv>?!YIty+emFnh{AYQBQ@o86u#NnK&7vV!tY)6)EeC=oVcx?lAaKS zyW8uii*0wXXHy+D_5B^Z+)_)$#@s>c4Ykzl19xzCQwF|oFa>fU%8{er6~WAocMzqXP(J>xcx4X&g< zNZ!UNwH4H$f?H@5TtR8SxP_-`%c=DzZ((C_Id#eR7KYW8QHiT=;qdikRNm-Ym|Opg z`rU97pM?CPI@52GJT9fAqi$kKSScmD^Cn8R{G_DpZldF+pH#d0P0VR4p(^BWqR-Y6 z>V44-RPHLKUcSD8)jNu*GiPpKp{R%o2)uzcdy1&#x;JpVbP**x{ssmf{6VF+MB-=p zAJmcTNc2ATozlD)iGv1xry6$?d3Yfe=@5zZ&_YUgUL*?7f1^qjBC&e(H)?0eb)0vt zfKqyM9nY&2P?2Y^Z1y$W zviJ)XeD@m0Cw`{h?Yf3TSAC|`?62V|ejc@7;~LI1%%eWaU&Ei7pQs5%SMjaoC(7&9 zReX{6k-8Oe6*HYbQu+Q@QK~qX8lZI*9es1DCCXPZ`}YURt>FrKhkT%RrCq^MZSSc| zx2|B-j`!5Vtyi#6>OGZcc?Ii^yrXzCuaLjTyrTq?S1{y!4#myCj3r}psD!7NG4yse zb?@k9oHR3=I^%g6>mO%Po0eV1?~Ai28>P!wjhU2Mg;7FEsqg~cRTEMdUtGZOcmXx)#09*xNz6cjc>6i@)TF6+t8+LrBZ>Mk^BgMK zB~j9n=TMp4%9{A)ENZVsYU$&%c&zO$Wqjx?Htl;$*}I;_9fRLet_#oNv@35Yw*hCd zcG?@tspJfPews*`zdnP-kVvhHID-SyUsE&v&Y-Q`YijVyGsr1Ypa}OXI1><4@xPd`bB>N8l~vm(=Kt z2-NuUf=a#>frUOVs5M(6@L|()YJhnJUfuhgx;rfbV-=rMRChRjyZ(&I{1A?6bDmLl z55h4r@hMfXJDgm9J*AxN!tv+lC)CF|;h5n2gff&4$Jmy~R6_nKqz^o%CO$cZEyEsD z`wyK$lRI%#vCAps&X1#(FF1vcyhqeYg;S_x^@#fV<0MuUKcptdpTyFThZOt7Nn}Yq zq;7eg#N}sVsr;oU@xtU-YJlQN9QHhhTJq}zKGlh#+}@nP^&cNldrqG~bDsy)HNO*R z(R!bH1}8A&@O>(I*a>_w`aYFYc^pT@+@td7<9KZa!SlyaE9)-xA@DfLyWgc!wT@$5 zeKhrY)NyRv7fnUg9K%T?qN!v2V;FcZidu8|7=B(BMd__OhV0Bc)L6Y^IMn?P^?S@Q zEN-|>#n&Ij_XloMJA_BEWYlenx^@&t#NMLXLXM*U%3IV!gQHmZ{wC!*{wQwnxk>eF zI)bx1ZcvX>kD$!S83e73%cHLwNGZWvblx5IXB$rj|`SgvQ@4{U4UjIxecMjlwp9ih*LHVquG- z#LU_2#Y7OhyW^Tyy>=^h>$UsZb?u(B?e6Xt6-5k`hWXC*TYvbQA0Rn1XZGIjTF;}V z#ZA*4hOSW8uTInRT~{dg4b$}7b<0(Q;nQ>*|K)0OgK7HfwPos1@o9Qn_hstMuc>-U z(o*Gib*i4QaH*=eeyUzmcBu**HdQ}6xkPmfo2pgoC2Cl)srppR-zwr~gzh=*Z#DOF zgsxEZZ?$l3g!VYRSj`_Ap}iU{Rx|5I=+O6z)OfE5y=?ph-ohAPw)%xNTy=>1y zrB+YTVf7a(ufbDvvDXV!Lft9abMyjrqtFyx#bbe5_jR)FyKBDccW$!2Sa-gvwqmlb z`*NQ8IbgDWKXRVhS8KA~mS>*&BmZPQch_81BzlrwTyL(ra%z%xyqcqiE}5iV#>`Rq z`%cnB^UYC*FiB_FJ6kpOn4}Mc%~tO|Ow`jNXQ{s&6ZM#hvy^keM7^l+EH$;~M1Ae> zOqInpQTsHTsV2Km)SJJ|P_gGH=(;m!s7C`QXqVD6)c*Vvbo8m|YRakcI<~`f752w? zT{v-?a>+AZ_g*qhoj5*D->W)J_3S=Q_qZ`tWy(HId-j{ERvjFxKega|K$|5sMQ$#_t+^aK5ewlTWE@EzIC)da%8gF+<3Ge+j6psi65nV z#7$>W|W^s!USzzKztMu1{2Zmygu#`%hGtf=BAFZWGnRk0W$=^9kzN zf)U!eV7z)1I6}wW7^kkj8m|3vj8g|@4A+Mmj8%($hwHJk#;87zhUuA?N2?kWhv}zT zN2>&%VR}gYQEK1KzjUJ+BURTCf9XFjjZiMd{?ZS#j!>H}4Al{#!&TtGp?dhNVd_l2 zq59vef2rE$5M3e1U+P4UAv&hfP*pDb5FNK*h?;j`u=u=>=_g0JQqtc(nU_1-pr zs;S%m)HhcRQsYCO2sY&*MI&@TDHSx^=y;T39hR++ zSGuZy5B#C$dvsL+?f%gHI&@J-(phhB?yM?r?V}T7I;qtS`{-?fomBdtz4hA39aYDb zz4g;;9n`+y-nvu%4l4P5FI~13Iol)uzWib%i=@)zt|-bsS#@{4C1*>O)V;f|+OdUt>)PG= zyEIql_H@%;iOtlimfiHYkY=iHa#vk?X;bC9p{vdl*+j+E>#9SlH&Gj-yXdo18mq>O zy69t@wUG)5tjnv%do%O4s4OOuzo%P6b;c9!?&boEJa8>?BCq1@T1NG0)PCDvH zn95VIlV0l@rbg+GdPVzC^{9JC{d9MIRoS(p?wPK>8vAbt?cY2^oo?PiH`-E9r6#o3 z|0dQ|RoAxHR_#}HtleJM-cUzP{Mb&9`c+%4n%hpth1OQPtF_a|*Va-;9=6pNVr!~n zW83P2p*7Wh@3#8j+F-TuLL0sGr>NQe+UQeZqWa}(qpNLzwXSTfKgTQO(XO?QZlu(c zv{t(M7DKJr*h-&EwX4SUTj|v;?J708rFQJLsZ9%8>XKP(s-}NSeWz29dibP;zI-H5 z^_b8?XU!d`K9y{t=k*Oxy)QM_9nblzr~RAjp+)^w{oKv<~Pyx5`EPyza~1erLX$; zVPk!5e-(9QOkTfWt)TYAhwBQP%B$I{!u6VrKsZRsWW6 zpaUX&RQDTU*8N{b`j%8#eR-4bfs2SLN>4(>CwoYVyc>di>O4 z>Q3Q$+U-+ORrq9G{jyO})uCHmoqE7aEzMk4_bBM4E^Vu$^G+zDel)0~vqu(I`M%cH zjT#hIRTtIPkMBe>65#1Deufm4=RvL?b&KrIm4XF zKg`fOzqzZ!(RLls(Op%UZ`V1lfbR)=kMsI_B#Xhx2vw|`-VWB$L^}i*9p|)cVt!V-v{XGg|e!M83EdF zmW$e2K0uF6%A(F*^Vd21WwBmw{PpLjnbrGT{yI;?%qn_+4Lw9xShJ<*+lV)3)kX-ZO*R{LD|gB&AoA$NTAO1JbKD#r^cQSLu|`nQFRsi*)L1 z_iFmh0;jPzb2UA4RGQImYgK)&TdGksw5nblo?=}67k-mnd>qMN*rGtTF!qF3DgWrQBAtcRceX8~JRN^s({ZjFC?(>hXiV8u!Ll)DODE80Csq)aROgF-DxMphN0L8z;L|(47K5 z8|gDt&~6n!8TO6kb%Wwj#-KXowRgUc#+t}-dXC!%gsHr;z8(x;sEj(=yQT`H>^ z#Jn}~^ewC1-oG)5Wh<*Yy?AYu-sPj~KYV4BZs?;g+CA93lYrGm!Lbu#^$CzHAgwAl_wo&$&x2|*OmT{)7 zw=Qz@rqMd7xSn<5h7q~4xSn_Nx-r0BT$ep}&4_tgOt-##)#y96nD)AP#dukym>zZi zveDQqs{1{=WE|~SRR4T?(I}kerSn8zFh;KR(ieZ8H*UguJMElN{ACdx>vGQMJE4em zzJJ!(Q>=&{<#oo0Iayd2EqB`R=~7s?t#Qg|o35}fU+bhXZG9oVsIfM72N%){JDSFg zR|R#M{thE*VnN+(%n2i{ctM?S_HiS}=>mG-s$+&{*8;lJuA@f5^aXUJdBn)SA-~Re z>#*ToGrvCa=8%!@wWrP)chHEQ=&2)J4;puhd+JU_4;Tkd<OMK@qA5gD@U`<7^QOS+MTuBnp_HjK@sTQA>iR4kH9 z*FC(+*nc9YzH)D)QLTMW{UP=rV|S9fUhVOZQDUXL{^+;CSQO;0ueDfjq&&)@Lx!(2 zx{l1D+bv&foXVd=XF0LPD0C#d4t=rO7}zSiE}3DqVgAadmzG&&xGc%0H#AsjG^n0U z*B-pWn041pk6*UjI6K5mH`U9G_}p&#MC4MV%syAGb1XHQG;!5!{g)Vjea))pbpG2| zJTI$mGjp-AyHZwt;=m%~^fecKu1p` z7R)mqf5@!o>$%2_X_>XxmpR7C(wTMbB6Ex#=Q8OG;j@kT-81QSV`mwEX2_(&cF#1z zH)PazU(7H{1ZUJgbImY*zQ~~etv%g1H7`F5w76f@Cy{XWg~@R?{7FO_D_IXT{F z)iu>DQEi+td2NdMdGi=!)6-=0eWB5Yqd>Chv2dhuwPlhyH0ucC)}ll+)1+a>wVMg% zrKF*T&YobN95%$*5*lxQ{Qjpgby}QRd(a@G-PvE}oi787GU1*r5&z@6xo~7JsT*))>|JlbPvb zYvcIrDD&*7Rz~c_kLKa*EsYYHKAO+hH#h1Be=r05n;E^vzBkWbYhsK(8fi}N(b$;w z^PM?1wV^T7_noZEwsaH$#mM?_Qhj2Glo<;;+pX*+UGE4zJ8f zyXqQmmc2CJHmqZ8yZgc%^{tlCGv^Dl&fhhSLJgjqwS$6<3)7yN!(YPad*-S6Vwy5C zr#&%8S22ubK~KyEk8MVYVUNuw5kbbLy^qXUzJZ2U^g}c8xxX>r=b^b~P7NcW+XHi$ zQQc^>_P#mgOEqKP<9p`$bybb@`R^tTavyyT8!fo@_Ulon- z>2I4AD^)NGs$1sn_vMVhkvGlm8_F6@4%{#scl0s3#9TKA6)I!&E_dC$@Tip0yT>)N z>GG0B=XF<2kG3U@#!s%8ZiT&#z8dOsibP zn4RvTnLfUd(a?Uuw4EwwxC}pUZl6`aIJWnk*|=4HqsQm7X8DqyhD({Vru}4mrgK3ar>@iK?8+j?{Tq3lM! zB!}63ZZ>0hb%)uZmz!~O;0be1u&d#{{kR!hIIGeB?J;vfLKb7M*D!aqt zLz#>ci;kFkmSi-VTsv&~jL2Y&%yQU#&^EoXJou35Q0a{QqYs*U>!#Vy9Xw#R&XZ!l z8MEK)_d3yjuk3y^W`Df>PPcvL%W1#tmsjsK(J|J3?7<#0oBwzFKe_gpA-TWWr-uD& zevgT^ca7L>y59U`x2}EWf_)$DnG$xI)0V!sU#q&){5A`q*mo4zX5R68W^dYTtJ%%xiT%gyEoN7*NA@}AH=8%}J+K#dZZdc0x@X@V zxXDb)amQX`$VT&Uj$8J_JO44?=DcC|joe^P$a~Gcx#$LSR^cmlk2dSgETu2m$1GfD z{_wqEe|}}H*-*~e12e5P3pP1ppQqNCExVtxzZkySOg~E7efF+0y%sv`{i0TyJ9Zwo zZ!59V+*>n9G`+x&;&7tpB*~6men6c$o+PzE9G2abc zZjbFa+pK?bsr}^AS*BNxCH84IXPP}aF1FXtI@9#pyU?Dw<_xob<^^`gsOe^8hk5pa z`=^<|4$rX{{yfzj?lIebrsPz!?~s}Ho*g30TX(11Gc1{6ZV#AdUv+)5`EyN#y>gbx z=Kd^G><&ya-wd8)uRCI*>2`90{qN2b%o^*)+85m#XV!}tWuIPitZ57!ZXddTv{|s@ zP4TsX}Fmuq_6$du)oadp}p;6-w!e0H0fcl+u4X@`TAD!!+$Lt|RUiA2)JEp;+NJFq2Q)NipDJOW_Pl{PvsQ6?w}xTn;LBcif3v<> zvt?m>hDsr3a%2Jfh1GS5zpS2n0+8$Z$Eq2(sZW{A*Qu`;&wk=CE^Vwnlxb zn-AM3*-kvHX1b^TvU!J8H4AO~Zku?xikaNui|ujg%I5yUQML+8Dw^`{oo#rg3g(8x zuWZMMmNOqOdS**_<70jp`N-zmtc-cB&plh$)1}Pm-EP_D_?9#a^txu-yUyF3IP{Y3 zrh9So)U0#1595lO4|bliB}Nx9&pvS2GIuC!&d7Gm=61E9St{(1&COQ8T)t?ZE%SCy z^WD4Mw#5ATOqZHFY#*k1m>IWjvEBNW+kD`;(RQ#$E_2F)b+(0f-A$Lgt8IO2F0r{4cQdy?UTC{BFRQsQVxH~q)GTJRpxL%&{WF`<@zZT?PcxdGPes^t zXa;lFqDi*?N7I>Go{zOvXq4vIx_!9quL{YI4m1C>9mtyCI5)PhEh_S-bWD8s$;|RRo#@2M)XUCA7&28P&wUSad9}w;(?2R`vSXK{(al#uam%+muFroI)MMBd$H@`5g042* z=qNe;Qc$JJ>m7;ash}BdYaF$U91D8>euX35Kl_3zo?Ysw+IUCMuyu7 zBc|Bupt#m^9b;-Q393?kmSfz!c|qNBO?UiEHzR04^c2Udm6L*wU7F~KI66G&c<2~M zwOM_G64DQIT;I_tsN(T~juwTQ2elc}$8qsdNYLo=-5h1#8$o}+Y3~?Ot6I>Ol`S0y zzxV|0Y1Y{B@`G2Xt1 z+BnCF1=qg^Wcae@MAz}R0(?7cJaK!=zJNAYm!5c2Z%M!y+pH7i%;5pP&BvU$`!pn= zOVw^CE<||+%*YvfBIAwk{@cD(IgxYgKL68KJx}y7hx>1Do_zd8l$Za7oR^Om-MX*F z)2mC5zl-v!aX)A1@%K?))gR})eC$60K#%e_xAE;De%!|YZ{z3N`1Nf3`gVRlJHNl3 zKaZV1pPfIioj<>wzmJ{2pPj$2oxi`Ge-AtVK6d`S?EL%L`S&#V_ci$UHu(29cz+nY ze+=GV2Jb(E_ou=8*Wmqa@cuXWcrf_*F!*>e`1mpScry6-GWd8i`1mvUcr^IHu!iq`1m*Yd@%U@F!+2i`1~>Wd@}g_GWdKm`1~{Yd^Gs{H28cq`202a zd^Y&}Hu!uu`206`JurBEFnGN%c>OSVJu!HFF?hW(c>OVWJu-NGGI+f*c>OYXJu`TH zGkCo-c>ObYJv4ZIRJ>j)UOyGDr;68C#p|u&^;hwFtayD^yk09_zZI|Nir06=>%HRj zU-9)o@%2IR^+NIWL-F-Q@%2UV^+xgaNAdMY@%2gZ^-A&eOY!wg@%2sd^-l5iPx19o z@%2&h^-}TmQ}Ojw@%2^l^;YrqSMl{&@%35p^;+@uTk-W=@%3Ht^kGy8hT{4|aXq5AK2cn+D6U@=*E5Ri8^!gG;`&E%J*2okQd}=7uAdaw zQ;O>=#r2lr`b%*=rno*+T(2pv-xSw#it9VY^`7GTPjNk{xIR=|FDkAd71xuB>r2J; zrsDcjaXo6yz<;k#71yhZ>sQ6~tm67salNa!{#9HLE3S_f*UO6QXT|lj;`&-~y{)+Z zR$PxOuFnx%1l#r3@6`d)FpueknK+z%-34;1$ciu(t}{e z6!$BN`xnLijN<-AalfOu|54lzDejLH_e+ZVC&m4g;{Hl;zooeUQrwRz?#~qWYl{0f z#r>S({!Vefr?~%9+z%@54;A-|iu*^!{iNdlQgOejxc^k#k1Fm@75A%(`&Y&Ntm6Jw zalfm$|5e-%EAEdK_sfd=XT|-r;{Mv2k^bIqEAGD)_v4EDbH)9-;{IK6Kd-pISKRL_ z?*A3f0~F5(6weD3&kq#O6BN%E6wezJ&mR=eBNWdk6wfOZ&o30uGZfD^6wf;p&p#B; zLln{a6wiAU&wmupgA~t) z6wiwk&yN((lN8UF6wjL!&z}^}qZH4l6wj*^^vlP#_6wkX9&%YGU!xYcQ6wk{P z&(9Rk(-hCw6wlif&)*c!;}p;56wm7v&+in^^Aykb6wmt<&;Jz90~OB)70(M5&kq&P z6BW-F70(+L&mR@fBNfjl!ShP+{1QCR1kX3Y^G@*m6Fd(E&qu-YQt@a`5~dJWmJD*TM64@cbP-j|b1^!Sj0X{2n~d z2haDx^M3IBADjn(^8s*P0L~A*|J0Ot+h`~jRtfb$7(UIET8zZ@_sDINt&1J>dKYoCksPA#h#< z&X2%(5;$K1=S|@J37kiP^C@s%12j}hJ{2iRfgY$WCUJuUi!FfJ7-v{UY;QSxV1AzGeFfRb+2f#c5 zm@feH24MaG%p+Lrf#3NAFs}gS7r;CNm~Q~{4q*NP%tL_r2&;SaJ1+s|C%`-fn6Ciy z7GVAY%wvH03^1<&<~P7R2bk{w^B!RS1I&Yf`4BKK0_I1+JPDXD0rMtc{shdUfcX?K zuL9;*z&s0>ZvpczVEzTn!+`l1FfRk-{s_z?f%zmbuLS0oz&sO}Zvyj9VEzfrLs|F# z?|c-Pmjd%sV4e!hSAlseFn9W^J8G1 z49u5-c{4D72IkSgd>WWn1M_QOo(;^mfq6GD{|4sazVEz%zLxTB8FfR$_C&4@=n6Cu$mSFx8%wvN2Ofatr<~PASr`09> zo$mzmo?!kH%!7jYP%tkF=10LiDVQ$>^QK__6wIT7`BX5k3g%bAJS&)Q1@o?8{uRu_ zg85i5FAL^p!8|RPuLbkAVEz`&dcfmX_nC}JizF__r%mah@U@$KX=7+&N zF_fuLtw?VE!J=;r)P0I)9r_6NW|0oX49`vzeD0PG`JY~J7f1hB6F_7}iD1K4i>`wn3L0qjG7{Rprx z0rn@rJ_XpX0Q(kT{{rk|fc*@xuL1Tqz&;1q?*RKAVE+T`gMj@IurC7kN5DP_*e?P5 zCSd=>Vs-uQqk#Psu&)C4SHM0C*lz**E@1x!?8AWl7_ct`_GiF84cM;%`!-?f&Cz`F9i07z&;V!F9Q2UVE+j0BZ2)Su&)I6m%u&~ z*lz;+PGJ8D>_dV5D6lUD_NTx;71*x=`&MB83hZNn{VcGr1@^bVJ{Q>U0{dQI{|oGc zf&DPBF9!C-Zeafn?8AZmIIu4V_UFJp z9oVk}`*vXe4(#KB{XDCC`n#_O_V>U(AK32$`+i{m59|Yi{XnoU2=)iTJ|WmI1p9_y z{}AjWg8f9WuL$-R!9F9{Zv^{}VE+;9LxTNCurCSrC&4}?*slcpmSF!9>|=ucOt7yB z_BX*kC)n=<`<`I`6YPV6{ZOzk3ie0AJ}KBQ1^cF8{}k+_g8fvmuL|~8!9FY4Zw33V zVE+~D!-D--urCYtXTd%#*slfqwqXAj?Bjy{T(GYT_IJTPFWBz|`@UfR7wiLr{a~;! z4EBe?J~7xY2K&Zf{}}8egZ*T%uMGB=!9FwCZwC9$VE-BHLxcTjurF;rj(_*3!9F$E zuLk?pVE-EIV}t!{u&)jFx4}L)*zX4W-eCV5?1O{-aIh~9_Q%0KIoK};`{rQ(9PFcm z{dBOe4))ikXHioOF*6p$TtCbCm{a>4*b3dmOhc`G1)1>~`S zd=`+`0`glxo(sr#0eLSV{{`g1fP5H`7lWYx^J74s49J%Oc{3n?2ISFzd>W8f1M+J? zo(;&i0eLqd{|4mYfP5T~mjm*1K%NfB*8zDuAb$ts@qm0DkkiTOBLewEAg>7I7lAw@kZ%O?j;!$ZrC9P9Wb2Cy)mP@}WRp6v&SPc~T%> z3gk_J{3(z}1@fstUKPl%0(n*--wNbif&43whXwMnKwcKe&jNW`AYTjQZGrqPkjDk` zxj3UKz+Q19@g3 z-wfoPf&4R&hX(S|KwcWiPXl>sAYTpSt%3YCkjDn{*+5_EO9$h!micOVZBE*`JW&U6y$?~ zyikxI3i3ojzNp3A|IHf(`J*6@6y%eFyi$-~3i3=rzA4B%Md1JWryvg%D^-D#%*}`Kut0738ymyjGCk3i4b*zAMOk1^KTa4;JLZg1lIe9}DtiLB1@=n+5r^ zAdeR0(}KKOkY5Y(Y(c&)$h!skw;&G}i26@dOzZv8?gM4RnJNBFR4Dz2r z9yG{@26@pSKN{pogM4X_Hx2TqK^`^8rv`b|Aio;qS!3q^`PLxs8suMtJZzAU4f3)< zem2O{2Km|`ZyV%qgFJ4K&kgdrL4G&L^R~`QfAhUT-Z#kq26^Bh9~|U`gZyxiCl2z( zLEbpX9|w8lAfFuMm4p0pkY^6^%|YHd$Ug^p=pY{*Y zAfMg(JOAdjgZy@o=MM7SLEgKSqxsE$2YK)yA0FhzTW*Zs{CJQjZ?VvR^W{O_JZ%5x z&x1UAkWUZt>Op=z$g>Ce_8{*bcCESB$Ye*owc0Q~}>ZvgZUfIb4yPXPJ~Kz{+~GXVVt zpzi?mAAmjt(2oH65q{W73$2K3K>J{r(Z1Nv$}e~tC{{_V2?{WhTQ z#&VtQ|IdE|`fxx$4(Q7P{W+jd2lVTJz8%oN1NwMCKM&~Z0sTFo&jH_kU&2Y=t~0q zNuW;&^echBCD6YF`j|jJ6Xro!!vg(Spf3ybXMsK~(60shwm|!mf&MwrM+f@pKwll`uLFH{px+Mk-GTl)(1(Yj9e?}r zKwlo{&jWpWpkEL4?O8d)-~K(&#|QfPKwlr|?*n~)px+Pl{ek{J&<6B3BIr-V$ilyUilAQ+ z^euw^MbO6x`WZoABj|4geU6~t5%fKR{zuRU3Hl*HUnJ;{1bvdAUlR09g8oU+M+y2V zL0={4uLOOTpx+YoU4s5g(1!{7F+pD@=+6XwnxJ13^lgIvP0+^)`Z+;gC+P14eV(A- z6ZCz8{!eSJ^V1%0NV-xTzng8oy` zhYI>pL0>B9PX&FdpkEdAt%Ckl(8mh;SwUYb=x+smuAtu)^u2=qSI`Fw`e8v|Ea;B~ zeX^im7WB=6{#npR3;Jn6UoGgbwOnMseYT+A7WCbM{#($83;JQE?*)Cnpx+nt{eu2q&<70qfk9s|=nn>c!d4FZw_h0a4TJt+&_@jV zi9ug6=r0C+#-QIA^c{o#W9z)&w+|WgBZIzV(4P$YltI5T=vxN;%b<@L^fQCLX3*aZ z`kX<(Gw6E;{m-Be8uUYhzG%=N4f>=(zclEZ2L02Zj~et-gT89eUk&=KLBBQVySAR! zzx~&s4;%DjgT8FgpAGu7LBBTW+s3i~`?o&(> z2mR`xZyofngFbf9&kp+9L4P~wa|iwIpzj^@zk@z_&<_v#;z55r=#vNi@}O@X^v{Dn zdeBb~`szV{J?OIs{q~^m9v7abAa}A8uI{PWVcmuYry?lDiTOiPp{?7yo2<7}o$!2^ zik;SNJJ&RLq&cz1o`yfI+t&lqaL&3dy*>@@PAB@@Nkb#+c2_1Rrdqe({GHfm-B$m@ ziF?-V$W=~6TeptuP9$5mR{dZ8`&Xi1I{EMII@Qw2e;@DFAf5d8|7Y|_C;xr^j&bSa zzpr;~X*&7u>&NU#C;xrFT$j_yf8W3An{@Ku&(l0Po&5Ln4a=Ke{`+~CRZ1`a{rpGk zrI-JHpC_HIx2@Zhk?G~X-`8tVdin47m!0WlV3HGE&ZU>riB3#!Se0HK=tBi6q%86Nn zGD`Q4*5}X2D49Pvad|^VSrh3*)bWf`;hhs%?`4!dZ>;bCC8Lyk?L@sSnPkOFCwdgi zB{(hNhWh&l4w3_01#+kDPchC6fd^w0{59nWX=HCkh_UB+KqP5pXk; z9J}pAi;tP)_Dv@Sr_U@etovwQq0I8;suMf?GRw2ePFxDlEY~hN@vdiP*?-=;|0ZOX z`DdLdvOKeNJ?%u`zRXhoq;)@B$t+P0CkDOEENhQjzfVeL2|en>=6qS?(;+8LR?Z@m z4><8SB#Y$S=fux0S!D6QPUIM!MRM%2ey_z@WZZTqf_G(+w_B{o-T5pco17T(B8x2C z;Kc0sEb?Tnb^qjYkpiooI8n|;8m_P&ueDrcSEom zSzINmgA*N#xk}r%P7Dlmm6I)Rcotw-Fu%0^w-DIVo^}O|SlQmVW=V!Q^EUVx|$)0X9 z-Ny;v@oqApq!Y$6Hwi7~M95w@DN@+FUoN}JJ5MJ%y>XL`d9254vYWJVxBjkqvq?rb zC&pIFCYv%_&)s_2#7J-5|DChR<&-om9hprUCZu8Q!fbLeHVvD1WRrleY1nl(o2>bi zh6B&CNn&Igj{V9e;jh!6-LuP*XV$gBC%fExn1)Ni*~Rs48m_g?F4b?O;ntAs((-Z| z?#|9G1J0%4!KUmo=42Wknb~E+@iaVnkX=R{O2gBy+2xPDX?T`3hcwxlhUeZnq|z4a zZCegWx52t?o%|h*3Xl{U1|(Z!`Z^_viHw4nAP3IyI&fPG<264J=3tSm%BuEPQ#7~?h@E84gV~6 zm&q;CuyUWfoNkncg;(4qzJ3~}zjc?AwbL*z#a-&DG%G)!Q#u8tp-<(UGN5Xjl^f3~ zLn@@9Nf+zw(rKtY%KCV*G}Ks>Q|c8=gU`;KQpzI@1@R? zspxLzl2X@G(da=gnR6i(0bg^;=aZ@M&YD|-kEO!ZJGac*pNj86x#ikU>+3hmEg3gk z*Zh9D#dmEgHbvx?7RypGb4_j;xF8h+59gNgGgHy@W^S1}ITh7E=9bB0QjtG>9{KC9 zR3sM6Bb^4M;&HV+qI#v`c!NCR(K!_>dgPH8t*xJHTpn59Bo(ce=8?9c*5~iZBQCX4 zk?T?(*=0*b^s77);+Kj`iFxEvg;e~L$3wc5O2ya;9`d|MDq7a@kf!-kQK_ScIC7*S z^KcI-k|h<-=6T4_v=r>$>LI7%QZW6Lhh+SkVm+@t#Q2bcDnC4=|H~9)$d*?YJxsy< zl6mFdn%bJ)dgYTXJyVc= zLO!u|Ou@xv`Q%)S6wKM1PwIrHpy}m&a-wz$^1jI@W$h_=n3PXuS4+VP4^N3Kmx6W` zJ*B#L3JTZtl+guJ@T8-s9Lbr2<-iqDOmQRwA=9XU?-cH8hlKI7cDH#Ke{8Id6GD@|~FDZwT@nk@LxxOnI^QYyP zB^#4bdtH8MzA_ncNAioy!enf_m0$KxPe$7)>;2=C;hLd@~3pnP^qM#l05#XWs8w$>^rW#f|&*1n(wd`Uv|(1N1gCSmTJf?|7| zgi4zWN~N1gxMmg<&+|#>`=FrwI-UfVuLb4m-Xv^vDJ09bBmu<>N!!&)cobMj@+?Zi z;HHJ-^zn(OTwngg~h*I68u66OGMEmobFs$E_)=Q;mE?0$u$X&7g!%pOGNkW zg{4z$BEFn1EMq?=V%U?yvhaB#QhpSc)prsxIa?7~b1@NFOBInNjzr8cipZ3GiEwXO zMEYz=#DW1ur1q*r4=o}qMStJeq$jE){ylV|6-jv9*cE zy8_-4+#nw1t9pw8>+?drrE=AH9PH{X`AfwkZj`sgdB!7fk+)oPjmO9x-m)Sk4oA*- zOZ%^J`1!+bRyBCLk*-A*ii*eXovV^!CkHd3&30b)-4tZOYkW%a75Z1qh zY+4wH@ew7Ya73K7E+`>0hR5N}!4eYPCk`IhOGv%;ai|qpLY6g*!=Tg>@EmlgJEdPZ%0i~qKtY7HVxRksY^9v(-my%@z zeqsKEQWDbn7d9^|C10BS!tp(&WM(bv>s>4*Ue$l$<;zmCrSva+i!UWU`G3Kgv$U+q z`U~01mX>TuKT$Bav<&+E6D8Y}mdnq6TDktxQs~A{)R<9Px}E$9`})$de(z5NA1y8S zH~d7MTcsu4;-9GZv9y$kux`_p5!*29wm=yP?e){zf0vQQt$#x5myrhbf5O(Kj3DSI z{6>}$pYlIZVL=&jDf|;9ww00p<{zG?%E*qCShzhZBLlz0T5iTNQuakGqFsFC@r_tK zE#@PWPR8O=fR7a08;gUDedOT!Sgh^sBeF0S(Hby9g*cl$dc3YC|_r@te(T6vkb_d60p%S-&a@7UM1 zytJPG9lb}Dmw(59N0Ei)C3(Pi+}u`Pq~mu?JXKyshku9fqw=!L{v9vAmX~|wzhjn5 z1&J;A9W{zokgTrO`~53O-h^+M+Ngr$|L_eJdR36z55D2%xC)Z~{5K3~mo1zEN58yY>UAiXAj!>8B^Qg+ZcL}aTduRDH2k&+c51DC_{gJ#jL#*<@4LG@Vrz}+THnz^)D;R$x~lZ zF214^-t!fE-7Cq!HDBRhrji_;{T0VlB}o|d750{u#JA5^oakRkI<@+WpomH`rOsCz zUR6ofR{M&o2P( zS=v^QLFMGi^4U8E^YT=Yp*dp^U9O7!Ncn>LHLFOUPhYUHO%=KS@C%X$Rgs|cU(jrN z6|&UD$V_Z@at8i|L8AR{jQ2^==}vz$yMY=i!Z3*;VVCCe!+zD zzLLGl7hJ6AD_%vuz`d=nlym9^MI-NFU-{&SM$_xQ za(;U>=DhQjrAwo6KG|0~O^HToo~lyx&uCODUsdjPh(^zvRb^smG?ulgDy96RadA*p zIawkazou1{COM-~d~H>EoctMKhpI}OkDoE*T2;Am?=x1sttu8c7G_daS-<-;UgoYQ z$tym?S+<&lPy39b!PR8Rkk7ESt|s?8eMZZH)g*g^&loVZngj)WM#SoB(y65Nbq-XM zQ8_;J#-ldZ1S=l}AP+P|Xk zHhXn>_$msIN>-O{*P?LMR$bm5iGrhPb?LY<3Oo8#muvH)uxvtg@f#h5$xExt!k$s+ zx4XK$ZxV%O=c-FJBMJdetIJG4|C2SOWUG&u`k;nntoad5 zztoT?6+WVHCV$!H`4Mjm`OARxAF;ivzm$vqfC2UW<@tjTsNC6Krl0HzUw{2sFo1W3zq?@|6r zfDG>a9+zGPNJP{3=pG*+^X%`Dnj=u=mwu1GO9je|obOT29w;LcBXOc>pmcg0iSRyw zV!s}Vr{e=9*O5r8haD)-)<@#|&Oli|D-xs51WLQVBH?@#DA_tiV)EBOIT#X&j9G%D zMb$`5DH0@~3q>NGUyzK-6p7KHL6Y|69b!8N$(V=l@W=2Vi8=KS&*ub5+a2%Fcw>;9 zSo{trj|EBIaqm#^R*>}U^$yG42g$C+?~pFl`g(!y(A&c%-X-4QS~;6E%JvSGgKaYO z=UdEcWs`Z&-y*udO*UM3i;yWc*}3N})~~S1uH|nLzsDwi|!*1=T-k@N(UB~GMu zydj@{zQ+7uL+U<%jpMBhS$_UC-t{-+_3qbjn_@_brLR$Cg(2<7zedwNhRo{q8iUUp zvaiu=%zJ9cE&tcp{@swsqOWnrMOoMJ*LdWmBrfI^qW!G5AG|_ZsFFzi3OTwcxw+*P z3Jq7XcitnxkCJwsUcv9E67PDi;D1BOt4gmB@J`9neAe4ZO6sJ(M73Oy zsCO?>v5ckLy!H|$4M@R*FHxWwWb>+*$kqqqGvy_c$3ZsqeTk^WkUY&^;{JB)sTA}Q z`XuCO@t4?iAL5twC1!qxO#1o)ebb9vdhh~a`9(787x1YhV%z)z>1&Jhp7R2a+lb5_ z`T~0fifn230+S;|j@5jD<|{?cmVE*5y&~sxzQC9BB0BCl4nGyy^ZYr+eHU4F?m23@ z1k3Q9&ymq9SQ;*RjnpUUz;DTc==ITkko33=Nj%m7ZhU%wTbPJV*O= z!Ll*w8L}M;7QB9jV^@OZ_QhxD`6^i2|N9K?al!KZ?`Jrat){dZ^9*ghYs$s0&yeI_ zQ>xT|X3fEB%Dl?Y;NPvLywCd#w?@>I>d8;hdu~k`{rV|V{;4TPFFwWmqc!Er?x!ev zqox%4`zdz4ttlA&6ak4frCpb&IO$$X2G)Cux}|E#sESWg3ZTk$>U*9;CZW-tZ)AWQzL6h=bBIO zJ*k#>`aD6qT(#v~_9r-9y0-NF@fc<7wZ-MpV@z*STUMKo@xEtmDYx-4YLBTcyJtMc zng!O|10Un(X6xh4A0zZcZOIz+7^`kspI`JbK1J4+^BEr_Ai1`9Mm@shTy><&jYqg# zx{ho(@CfeqI`U-sBQ$AJN3xB7gatk8h+p?dxIVg$G_U^%Sr^oizLg#!cyk>YmFE$L z9j{}ZH$TMIn{{Nuvxj*2u8s^l{ScXw>PYu34^bs&U8z6&AzGKJD`ozCh_OL+CAq~z ztZP(PE(TeGo9=aGPSJ;WHq!ck86P5UuJ!Q`58%GBu57*b040ysm9Tve;D5cYL@s%N zx^L>r$k7kbEWWN}===a3v)7Y|+7HmfyPl-^Jis6R_2kd&5756sJ$d}?KKga3C${_d z(PvmaS$yn1y3ML5Z`a&MyLI)X;^g~ibg-WE?{y!+m+Q%0_RQBUqwzK?L(yQ^m`ciXNcJQ-9yOK5GmjI z9=ukDNKU_d`2KH*eDS=8GiO8OY|>pUcoZTFUfe~8FCo(M%w3euP+#(Fxr@)9_2uHs zyZE<4efev^T?`DaF9n+3Ma7o&hOz2`z9JYsc4@`^k5#K308c`|=L5Y_r}z za|eeV*2lNpLATrW<>1Ua$o}5?`~i1xFsZ%_ZE^=~a)!zUzdJ}Q87jH+-@)?0P-&5L z8`T?z%KYcIalLD(oH=zH-G_(DmyNd(KPyynSs8=r>q4b`-`mJ{FjQ2-+gN`oR6=}j zqwMog3G=v(-QPo{PTVc{W(kvk$G5PjP?&f-ZlPk8Fv+;?7Piz5ljoCe!K+P}?CEg} z3;T!3sE}L8Feyyz1 zKysKA8+{X3ayF3d9d4pjsRmL(ZemPe1KI3-6F0*fNd8PW;oY@?OnQF!`3HUa&^CsZezp6t?qTqSP(9$Wv*k# zrf~U~^*XK`4VSB*uHnPAaM^P08q&QEmr?&-L;hdkQulwvy?1yORU18eQh*S86HvfV zM2hqdnfIj#(g}pnA)OFNf%JapQlu9t(m|S1rDqnsBVboVRQT)&id_`$o|6^C@4LU} z-aqd1+<9{H&MvcOW>4GuEo;rcBn^xAQNN^1(xJLR0u8<-J(~5=j8>OqVAnocyYeL& zF|?1K{r#eZ$M@05YZoPQQXl>O$VG`*(nqJRx+tTz_R-?*i!#{mqtn7JO7FM&=%1Y~ zihj{YV`^WNCV%wNOTHJSTB*L;;L8hAv}Rv*pS>X8x9qELZn+?Db?>VcW?hgyBl>Fp zaTjF%_`dpL?+Y?^YG2*o=z?@!)>p5Wz95xf>#O(go|kWq_SN!lotFde^wnB>&dZdq z`fB|}=cV_3BU8>xxibBy?ewq__PHMi}PoJ%RPELPi^8Y?7 z(f9jl^o_IPQzl6Nz*$*cD@doVIV-JN2dUr0vvQ$Fkm-lBGJIr^{@L-Yd^0{sV``q2 zl&L{_$?L5A^>UClxOqk9Af4Ui zjC@zJzaFW5Mn(qo*IPbkbiMSdglz#wZ~7& zx8@DoxbB3LiCKOvP;gSEtyC#2?#VD0?J zacQ_RSjT^OT$=3&)@28dOUvWIdSI!M?*{ADRFnTzuzo)9xHR}PSify?TmniB)Z68c zOND@e`qhue#Jj~ny>|7O-0eD0PwzY?9}XF)Tjw4#di;SpJ^q-i%^RpAdLNUC3kGU~ zhR0;Y#)0}n@nh2Jz(C#k^-=M^Fi>O89+gk757f%99+lVb4%A~)k4n0Ch(<&nm5!A{ z^si1wrAWOHofmLa&bANHryfG4_X*K8pFlc=nRGtnkE9S?umZAUT8KW(fP^j!(b0n; zrM8FY=~j?~c8FH52no9yq6znG@x2wI2d>((>6Z}wV}~uB{RU~vIktTA zLAt1iEyX$x(u2?1vTVR0eZPn;&qNQ>+qd#%NBSVWe>`7W%^IXWYxCvcD@Nw!OPig8 z^snLh^2YH&dZ%5!G&BeJ5^!>`HXC+WV&5CA2ihE#U0)5>R+SFRPk#*7*X|vX7A1#h^{a;@vBnUc z_WB{&(sYP^HS3Uk(s_t>9&<>_gbdLoT@Q)G4AIYP9g^70A^NQAkSv%zM58}BDEn6p z(N_*1ln-_e(Tgu1l%J0e(VtTeN||?u=o14D$}?XM(WXrfO1s~OXqS=)jX&d14f^JQ zgj5@Nr$;PCOu^2MjfKi31WHHB@W2KOkXgL)EwP0U0u5sDAp> ze(AkpsP4VGU#!=Ls{8f*(f~uX>#Y4!@v5m8vtRCiKGfJR_8ULPp&A#kUr=P2R{DFN ztf)Lp4}P>ylIjoB;Qjlgdxv5A)xv#Jwa+k3P24A6j~b@;d+n1wy?v53d6@p> zyHBje!!-KyH{`*lVS2@WLk=GprY%;yAt~pF>AbWzr2fal^os#+$o1R9v}KbwWcCBI zeTg@ub=l#X|J7c(QFFNddUCH!ZZTZzuiY!PyAIcooV{{v&~VKfvR8(V8LrD(?v)=h zhwIL=rrzw~dhGTdszMX5qqS;t>L<@?H<|k z^Ke~IagWq0IzlJ>uv?Z@9-+N1?UoYtM`-meyCtjr2>oWtZuzp;2z@SOJcBVi+Tc$J;<&4iKq`cFHg(v*?<+vOb+xOk*?*tSE$HjUJbX**=n{*k&PY=^8m zJ5q0S*dYf#9I3@B?=be!ky`)W>vH4Ik^20bugmQcqjcz&*X6frqcmp9>++z{C`}yo zx_GOR?OqqJpivrI(d37X(vf#xlV2x{(jFIHlkX;v(k7c;lk1B{X_<+y$%T!h^s8a7 z$s7Ad>7iDy$%-?hbXwWhB=>_++Vi{ZGUDq|>UUDORU@`bKIdiH+7qIpC79J zLEGfP+EAU?V4LjT9jbSIw@KKEP#yf~Rw?;Ts2)1BRo=K2s+AURl_5WeYHY$*`Q0~6 z4|d-wODct_tM*oDTsKTR{k=s_whq&r54K3i3t_rz_ZGP|I81NM-Xig1!nDZfE%H-F znAYvMMbc)5X~!qG$S=#obl}gMW&E}<4ZpluzCIkLW43IT5f_b|yjd=N9HtQ?HcQ*v zVLGVwW?A=Fn06_=W4tP7 zMult7hObJ+L{qQGs}kxC*Hbq($*c3iHT~cw`DRVH)>*ho>g@{Gi{my))Uj|K*L9P; zay49ipWY-_KMU7ozi$-RkKy{v+Z&~kSA@Q{eWQewi_qt$ZIrB<5&G(=jq*yf2z|2c zMmf|eLSHPmQQqkvp?ALBAYX?^Xune%kCDLy$u|4!Q=6&6Nlub>U`+7ZR+Y#Dj-+C#1GeRfKT`%7EB6NAodil{SQjc_8FQ1f) z)DNnzmoqgZ_4d7WvaMO9-oLm`W_5~G-%aZzrhlXs&0A;iFe24w@H&Gh6sdnSStnmk zjMQ)Z*2&)ak^1)MYbAGWr0zewRyyyB)J2Qditn*V9UHe+PF#u94qewu&ZnlG8fy)% zP^4b`b&Y)SAW~;uStE-}M`@=mYeZ^9=}!|)exoQ|Gjxs2u%fhU^EL8ppD6vpe~p|N z5v6&zR?D!sC@r7ATE5RV^%k#|+}TlDH-5DgUm2yFyRMe`+oH5qjnz`|aFo9M>nd4t zK1z#TStaE@iqgc*t7PWaQTmp9l|1+@N*fPZB?-l%b!yX9^6?YV`kvn^dA@G6KK=PC zvZYnDMjm=aig%6H^$T8+(F3FPTI?%wEHYY4c78=FB}Z%9Cr$q3Xbru$Qr=h)t?mme z9Q+YU(Z@;{JEp`$bgk{;&QZ}Y_L-P`XpM*F52nRI2e z9&;~~j2okMf8%9o_+*SO+xN1Rt{iM;z;j2;MH zBH2a9=w}Ut;vtpq%_bTB8VjXe zy;zO;Wr4iZI##P*S|Hb+kJZ!b7f7ApSRI$SK*om0YRRAl@>*i7ZmzpPzRitQ>+ksn zCn;9nd}qE4TM?^+x6PNAw#4f7iSrF!T&xZsJYQ~|iq-cT&6ncu#A*-U`O@(7SUq@c zo^-z(t2KAelkmS|b?S@rB)!B~y*YB8%&0n6JG7i9OP(F8bN%PZ>Q-a*GhAv~Z z_5maNkJacob7gJlSY01ESC+?*)obnM%AD-6TC(h1$(=b?+kQDm#=bmOL-XgzfK6j{ z(!x2?dhb|WHD-=HaeS=ql{s?n@>o4xagLn7K31=O`;x5scC3DI>?Mi&-N>acN!z01 z^qshu81#?LnQ z@i?v4ZMHl}9;dgTnk^eAjne}^&XR8P#%b=^S@NG(#;LVxmgH_5r@tr7k_rdM>FeER z$;Q*;bX1L5((IjaTKwmka`>}xy5syz(L3X`@0yu%?EX0YCS|74v&N~r=Si__NYUNm+KQ!njBxx6(_zwY&-R5}o+?Q6a$gHOfj^k1jT;7br-j35=Y15_EA8|Ul*K~;}8n62TrpxRK@p|)@X|gLIUi~jlldFy5 z^|`gv%8Qt61X&8XLg?|Z8pSfUiGQcXji<(-=c7v9k13aQ{=bz*UL{%krjW(>zcchCD}hg$DNuiFH}y@=F2CW`2Pg`IexO-YMP+CJ5QGF zR)WS>o-7GH6SUgxNz!<5f?hZ_NxqIu(BvhPWX<>ltvq&;49HE;eKJX0vl6slg-Nn) zX@dUetBFSco}elD6Xi#vaD6y`qRh=t&}q>V<=OKITD1K{Ir3hDPA)xBdfiOWpH92w zgF6ZOVS-yi?Yoc!ImnA{_67|k+nX>qJqBdHaDQ~}-s1e;WrPQ@Vo%=(Ebonw-cP-11 z)O(3~u49I*e~_pje4Q>A{m1L|`RVe*6XW&6w&_x?_ISPcS(-FzGG6!2NHc!$<8@Kf zG#T>3cpdX$s>B43*H#l#B`I{g{{C#LWR4rJyRW23cKUb?PfwA|DdV-+(@eF9*Ihlau>&I{gO%YE?L- zcGv{jaA&**dQUKTG~;#J*74G%=mb3-G+s)TpP=`DOO&^(Ptba65@k{S3EI0`q6D>? zpfTSkh+n4(nz=YZ@_SFvNgWbo+>i-6@n*bKj+&rpGvmchoS>0S<0UM6g1+!UoIIF5 zL2Ks4$+CqL^rt#;(rEPrJ#ulJVCw|UN*ZVEi4(MG)p7Fnu?hOg(XleRrBO(drnVR@>0wE_@uO(5$0g}SceFfA zOVV$iiI%|0N&4Vol%&o{QvakV~rK?2AwGBz?he#>9GfDr9jFd))lk`^cNC`Tf zq^EX9NW#@5T^SM~Gd@nzvG>De^_NN7bX~aY{4q)IbPJdKzmjyr?Jzl2ELr<443l%^ zll5MkFgaU2S?7EbYV;V%`t+1gIn*Lqx7G`l?UJkwE{~FBJ(6{O@+g@!Fj>o29VMef zlQk0~rQ6tK{V;N*)Jjd(#>Gd+8*jNyYb*^}q*1<`zrO6 z>6=nD_)rfSyEE1JDff_Ghf+1&)kEr@Ox3?PbeF#`rE1O#-R0{0sru8mFUac8QZ-`k z3lj6KIgVy87+lR%t^Zy(x&3#lPR{5iTZ*OW+fQ|q&~j<|)X}a|{;4z_5z$qS)k)K( zMY_t^#%X$P%kxsEZJOTe^}Outl%|#Lc9CAa(zMyaE^>2Vn(K zhGch^ITO+}xJG9wpPi=Nk9U$qQ`59fR3|AjH%)64>m<`(PSd})c9cKXrs;dVJ4(#9 zG~IMp4X$OHCN5NIZKr9|Rw_%+r0I7bh}^r9rmM3=dVZ9qJ*$hnax+cu9JS=z@6vR3 zge5J1Nz_VU*Y>00ARJE`11UE@Z!lP1H`bH7Y%mU7^7x*l)eQs#b;uA8p6kg(6vb#h({Y4lCH z4hd)>zy6r6&z@*5hyP61yOGT$(APjJ;UhRn@ab( z89L#mrt)Ls3@zKZsVr`jpmhQ6Egoc!@phSsm~oQz$Pq3K5( z%KNJ_^k`T^v0lwkFYku3c1MPG*w8>8?9b4|=Nri2qZuY1qQ1O#HbYNMuP=XH$@RWtRAtIx<&wKDbeglD8}gG^mh{uv2so~cQD>qun#Ox1yPB&l12Wa!y0%OnmZ>d1s3mz3nfh6JElC}lsV`QkC1a8@wceqcGAJuk zPYkUoIyqAZ{}~{4W|{r12oT?enHt|AKt5fbsdqkpTK28W)Ui2F%Zpnx_0wuk%fQ{4 z+Rv^b)emLr!I3rOvtyb1)Pw4>=3J&`tgbG@u4WpmO?4^rVWtLrT1}39YPNS*llZSP zb?4L7q~cxE?$M{@z^|G5Y}iv0@*q=(x}K7|MY44I+9zd7sVsfH1siagUIOP>g@BCFbGX;rT(Qm%8BR$fH zw?SFz`uqtA8j_{ACq5y&L$mblfG4C>OqT9FR!O20vUE;ZB{`6qr4g=5QY1G^o2{*A z;sUeuzE+e)v$OQ*rxoO#g;|>Gt{|mXWNE9XD@fOMS^5>qOWKw!T|BD1Y}lElfe*?V zeETf@WK}u2YiDVuRZdEu&eF1#ecBN(5-&y+Choz*iZ?=YKloG2%wjQfoO6rx*)+Y~? zl+snRHDORmx%+gs+P{>Li*>WL*pd>mp;5N>YFR?kT4w94cl_n~4%vD#$zMu!&eq?` z`ODkgv$gK-;)Zu9TZ4j%OP@j6nsV3A#OY@1qPc#uFEU$SZ{#NtW3%=6rDEbgAzQDG zD`xcE*?P^tnDoxe)=#$#p)@55CS~Gsn*3Z9u zV4Z!CtpRl&Sl&f)bWr%;R+|zzI(hY9)|hfRy7A-t*5b-JnqTF-xp& z**8bO4*c2bHZVumW&UJY!*aC${(Dx_upIsE-j7y|(K))f$&XgCxE!q)_k;D_gdE+o z<*s!hJx5!7amU(}o1@!n-m$W$+g6o%IePv5@2t-j=V+4(-&yNd z_MkIeK{ZH&)eGbM&XPUt4c(&(T`GUt77mbF_QMudHVexS}XM<>u%Lt-MH&ROPbF0zX4J{mdCz`eU9O+2 zzel`pm2Q%&Lsq|M^=z4|yFYr@n$#{=y(+zH?Uh{Z5%iArS(jX$Is0v^c#m8?e&#Lf zxxTsjqt{zjui#v*YF)LWhvaJ8j4M{w$XpHDd)b;Dk*i^M-n5p+uO8ui^tD|xfYuY1z!@LH~J2s>dt*p;ho zRvx$V_vPxT_l{Yqhs}AEJ!UmHnyY7f9<@F?nX57l*3@&k`ub7ZYVc;RR{AsFy6{%6 zrnStsV&2cyD+x!e2iJ17=GMd3{7-W=?$#lz#(#2kSM@{It6%5p?ZF4F2H%_hU3kFS z`lC7TOZ%kTW_Cr?kkvDf;zSe{G<=ZAt=ZxECHS3V4-8XHuhG?Gtbz_T_-6c=ARoP-K zdm&Hz57=z&?vww$4$jlp+itY}GdxdQC2g?22+h;| z+t*v4MdoSKFV+*DU<`V0*jd{9f&tfZROP(J8Zjp6&d!AmX zv&fpcGfyv%TxiwUYx-g70&C}f)6ZAtTkQ|$=>fm_)^R&eH+Gt5bv~Y_v$N(}M^EKx z{N6cMn{#>E^Y%;Dwu^aM(>Q-sxssv>wF(+umEPxCZC^F^!MtvpTGGu>MFWu89u-8Ac?Z}Rj+?P=Ci-{)!ch^f|)AM(_D z$rNkBPkFlX&B@lOU-Pta(aF|Nf0*rMl2z^RJnfo3(dy)K>*7$i74GBKg;#T}oT6@h zu~Uw!vpcS^w$d)XEcN>^)YtXrp)eBSzYoLk%FbhdgXxb@5LI$E!eck7(tMs=BF`st!&^-Xo_$@YQP z%5>9z+uB>VGTr(~)pl0h9JhwfY-2^|x%Jxbt*q4(-P(6dOY7~)ZawlrbIWU*TWh}1 z%zExcw@%#O#2PTutsgzp*h-r1)`m--v*yk*{p8!w+BDCthm-4D2Nt;X_nXgJrxv-j z>43V{r6q0??^?&Y^0HfBYFgWRbGci0t*L39S?Sg*r30)ZtK9lkZVhYO8n^y&yPCCR zom-2Hc*@G!;5K@-s@CvLMz*hFwb^X)w?1K&-fHSqu4H|>&1^Tlg7w;KZoT?TIV*LC zTi=K(Yqj0w)&=jBwtn61*0G&SSv&W-HE?$cD{7xCgM;0*`;>*8hBPI`Efk<~-jx5m@KCx$hPn4ea-cTi=V%4@|jXj=Sff zz$Kr$^{=}719yMs)@eR_1J8c$)?%OS4E*S(TPNqg7Wm~YxBj|pYv7&#nEN&L)xaOW zaO=hX8v^fs>DES#*9Lz5m0M@{uL`{WwYg8eTpoDo8*?9>TpGClTeqgJSrquncWynH zJwGt#wrOYZoWLR9yR}KnS%Ho3nDZ|CVxa4;Tj$@N68NT(ht5q5T>OK%KYC;b4*t>H zA6}_}mF}7L4krX&HgZVPn83+DxizanL}2ru&2_msJn*`audWCQob-$7hXMTpYyE2O z8~+}Gwvk&;bPf#u&8;i50t3G=a(eUDfl0rc{{6N|;2%bITVFpg=MT458&*5;Pa|)a zs~(vAr(5@*e|YSO5DRrWv{I*qsia8~L!w z%?@q;HrHv*dmUyNIluJz4(}OxDL21EwFl-o{C;PLP$Qd;*wA5>kwY#n?eLzF+3ja_ zDE`po2WNL^Yh+lnhz=1(&M4EP!;404`Mybq%|;%-_(X>jMs5wh-~J;b&y+de{#zqI zzPPmguSULCrbqh+Mt)T0d^?wGqDD2iQjh6FEI-Wphq?V>ws)BAAL0IvaQ{bmJV$tZ zM|iwPc>G6rK1XYJ&A4k|fN7!FS*ndaZpZV^On!&FQ3n2KA+EgKCk(Fe)H=T zJkR-jzVrFK=kxi`=ldX^?}vQ8FY@{R$mjbcpYNA^zHjpR{>kV2D4*}Ae7>*p`Tol1 z`z)XDw|u_u^7;PD=ld|9??;>OOPlXco9|Pb?^m1eTbu7+o9|ciLb);u}U~{}+bNpa)JYjQuVRO7;bNpd*JYsWvVspG=bNpg+JY#=odB!(3 z$2&I1KQ_lhHpfRc$4fTHPd3L>Hpf>s$6GeXUpB{MHpgc+$7?pnZ#KtsHph21$9p!% ze>TU1HphoH$BQ<{k2c4XHpiDX$D20CpEk#%Hpizn$E!BSuQtcCHpjO%$GbMizc$Ci zHpj;{$ICXy&o;-?HpkaC$J;i?-!{kNHpk~S$Llu7?>5KtHplli$NM(N|2F3XHs=R6 z=Lso$Hs=>M=NmTXA2#PBHs>cc=PNenFE-~hHs?1s=Q}p%KQ`w>Hs?n+=Sw!{ zPd4XMHs@D1=UX=CUpD7sHs@zH=W90SZ#L(1Hs^OX=X*Bie>UfXHs^;n=ZiMyk2dF% zHs_Z%=bJX?pEl>CHs_}{=c_j7uQuniHs`lC=esuNzc%N?Hs{AS=gT(d&o<}NHs{wi z=i4^t-!|vtHs|Ly=j%4-?>6W2Hs|*?=leG2|2FjjHuVEG^#wNd2R8KyHuVcO^$j-l z4>t7?HuV!W^%XYt7dG`7HuW1e^&K|#A2#(NHuWPm^(8j-CpPsdHuWnu^({8_FE;ft zHuW<$^))v2H#YS-HuXC;^*uKAKQ{G2HuXa`^+h)IM>h3IHuXz3^-VVQPd4>YHuY0B z^;I_YS2p!oHuYOJ^<6ggUpDn&HuYmR^<_5oXEya|HuY;Z^=&rwZ#MODHuZBh^>sG& zcQ*BTHuZZp^?f$=e>U}jHuZxx^@TR|hc@+zHuZ}(^^G?5k2dv@HuaOBz7o`5g8EEQ zzX|F)LH#GF4+Zt3puQB;pMv^SP`?W5TS5IRsE-Bpv!K2f)Zc>oTu{FY>U%-`FQ^X& z^~0dP7}Otw`eabQ4Cia?cKWGmC?E|2_0JI-~_5{$r0NNWs`vYi? z0PPc?y#lmffc6Z~z5&`hK>G)14*~5XpuGgNpMdrh(7poNTR{5@XpaHyGoZZ&wBLaC z9MHZ4+Iv9z4`>ep?L(lw2(%x8_9W201lpTG`x9u70_{_vy$ZBnf%YuWz6IL5K>HVH z4+HIEpuG&VpMmx?(7p!R+d%spXpaN!bD+HrwBLdDJkY)e+WSEJA7~E*?Sr7b5VRkH z_C(OW2-+J#`y*(N1nrZcy%Mxvg7!?%z6shpLHj3Y4+ZU`puH5dpMv&O(7p=VTS5CP zXpaT$v!J~ewBLgET+qG?+IvC!FK7=2?ZcqG7_=XQ_GHk$4BDGP`!i^d2JO?Jy&AM% zgZ6CDz75*DLHjpo4+rhzpuHTlpM&;v(7q1Z+d=y~XpaZ&^Ps&RwBLjFe9*oR+WSHK zKj;qt`Uimi0-*l@=uZIp7l8f-p#K5rj{y27fc^@g{{raG0Qxt8{tlr31LzL{`bU8N z5}^MC=uZLqSAhN&p#KHvj{*8;fc_ew{|4yK0s41<{vM$J2j~w1`iFr2BB1{W=uZOr zmw^5zp#KTzj{^Fqfc`3={|e~O0{XXr{w|>Z3+N96`p1C&GNAtq=uZRs*MR;up#Kf% zj|2MWfc`q5{|@NS1N!%X{yw1p59kjB`UipjLZJT;=uZUt7lHmpp#Kr*j|BQBf&NOM z{}SlW1o}6D{!XC(6X*{G`bUBOQlS47=uZXuSAqUkp#K%LgI{*IvkBj^ta`bUEPlA!-2=uZjySAzbQ zp#LT4j|uu`g8rJI|0d|q3Ho<}{+^)!C+H6f`iFx4qM-jM=uZmzmxBJLp#Lf8j|%#y zg8r(Y|0?Lu3i`K#{;r_^E9egk`p1I)vY`Jg=uZp!*Mk1Gp#LrCj|=+eg8sUo|1Rjy z3;Oqh{=T69FX#^p`Uivl!l3^!=uZs#7lZ!Bp#L%Gj|}=JgZ|2(|1#*$4Ei^N{?4HP zGw2Tu`bUHQ(xCq|=uZv$SA+i6p#L@Kj}7`~gZ|o}|2F8)4f=P3{@$SfH|P%z`iF!5 z;-LRH=uZy%mxKQ1p#M4Oj}H2$gZ}EE|2pW;4*Iu){_ddvJLnG&`p1L*@}U1b=uZ#& z*Mt7{p#MGSj}Q9igZ}!U|32u?5Bm3m{{Eo-z1 z@h)Ke3m6Xr#>as1GGP1+7*7Mn*MRXhVEhdjj|0Z%fblwD{0aWd=nV&1javs@larV6c{fB z#!rFqRA77+7;go}UxD#hV0;!BuLZ_$f$>~md>0t+1;&4Y@nB$l7#J@G#*cyVWMF(5 z7;gr~pMmjcV0;=FuLj1iK?>s8!1y*W-VKa@1LNVq_&6|L4ve1z<4C z_*gJr7L1<-<7vV8S}@)grAK+=Fi z_+T(z7>pkV;YB1g!jK2osvBCIkFkTys-v;Bk!T4@4-W!bn2IIlO_;4^@9E=|aqC1@gzWe2@r1r#Ge51C_sD)5U&EnuK@8ZKzs`j?*hcX0P!$Dd<+mT z1H{h&@iahu4G?bw#NRM_ZVw&@h|dAyb%6LCAf5+^?*Za{fcPIE9temJ0^)^$_#q&k z2#7BN;*Eg#BOo3Lh))9Im4NsqAf5?`Zvx_-fcPgM9twz$0^+5B_$eTs3W%=);;n%A zDVh|dDzwSf37Af5||?*ihzfcP&U9t?;N1LDPi_%R@!jL~Cw@MS=}84!O4#G?W6 zX+XRh5Wfb*vjOpKK)f3e{|3av0r7D_yc`fe2gK6>@pVAF9T0y9#Nz?+c|g1#5Wfe+ z^8xXFK)fFi{|Cea0`Y-BydV%i2*eWt@r6LVArODaj1N6{L?Av9h*t#S7lC+2AifcZ zcLd@efp|zDJ`#wR1mY)wcuF9?5{S11;xB=COdviJh}Q(-H-UIgAifib_XOfUfp}0L zJ`{)-1>#46cv2v~6o@wk;!lBiR3JVTh*t&TSAlp|AifodcLm~Kfp}OTJ{E|V1>$Fc zcv>L77Kpb6;%|X?Tp&Idh}Q+;cY%0bAifuf_XXmAfp}mbJ{X7>2I7Z-cw!*F7>G9p z;*WuNWFS5nh*t*Umw|X@Aif!hcLw60fp};jJ{pLZ2I8lIcxoWN8i=fp~BrJ{*V_2ja(pcyb`V9Edju;?IG2bRa$*h*t;V*MWF; zAif=lcL(C%fp~ZzJ|2jd2jb^}czPhd9*DOG;_rcYd>}p_h}Q?=_knnRAif`n_Xpzt zfp~x*J|Kt}2;v8Vc!D6lAc!{z;tzs&gdjd4h*t>W7lL?(Aig1pcL?Gif_R7^J|c*h z2;wJ#c#0stB8ayL;xB@Dj37QEh}Q_>H-dPMAig7r_Xy%Yf_RW1J|u`23F1eBc#8l3F2phc$y%-CWyBQ;%|a@ zoFG0Yh}Q|?cY=7HX8iBL_XP1iLHth;4-~`)1@S^b{7?{26vP(=@kT-XQ4o(5#3u#u zN&_~vmpK~h(`kLe@#R6hc@Tdd#G?oC=|Q}D5WgP8vp04N557H!cMsy< zgLwELK0b(-58~&8c={l|K8Uw(?1>)yeGrcy#ODX``a%4D5YHdP_XqL*LHvJ^4*=u` z0Qmwy{s53q0OS_{`36A#0g#UXkk0_*Hvst#K>h=e4*}#y0QnL?{sfRu z0pwQz`4&L_1(1&ci1i4+7+e0Qn+7{s@py0_2wf`6fXA z36PHhiDm4+G@K0QoXN{tS>$1LW5L`8GiQ4UmrmiPq4+P`~0r^5e{t%E)1mqV1`9?tg5s;4ribu4+Z2$0r^ru{uGc;1>{!&`Bp&w6_Aewiny z4+i9i0r_G;{uq!?2IQ9k`DQ@=8IX?#w*mQXK>iz$4+rGO0r_%3 z{v41`2jtfQ`F2459gvR)i<)4+!K30{MbK{veP~2;>(6 z`G!FLA&`#<j0;4+-Q)0{N0a{v?o33FKD-`IbQbC6JE^ zjC?4+`Xm0{Nmq{wR=73gnjp`KCbrDUgo}jO`4-4eS0{OB){w$DB3*^@V`L=NVx`%%YEe}Q~pAU_z$7Y6c&fqY_ERlqL>@{NJ~V;~pIb0Gg5$VUhA(}8?-Ab%amX9x1zq4i1+-yO(*2lC;8{CFT= z9>|{u^67#6dLZ8($iD~j@qzq&AYUKI-v{#ff&6|T-yg{T2l4@e{D2@|AjlsG@(F_c zf*{`@$Ug}35rX`LAYUQKUkLIUg8YUc-yz6kna=Z{{;C!L4Ht>FBIet1^Glleo^z@DDUu%g8ZW(A1TOB3i6eL{G}kD zsnO$m_)S5+Q;`1@&wl$R7>zNrU{-Am22| zKMnFxgZ$JWUp2^I4f0uo{MI1fwRx^R{MR5KHpq_+@@0ek*&v@b$gd6ZZG-&VARjl# z&kgc*gZ$kfpEtrGzH?M9;6DfX&_RB5kS`tNPY3zbL4I|RZyn@c2l?1Res++r9prBZ`P@N% zcaZNL2@Q7@4K|ZgNJB#)1~8$EPLLi zr;NO_)1{>!KE$P^F70dNwp^D^Gjc|hOLrSNx|d7eHS+o9F1>AJt*S1)Z>0LTT;48c z@%1X}<#KsFYf@=u<-ZqiucEa~U7!A@z`H>Q=f9WVN=JAX`O0kLbKm^)ZavVGQ|vQG z_!cSUY~kzdA}HRIQ|z)M{EEEnRQ4-Y)(BtUBC!c6rgpI(&2EjD>y&x69M+<%HwX^CHir;^M6lv8IZoACAD=p5Y3Jes2Z zPdKH^m@MZ1z$snMZTa#~^=jsFRdD+DM^m}te6#ZKX;&pD;nl_4xslAz<$A(7 z=*l~s!w4>0wIF*Uv#WS*GKD_v{XD1YRn<9*s?Kdu)wvlw|IB9Pyq+mtp@dKAr%Hzu zb#`0U+>G9JTqR0~$uyfk;qocnzC?!-Jt~;Ho%w!d_r6{wN|^j2UM9b2JyWS#DbwGq zUBs#FSH`sBtQ4>CSY7{81r3@iZT-#lXzZmWJ$oqfY{?!K%6XOd>R9yU&Ly2@OBQkY z_&NLNQNi0BRVkBn4u#3mk0nh*Wm^8LwCv2uUgq4IRd5=D6A0tuL{jgiMOli8b`MGR1SIGh#+P=a!5gT;UPG+O^#=&X8t>U=1&UPjy2^+&`cqz0rUCdMTPgeS!ZM8`)&M@2{@#VnTGI=o2h{aRaYXIfKIJAq^Gw5foqdKi_9@lasTmUB(=?!A zGoKPYeMU9*iD~TfWI!#SsK!3kjRM}^awV4@6z2hzO!eS z1H&WYqFtlo62ntmsR_xkF$vL80g+?ElXyto!Xr}>lO7#UXV3ANL+Krz&^fcYD=sl1 zCg9O_&IdbrOkz^Xzq1Oe|8pP%y9N&o?bfMB?~nmqT`%+v3Fs2wxyGKmp;_~$Z35~g zMaM;lCr8&07;X-~N#QNisAXuIMiJ(|iyRY>6rC2EZ0@>%X6;(GXxeJz;}`p}-ib;~ zbxyEL`w?CG1osFo_#YY^osv49InM_Nh4zk(7!jP9niLs5;)O03*kE zJ3roh!M)@f-^En>=d3yncp;=u*S-UJMGM>br&pccDZEGn9$h6*5B_gAnw$B5A28>^ z_@5j4-?z>`$J4h{-yVItxq?Hxbn7|%X&6@v_sDd zuhru>p>rVrdms0GA*6RF^ENlvs(nB`=MEa^dA*poQGhv;fUbPS1Oz1|Mn)$mCnhD= z|Nr6^>*Tz5!=0Cs%d4JQEz-r@>(LpF`m}Hr^)J?^xOaKqie8nxD*IINs_ONmR}Jr4 z&im4Noj){-`B3JRE?LS|#iR=t=XKkublEAs(|o3T&o#9hCuhc|ghv>el2jna6t0;) zrMMbLg{OqO8b>52yBeE^q_LCP_LvkuEvpx@$u2-k~cONp>cRhN>Xe@YRbP` z8Erle&VcX#ebN@Hun2YMM-^p64BII-)~E^-?pZ4XTQbFuW-L%X1#D5v+BC<rL6??fqribFQaze9rz0k8h7zceZJ2e$G8zpk58ZkylZ^+uXG zoijNtT%0oJcgFn8=Hm;b)4mz`4z4^Y2T7wo_o?+cNXXPoaKGW&KIU!XT;G3|qAuq>A*y7`==xSopP9IM-zw)MkIz3kI zT(|!n?wFx-ofKD{sK>tNgYGy4f++M^0H z={%;LVT5xW8z}cs9;b8^V@~;}ly@lqrYvb5C#Sp?Wh=@~jx6GGb*1d#NOP->pbU4U z*)ERh2~6iOJ&Ea;m|np2TFULr-{nZNA4ebO$a^e*;7D_y_?gGs*-s@$nsfluru#hg zeJMTnkJ;Y2pPhCBDCHj?xZ(RzD~KD@)+eQ%8Qhq`^#+iIn!TI-lqJ4(%ZSdrk?rKd1Pry z^Gf!lt5Q~{e1@_2PIm`d^ zT65=F@D%%cjW8YK_0XhVd%TCZt*rtd7LF+X3&7U0p)zh%-z zSDTcp=rvQrUGy2VnpbqR`JZd7C60zZ$ecuW(N3n+Xz06|gwfEiGUdejf{T1DwV4c;>pioX#s{l;ho<6=x~!oQqcv z QTGS1dsy?$qD8RvE6)yHY&4=2md*EudfU+0L*I@^>shg2@htW zmsbf#>F=r0w6I1KS9zx$-+@*^jQ}G&HJsD(w9&>@{yDSm8xmSj!?{478cqj$YFu%Z zcZ?{$gPhm9*-KPm4ab&K!8witUas;dOu~2Y#)2x-3#%M1ta8*;$#tp>am+iWm92$U zJ}InHte6?7I0rlQ+kz_2=fQI*W#-{o>XiAHnohym8 zf&yo4OhJJo;vN+^YZ(Ovj&MeN1zR|4GYSeE@zSFLXKh(Qfg@gdRN$<=T2SDKZI23^ zwKob19C7ebfwOk1puiEg9~GFDM@w6?Mzw!Ov+C^{U)GV%Nf&YK2(`;PtG&(7)N+Jp z6kuu<_5f=+T@X=F%MngDIBgYn2W!Qd?8ybS9O0b0Q>(BGSnDN|J-48iBb0D9QjqP4G3MvgcI4QCY)51;+mX&o!8GEC8O(O%tb%MuEMvAK zR}^GB!nxp1+m75)knM9dXM1{xA0413s#%TOU3%XOc`p2%$<16B3kW zNC-^?1cVWg5}JS@gr)%z0)(c>4q^$m7pyc5RzMMHHl&HDG!YOLP!Un-DiI}<{yon= z>dmiylK-rwi{cXx8mv)0;cuU*bQWzJrEA8Hdnw8R9q0>uCwYGd!zl*zj1plYQ?XZkUV|JV@Czcm=+A6h6gz*4pqtO1KsLu0zN{#KK&lQMJDs9^qJs9u&FEVQJQ)rFF!46m)OVmAT9~$zKc?mFmTK zlXIE8lA7s0_YWU!iNsYqc&vrI9rQ)~zc;>8svU#JOa6(2D}1MkyO{s&Wplfs1g)E* zVZ@3apOhKO>d^+ne`jnZ_y%j=hMT}x0cM14zRIrlnoj zptzo(gY7k`W*B@IMth;yYzLeYf&IWC#0crF@Zv@sX!6t?5gS8|2s}EM zX+Oqq#1^b~7Ya3r2_!I%+xys%JYB@bdFWkk%;XEvxAi~X(iUk9 zmj5TlOlp?0?lS6t-|3gxtz-!}W)d7seZ&Kj-;aT?rv`#)u%`urse4K=Us2~D=)XJy zfxt11;J`7G;J`5u4+Lx@UTZk!(F$k>+U;dCK=NbC@OPErA1}kdT83wTv;*xOu^Axw zpUd!pF_%)e8UMfwZrYafN2%yPxtEuHF61-G-m6VX|D&N*?8o+jc~9ebn` zCsQO5=OoWlq8>*ABB|j-Bws*sys3%ACkwU_yiTx(U_Zf|1xE;`2~HEdTku}NhXfxJ zTqL+$@HN5pg6{}!75qSOkKjSUV}f~t7<$(Ayh89w!5)Gm1k(kT;J*Zy3N9z&p7yHX zHX^RkA4vQs!XFa;nDE~T|D*5~aM5GCCkgfwoGQ3b@Lj=Uf(~2+nJ!)s)hji=z$*yL z$9oD|X8wfTNWFKREJHd{EHwyL^yh%_WXXuX>ULR-h6NR55sE;?~bA-V0$om=V^R3_yg69P<2$miHDeth->G%9d zUv~Vbfy6fv)Z>uQYbE@3g4YZ766`BDSnw9XF@j?SGX!S{>V63ObA^9MQ1?s77YqNa zpdMg=e5LSf1>X?V{T1;$gx@2m`z_>O2>+$vNx`#%e7(+g)#IW-x`vVu7vwAj@>K-u z2*wIF6r|5P^_mOPPltR5!Ons=3icKpC^$rLq@W&xLHY^8PZpdh$QS9ff1lty!TEwu z2rd;|Cb(QskHaGUdg0#^+#<+#`Lw@VaG&63f_lIR@!tyngW!3=3xfLk?6&TOw8ubn z309K!=bfG7{d`VheADL5T3F+O*8Z=?50jFUTeQ@we?5NKnHLWn>gF06;964Cxcbb6 z-cjC=tnf6`d*7NXyl(Hfn4x3M$4YXGOG3QqY0=FcUecM~j@|~E>V08WA4)oUTc?(m zn2TnlhMs%R8Qm&0CmJvG5Bl88`uW^@Q@kU*pQZKlxi&p=Ix?DR2Ycs;wXc2dZK2*i z-c)V7zt8>fz20u#4&MGg*Q$>ZM{VjjL?g+2uQ$bexfr`#4ZSz`+>wK{y>8wRXw!y6 z@=JoGLn(=!?gk(Hicbkqe=7OaMLe^|Pec@khr!_v~c=@ygK3C>_ zYfSGI-Y9QWPDwMi%h0igZZX@|@7u<(+9t$kICj6gU37D+jm!m&yml+G4NA9CL$s1r zkAF%l8C%&-^VWnt?s_onnNjYL`BC1`$IQ%I-f84@#PK+UEDT+o|2!ToL!`kiGb zIL1Ea|DAs4T;f{j@b|keF|H>U9SB_%vM_A1BQDTZA-JgE@`B)U{D!@w9(G-DAxWex zC^%iN2D}bALK6Vyo4nRE>I4N0U_VW8hU7wKI;hlgh?a!yAh<#*Gera=QZlq8Y#qU^ zuVEM*&ql();P@<>c7^RCINY2xhT-t`7Sx835I!eiRJ$Q;gt~b1596qIIY{+DGDfvi zXg6EJeHV48~Dy{Tzx>?T}gIH@L5cR)m93#g4`xF>0juU|&YH z%3(;m35h0%DVJ_Iu4ei{*dnK6XR-H!Du27-XgU_eE;1R@`x=f!7TSb0u-$~M2Q~^% z_l6^hhB`7fy`$l1Ms9-UIvI{+avTsZKLZZpj^;G9!D3-ZvuvjFGdkI^g%)ea)<=oU zXC#d<94(lZ_hPUkg`G<_J<)KqWF&8l<>M0?%C_Ns`sn#*cb((R9%-KCz{a_iG*Yu*rZ>o>;90H0qbp%lWk&(O=Q@_R3VJ2t5A9d z{@|#9DmmKYR$h&R{MUl3_CAQ)NO0u-aS&I00pc);;~?rl`HFKO5=mSFaXktC3K&D8 z9Ekf!(C=#v2@i-PBpQR@lfe~y?dKuU5kxYH9w7RV7zkoCiBu5tNsI;Y3W>=eJ_lh` zcko%-(ba(pz^@Ja3lKX##jXYpPdDAM>);Yo1IMVlgKgUnTuptTEdELIQ;^beqoWn# z_kgd()63CQ+c^)uHXAAtG6qL~$2i#6jZ!a6n&~DGb=Yvu1wCT;+@qW79!PalZ6d*@ z`h*0V>I4Zkl?xA4x~bwxu&H{JU{lQ?!KQkO1eUyv{f|9c>J(yaV4@R#O#t=89EkP=#2 zr5@YaK})t3*Mj~}IBW|zS$J8B)AMr8K5mDj2&(aV#{&@0R@OUcnrPi{s{i{g9o77k z9dX^X=UIjY&$D!wo@W_uId4P+J8xK%EuXR`Tb3*By1}`ZGVfE*y@Y2*uwzHSQG>B` z?670;(>ppi6Hhrk12bS9myCdITnYkd@gpT*7jHlkFnzOB8LNdDN!qalGcqlr)LhI` zx|ouw%OtZ!Yf7HN){=~btz8FM^>qvg9aL_xp3z!I=Y+b%l!Fxg$euOI%6NjNlg3&R zPj-s5rkd6Z;?W=cErHpsZS|zq_@JqxxGLZ|;BNg}g10Zw@kITb*0{ShNPnmV3hoF5 zeH}IW5vXbTsQ48@pxn^yLl~;bn+UdUpKLJxz~3#H?n!8`$$^9vY^E{Yl}&=L7{Iu- z69p}Snc+9W6W=OPUqTd0W}7o4jrmtPYVvCKcOBr)5vgVlduYz5hx^;SrvzI6Tym~=Jr?OGV$RocyjzS zqn=;OE-;S6I9Qpg4PK@?(_9`zU8SQ_CIGCO4FRRYW$mQU9P1f0_rO+k8l_A!^AlQg z0QNe>VDG_(q7hg@%oU-z7c|+2U=?F9C>C>U6R_IG;rpbYXuGsYHK%%e3xU)&nQmNCy1A$edzEmEK4PBmqNhnJ7GrOTn57OL?Ae=jw@CGU1R8P}gT@0qx<>x9Adt2XO)S=m zRM&yA$FZRoYaTmlJf}r{2$ng2Z)U6|@^@A{L7=nR>3-i??c|8DAAn(yA;^k!;~*<# zx^a*dd9t=_So`1(j+=_^;6y%Kn8w{ZgLRF%;LxmuL~OXG_8_*l!~`az7^FW~sruNd zaNwD!4K{Qy!fZ|6L|}TJEq{0hNWLk=mO5Qug5;Y5(jTHgVNn2rZ8oqdKs2QP_3AKJ z=7B1v5P8+ZIg=6^=gKC{Dp-7=mom-Yt*mVWcR!kHX|-loq8A%Xcjb+XGzTSuI^ssC zTO$AIxx+8=_ivs?)3E8&lLT`C6Syl;gQdVxvI}DxL8oV#_{myz0Kqa9bb3;irwmH@ zDBu}QrVv;%hf%6j=~^`KF@RN#n?dOiNbA3?QDkZPPc@q4_zt=hA)<8a1e)R|MCxEC z2%Ly^I!h7~bl0$xBc`1E68*gu#PEI+WCfBxuu|qkgQwRb1^b%e6Jjd(1RXf?3^TPVtyCJPjbY z&K&76V?4d)){UKBCk~5M;9Zo%ytX@`DR<4aV1|~*kxu6BM(*lz7t5U)-d4kOD|xs_ zb5pbxtbReRmKM#_bPLkGxogN>eeT+DSC6|G?r!F;iC;FAl+I5VsufwCOql~WF6=1FdB~3_-#c~~3q@!&Ma|+hx@Jy{6J1wSO5?AD?o6)qn zIU^x1`Nq1jP%x)s;SMxbcdp+U*XnJi zJ!{sTUn34u4~`MTr)c%w$4@NlxJZy_THF!P3oJg9c|4cvoo%4 zfxMHFZ~L2hPpsdt6UuSrM9Fxw<5@GJtvRi&(}_9iQ;XuBe6AJ%lPSaB=YL;15M zB!c=FoKtTbBfbR~nZIMq!Y+N6gEt6#}n- zASVYVlSM23f8dFF`6WGAV!c+z-*G*)7i+nkbLmLEAd9#v+XvKg`wT3!VKo^Kx!-a0 z&sWp1mUanVQ{$hoY(^wb=U_k1c%I)9cnjzh6@PE|eeV0i9th0}ndf@Yd|CVtX{{cuK(V89A(a@z(O5m&a6Ph@4LN@v)0!5CpwqnSk=PDyE>o4 z8Jb(*-&>Cg|2zJr_G1Gxw;xXUxT0TWN{MQt^DG0+a#M$!8(TMQ!S!H&xtzT&&d z3jy<`*Pos5t7YunQZ?|F98vzfmV*wq*FV`XJdn{IeSvIyTR_`o0BJk|dnqI&*m3;L z5o|95_V`#zdlj+S_V$Ce(||O-hP@x{P8<}s7j&?_?_sYxWVBZqn{Dqa(6pC`jbS&G z+LW=!_*2+|^;|GCi3ubyj@t!nIGilH4pX6rto?yH3@#8hO@0ORvPei^`E-C%a6JlP zjAdm#SRcC{Y$N3B4~cjk#Gyw!*d#HiddA*Z%m0;ckE&s#y=ZLAGuYnJI7}0U%nr6a zo3}Ao{-5xF#o-MK{#Ma4`n#5n4?5wXLI2m%@jPP#;jh;K`D=gJfHmgFo)rjO1BAzj z?P&#afne&`V4g=H5KMS$^Elgqb{g0WkbH|Wd?)Zc2D~=Xzm~sq$@4y33GJ0CJg;?? z&_4XNZ3kV>-`xcLuCK#~>s7ag-#TLSXv5FkF?D=^nKE@GCvOEmxR$xw{?0sIPy>&r zx<$B9YCH->Ob~2IyuvU#5YdcXg=hK6&muyf*G=LwBJ@`Y&+7~M4~5?+{81v(e=q!b ziN7R#vBZa>y_mk9#5a<7-cOmnt?=o>^E%IR@SG+-EAg*L{M*9s5T4g7+CMD(3E|HY zk^WcV3niY{59;&0jlfRl553N!*I)F83cpzR7m3hYC%9AM4@tb8?@z*Cl6d+pGQUV7 z>RW{fI~@0*oc)XP1mT+?T@0K-2Z4`4`FLj1&lmrCy%=7voY?XFBtq42;>Lm7q2WYF zWO~YZ?IgAq>>}7hu#ey{!7+m41g8tm7Q9dJaY42V?LQ~DLQwmGLcT%xPXvz%{wP=| zNY4n`(SDggukZr|#|TaqoJkD9atnfUh`8K5F1SqaB_iy-F8n4z?MDfHF5kd(^h%-L z8R6+SLpgtx6SaRNFi!Ypf*l1@1i8cj_3se8OK>$2_CFTP6`X^cgfk3I0fO_0NdL6p zGQpLC>jd8w+#&d};OBzh2%Z+q5zH4fT~i}$1g{dL9|OyCjbH~N>d}>mn_LgU z6p0@tI7x6C5&Cn4zhC$T!apVabHcwugx%Fd^ye)i|48tV$iEi;q~OnjK0yci2Fo2G zSXr>PV12;^!B&DD1iK0L6&xZ+?+elxBukVb%SCH3J^8XUl=P`JF9s_xuWjvox ziF}?V>hl=*w(z?IKNjTmk9vm%j|+Y;ctP-2K{`fJKTNQKU}ZslJwQCKi`3(Fk=RVI zqhJ?7zItVRieOp4?Fk~+*AM8Gy?#6@@s9~E5`0FG{#UgBw%}I5_XQ6MelB=S@Pweg zt{^@Ar1;pPh@?nBw z1jh=d3uXw?NsReDAo!@@V}gqWpAqD$DAZpeX!~31`4Eur61l$qfv2Mx^-l@@CYUEk z*DGEZD+|^VtSfkxp!S-A9-XtOuh;wsdWG*U*hg@HAbq%~f4d-kg2+!3yj#$|KGW5U z@%p+9d{+491@-kA^4ElaQ*fi;`+^?{(qoMFz7qUS@RZo)X@g^%EM4t$g# z9nZ+e3hL`N_~ydX4UO?P2MsS1R zyMkK?N_|s@P{phH#uk*n6 z!gms+dmZBk299w6tY8DdCW6fcTMJ$%c)cK9{Fr{A;4s0Ff@1~m5X=yqA;^zVF#TLXx(JeA zB)ClQMZr~qYXsjCd{>Yzg-rj6;OBxz1X7>Kz1XhilJ^>ZEM`gsnhpXY!ciH{ew zpX-{F$GP5`2>WdXI}nksvmk#rQcpi8Ku_PF5nqLJye854Azr5k-+^-Ijh6T{BJ>0A z3-IB9iA_EJc}A@-zfNINGS<-WF#PpAqYkX>W#$<@w8p()ml3`oY`%L@m4#K8hCgGR zb5sjk*!%2`$R>4N?L%se>g+rh>FOR6^7!rht7KR78adJKk(lEV-OAnmVQ*a8AfJ0x z4b12{|1&UBO6KCXqFe=-=Frlvv{ z>G>#&oZbUIV@(R?f>^Vj%q0$Qb)DujpKF;DvyoCH#^JS6_VLflacLWvIkc2>j+~1_ z7KP^+*UziIJ~d=Pdg|9Gp}QSs61Cryp(1`DtW~4FqDvR8U!v0B=4;_I zKf27_W4`S?y7LPMzV^i*4_oLOJ9nNVt5ceLq47kS)=6|UR=>`AJ#49aVQkikc`u~t z7SS`2T6-;t-IlkU;#?-<+LKRe?F1^MdS+M3nEkh3b5xB zJ;2Am5Ny3_L{+hsdthQ=pmwPP`-?92Yvu<}2#x}R- z9J%>w2;Z@?EJwNTq^Xwf^;$XF2w@iZj@2Fj<{mxn=FD4nJDPaXJyt8>wJ>#_5)&?W zA=#&;G@)+J*}`|Mtg?o=Un9Fn(z@OElU*!jjdb(HDZXQ66+PPhEMu4IOr4m<6zXDQ zghVidXWWB9hdXYAiem*xjKt_Y*h(m01m9^pR?^bd*do}1j#pS@z6^|5O7>O8-cEK0 zt*j#ZFt&2buyeeoOR>NxH-y}3UE2k&$gzfF4e8ggmFL7@$6B`5w`8yIv;0M0zJTmH zn&AZL^3i^FHQB@1Io31n_hk7_&SLpCu6$oA>sU@(gPRc84K&3$%jK{1v;0Y1{w2sA zZ!mTMS-!@wSiYEp7y8w-9g0+>+}CiLmHpG*`}| zbz4Mg{b*hJDE%e2XkBxmb+s#K{b*fhp>>6$Eqz^Ep>>okR9Q<9wSy*F8aPp0H)Nf@=l!Jc6G7yg2$j$~^zCYQqeA~4FY$f&+iWnT} zdtCSdehWkn68s5Wg#=f#Z9sxwp}UsE)gXG2hy^hoL=_JVROO7D#o($=1;Jl(Rrzz8 znN@uRLZFCO_w%Q9M*p53u)Mm>%7r1mY9fm+R z6MwMiX5udk-Aw$cpquF^2{zM@B-l*6(&%R5W4~^uD|zjy<9GmjOlWkl?lC;rF}$1w zD5#ud?UNk30Rj<06wgDWuH!}OwRSjyVzjLf82!IFMae%|1`ErUn#+TCyup)^I917> zn}iEvWMBr7Jypq$MdL*Itzrs}H5sWwU@j1T4+Lfc;lx6WJ&_4%D+Nsp($kpmlG&Pf zRK=PWgzv>!e6`^DL01IL52_wCABb~@YS@bCX4aIfTECm-gjd+Gikj8&mmMu)O&^M} zrVrIE9ixww{C1J~L?}L<3GR+3@-6}Y^8KP_K_vkE%L$Ax>qyQ!4*Yuw63tHG4+)^) zI89(Q-N;LSC9Z*1=tr;>0uJGckn)EOED$g8{-)Y%tK3_`D@1tkh)RjQ~CcL7DKrC1nd9w4?+p z1HW5z6NtPzwm*S&fV;OVn?w{g%v6F{2R49J>wbh^v7s!TiI&km1Zj9`=s>Gh1N9S$ zo{Yj$IShX>mVvd5@XnxZ;-M)o3hMk4QIzw34`H08Lts{Vat{gKOsv@wq?oJ27znvP)C7eNO`vg< zPfuIuYl#U=L@`Jms$ky|8#)F-QuQFRr$9_#=2$Daid_g;=n*IaHFRLvsS-4e$QA|X zY0H8-Oh8o1*hAV_Up_ju*0p67bYOzNZYELIQ~RC(gJVb7f(-@gOx%VIV#0ZB6cc$^ zqqO^fM8lW`oiDi>2Ik=L9DNxZk`WGKL$a>K&n+?GOHKBru?yHD^=vg5`^|tUN`5OP zbp~aSikJ*+Xng{!ug_u<&2&5ThggSH?0F=D+LB4EhV!4InGmr?m<0t&2bR_n`A^Y5 zYEwyJq=Fca4W}GoGB(rro2T3{t$g=3KpBqihYBP{^4!G&NXmbpcy8`0rgwtb;*kj$D5Fj4bdq?wgJQh_6mxLEEakXW@eQ` z?@1}udwA%06p)NCT$4ky01sPI0yD>nZ1=R%orj%{Pw4?^aOa6aOi&v%(v}7g*kCwd zuIxa|4S-08Kq`H|wA$5wJ!fjG)%{(nB}A4MYoP<{V2S))igK$kDOv?P=2QQUpKjSJl7nrH^2T3Nog_luDc;_bxb`FNz0nld%RBE zxT{+>YF0bGjyb?%-kxDrZELph#MZ_9k-AOm#nij;>bO#~K~5QtA!ufN_u zYmGU$t@)fI!Te@+0tFbvS!E7?f ze15jaT<7p0Roivb%$kGDTicq^33w;%@K1Gl*y(82$P-`ROvkjJL7eXsl~C7=_P}t@ zI&nR<;m5S$`{Ejp({?>(|F&imkJ;G+Ju}&(3vNwB;HO;uue<-wJO;n#+~vMVE1w*_ z!~PI$>8UEgQxS9wCo|~Gt&iK{laU!?Cf_=KrvAEZdgm#a-O_LJs3g5_R{FcO{y7l; z*2?1ce2&29c7s1}Tl&MTEP^iOl=SiV7V2cC)dl>IEsp;C=`raY^*Z)CTTBkY7d!ER z;1T0>wwIYYW6d9t5B72jP{$-ggB;tk%{z92{@}1>&R*eM&mHPyOq`n0&6=Z}(a!kN%LZ-It7i!t5H$ z7xIth*YK|K2lHX{7h>!?5bs)-)w@2blpgPDf1ual-SSB$QYVi;NRPNiI9*El^E)^wIe~>&p3SQ2^Ss0j5ut-TG*(=jrsM& z7Hp3z2H8(Vi1OR(20GZ@1=yPp8SSwww!P7ygYBKh)6Q|o>_9z+RBXZaGUKhu-n7SZ z+4k-M9aKGICmLv|UHPE6*`R~%orb*?FhY9~*lc@zp%QG5zu#8`32bs%8NI#b@XXGF zNwD?!swFtz`3>TRx8wL69&9hAnPGS!qdmBm`t5B8 zZKnZgbb`H95)$mVE#QOgVVyMpaihzpUA{x0?KCv;JnV6#%MNzjeh7l?(OJ7XWGr80 zY_`4QpqYmKm0@Ky!{AF~J1~yhIYC=5A5P(uY$b`K-mln@Jl&4E9q%NNwLegY!41Nu z$uEOm76}O~9|K=t1=piGjIj)?2kT?kgKZR4Y@-1bss?3XlfS-v!{^YNJ#tkRg_?h3$#ktIF zSwGj?4_BHg`xMG4-j|ICemtc@*(YGi%HGiRnmC*bG8*+Evi_VSGE4Y-iD-0Qe;NOT z#J?>38j0T~{7&Hy3V)agdzH{=w9|+P9;c5HfpgMJ#I=Lxy5BzX(e|OYTI6pM!EX~@ z=L25bhyDr5VgDD2&nF^2l=&e(O7iVM#K}E@SO?$F0LB2@NIG2}=ns|jBSoGj{AA&I z-=clHT^5o@{wpM2mmBdLh2KVGd4T`qxiz1${J6M&FL+VViFTx1uZ<4$2;Wq&yJ`A9wH^DQAAMMDSM% zpC~*B^cjDh@STO{C^_Y6BInRP`RT&X5}qCvwEK|oPYSMZQV!1HrvS zl;^l$fnas?P0IBgAmCu~c&NBVa0C%{CkoCGoFn+4;NyZX3etIj>E0CFD!5bdfS~pT zhu(L>pBKDHMEh35g^Ac+5T~_1pHO^_k%GJ@@;t*OQX`*}$X_j(B-mQ8tzZwq6v2Ul zLj-RZoG3U=@J_*p1?LMsEx1JRHNmxlZwqb`d|&V*!F__fPqF;p3jQE?UhsmTPq0w% zzdEOgK0wSTN$?uMc7mM+y9)Le>?e4$;4ncwM-leM3eVqvw4WhJmnZTM2tF$KnBWpY zeVv7#zRm*IiToWwecgrp1L1cG?iV~H_`Tq1K|QAt>9`I8%b{2Q21fDv1f(AoQD29F z`nn6eM&um?_4OC>0m5t7K=Atd3!EhK8G`yc3^^T?c)l$VTqLOH5JCQu@cKFop6*N3 z-y-;dpq@(v`F`OK2_6$XA$UgcN5S6&^91P+Mf>(#qiVv}6r?i~ET0pH^CIa{({=y2k|3>x91*B6n?g#zMeyGp78XQqTMG2=`uxrnc$0p^x&fW zZNaUA?+fk`{6vthZ`403ctY@`VA(lH^a7)Ph#;N8$X6GnPZ;?of^-cdf1Myb#K`v* z94x5s1CY~kjPdr|qv^umC3vr3mLOfrsQ;|sOM)u}*9yKNsP7BV-zNM{LHqu2TKMyV z7X@<#O9V~yW#+5rmI9-MuPTVOg>`&m!KQ+GPAT+z3g2IFkf6TbAbyPS^p9gc`o06C zn;iLv1nDiO>o2J9JBVK^JbmXFze8}3;3tA~sbl>2g69N(7UY95?}siydoEJ6@YMxt z3)1n8`bmPV1?f#kc`w1ff`bKb5gaX;COA=Wir_th_X|EExImEJb!rE@H@d%fgOED^>YpouhX>LBN#8(K(L8mqF{5u4n*|r z&VpS<-a{~ji1POr%ppR*5AT=AcOwz;I)A)0v7fi}^Az|F)Q8?^BKR~S^!X!y^r(#H z!zU#t{hc{D*CffOe*VTBoGko)Meu*?rv~1TU46#ayDH|7xV&c8duh>_+u_dS?1Tnh zM{FZ+To&m@m{T$;t4(TJTCbR}bN4&ksjs9hao?GGI&D}?N6aN?G`4R3{e>G-Zyy_a z!4cZg=WhGT*sz>vBR}=r*ynPhogICVZ9{TA=B6B@!m#}(*Vagj%qeN>NFA0|H~-*RBduQ7H`>aek$eD3j!#=e(&Y;1I5Ctu`vPjYk{rtPr5Mw*%9iDF93 z0t#o!=X0VXn0i%?Gt#m^o29MLMvZYDk{u(C`CO?U*o+>3%;%2wwAqE3Fvon6sojzH zF<*4_E=Z60s(^QcuMR#Ed~NWN<5_|&2U@4aWi?2>Gi{N3T*9}gcpSCddKw5OOBdO8JClTY!iFQ;^O+js< zqXr??*?wW_erO&}jUMZ1R((X*G*9wAEKiV?w$JA_c3~eGZ6usH;2GP{+eXgMZS+2IG_8f9}mmv8oKvf6k;OhhvdYY z3%exmZM&SzAAf7?KCKbC=5wECeutKO&V@rB zef%q*I~^^8xa~gIny-A(=?l9cH8?l8>f835iwxh6-1Z!Z%ZkWxL=20mcEJpDoQtSv zoa-Ka<$l!v+SxI?&Y8~j>(EET*e348J!@}RiDX4G!`Y6Gm8m1sX2jfI;EemC!VPDyHy>EXUUM!rDhGGTrpAQ_GsmvK z33gJ`9M|0g%LgiSgqGJA-8MB1J=eoNOZk3SyWT|qNTfW{gHkx&uW&tbKyQgoP20MT zS_dn1(pr&;Z+fF!8cm1phwa*_X)U}gwG~U-x6-yj+nEKS{#33+$|Do!6og9YX?tXv z^SZexzpgV%5Sci@7hP@ya?C7nSZPDM;OrWOv{hiUI&7LE--q*x^4ch`-6H#-ackN= zLHX8B#90&?g|pmf`tpIzr+xpjH)HEaTTxIz{(x;qt9=4wgU2wvI0 zp=A1#l(<7?Y6$BBkXcKnD~z8r0=z|VxFXI!-V64NSStGJsmHdANn zjH`~uVC_Tjde$)KxTk~0Y^q<}{H++?%P@a++YRzKHGUJ;>25|dm)vYgem+V!NUmh! zcK^aypRkc`j-8l!+9*q;i;yox;N&TGnvmyMsRB1w-iUC#hrNR@r14oDbWH{a$4U7m zsE#B&kVKZJRwp)2d$J*rJFX`?9b0+Khw8%8vl~XWrK*>455sCy5!oBa@>hQO^nUpA zQdhG4kq;K1UeYYr8H)M}GK(Dow*1%$_#x>CV?NAO#Ka>e z7t+Z=F?}3KcJ$k@S_^f1SfZyRc^{o{2V%M)W>u+}8Hm>tZ7TA`0u3`eoyyTnqR^K6 z5K-wKl&rFYi;kENhdCTnuEN>{?by?x!_Nzu&qO#JEQ%G~(61;uvuWo+d@ZL9b@a|} z3^{gyv=R?tRYwyfHLtIU2`_#Hi_(_}bcF19IfHjBfzfaj z4UR?YLDYx9m-6s{Cw$MtXr#}`Cc#vepL}paKE=YPmT(?@242jB=S8<~HYqDVzgH|r zhkEH`{Rn-rVRC{)e|94SOqh{@J4Cbk*>nZs@<1pUfp6_l8b`JdM0H)tp@al%72(?b zgfpU~q-Ij>@L%G?f32^}d>&CD7=}x(nN2buTlpYOh$(WR#JU6|qOg_G;cKE9*w8A3 z`Pg(hShtt4X$A$?p$hg+7!C3Yr^srjK9-KP${#BZlLYGmKRq&=1ls`eMAXu%{Xjy0 zU3;jIU{gSaHRoj&$CXFutVI$oVADqqwsdHYy_I1f!cEvrW6})$>7O)<$;c*Qny6{bdJld!5VfXC9RLZ9O(GYy%e8R2PA&m8YDtF*0WW_Zj@gC63Farj zN!`sTk2yJ^9<;GMe!Zsc@h4gyTg$+b`sO5Sss9ch&27Unn2_p)`^_!N5^fI`ZW7@R zODNw9uoSKD1tikKRodK4ZB6U6r$DdvZ%!?frA};TsZ*HS4K38B%uUJ??y!W~NDrFR zpDhSbz0Byg=1k93vHTc9Y`eHR=Ci7;dD7@^&ZHN(C$@gA*rt$q%oB!3<4MaR66xYT zCw2QKxNgftcsxiL_%4C2oBohO9h%TPGhj#Cwc03PM+7C0#}i-Tg47^6!XpwP9n{<+x} zKIsTl%C=<1EDnm%>CFf$Vp<@Dmg|F=9B&>%omM##>dhF|s#UY*IBZweY8BtKZtT@U zn+IpNHFr8ZP0eXMHKx~%iy2!lX6*E9I+&BYH`Vou8a2H3!%HK%1TUZ+Mby80O!bh^J`3uSp$CqsFhZg}@w4#o7w zPwxxbnA9?Pc+lq-{GR!E8>TN9qwYu_KVvx7!Oa+Mk&Fnq+fSV!&i1y8z5Y%?S(p9N zX{Z|PqTg#IO5^v_FZC^m|2^;f|3N2v?M9R~7T)}9hre>G_rH%UbttCT-t)Sh{=j2C zedJVpl%upCy|~Py&6AtqK>LrE<<{OWV?@Rn|EE1J?;Ag1;^aF)^f6;^OUsyI zpc*t~+tl|Jb`VzY4;<*B+d8Gk-&_} z7N*%$#+VryM#AV386%8@kyECW@oBdk-xB|mKNwL9ZRfzou?_}4_yz~-VG(2O5K>P+ zCIQRpF^=IXY;J6SrI!euviYtGdJwhACeXu>ggIZp`lnY<3wyYTp_9 z>Da-JyB>mId*fj*6P2Vrwt;Q0A80!bNW+UnR|W}ea!eV$@%Ry)Y*#)gZUpGye9zal z#>1H}<#xW-PY4JkWW(RaV>3WI-*nKy_8yMIFKftXuN*ep9$!4#X+RoVVUK!tu;b=J z5NvO0kUb>v+gk+MPD2}?Ad+ie+QE){5`tiRt6-1EiRBCSWq%1g)3843ighQErOjd(LSdrPsa(E4q6d_KxG1+i1w_VB52K8-wNl z8@}RpzC^sM4Q9ayw;bcyGXufI8;9U`i|o;=(gv5 zfWF%}eEz_8w)+!>wK>kLX0g^90IBNT9m%0O&y7`lt;(yX1r@!IFJ2jchK1;He z5vaI_2xbEgY6SZGHXYUv1-l8R z2o4Y&DR`S;h9Jipn9u!!4+$<5%oco2aD(8xg4+dm3GNsCOz>MlC+ex|CFl{<{=mpz z`vU{Hz7h3?3XT`lBPo#27oKmhsi*zafZ8t&xL4#{8IAF01$m;9*JCumB;h*<>NTq& zA13@Af_g1#$ma|HG%>_5mI!7OacZm;e3J&zb)Wv!ha^|ZNJ(&IEQFYugMH#U^-p{ ziMk&Gd7hB>2*wLG7HlfWbB%hP1iK0L6znfJNN|MU7{Td+cM0AjsQV@CJ|g@A!6kya ze>p+%n3e1S<)042klq1o@tqJYSR&uNBmO_29b--$Rgt zPShJNc&p$z!6|}zWEOgv!rv?Sh@kfOMEpYGmkPchxLk0J;0D2W1-A-*D7ahjfZ%6> z+W!;zoDg37e}ex}cn+JfK70@$x&~~>-^AW7JW1p`%!sAw= z{nz;n!hCpRvVP$twfI~9KP{R!_vrA~Yw$KTtfqV2gdgQ$qM%WnP1lbr(srH z*2t_CJ|j9UYgml?oY$?IXEjRb79tu%%fRX`kYN_%zGzu z(7Y?*QM7noe&&&R?p9a<g7SyW4NcaYT9dSI?r?NNc1D!_v-4nd^P7Z7=7z9m{>r zZR>rZ%V1;GdU%8^hmXj5U&J<8+PmHtxokP&*88H?z}lwuzUXb9GS?6;ui$)Ia zRqLQ1-F}(Rxn`X&bla93XH=}uxpy7bW?klUEnDY{SQCr2TGwF>)@6u4I4{;0+T`s6 zS7xDBMhI$lU#Hev-|o_Us}bjj>vGoZc+(xZ)u?Bp9V%WhD^!8pdBI^Cjj;yr9K1rk z@YEdml{7gFuZu}BSSL8r;kmyP)(URofH#O6HAL-9&yhZB`}$nx`}*9qogVXyvxB>t zJNf=jRgOSf8`AUF1Fr{ye$|;sDY#cDwKUHjrngWh?Ge-sYw&jRdkb~&I%7L|hZtTR z*D|k4zg4r--|IW3ES&nPApEI0~t*e>2Cd;C3&P<$V zQHwLzpl`&7THMjhkeo_pi~WgNq40~k2i9t4zUgyinrP?k=iIPyGkEv5?dKvvF9sc% zX~~a*#&KCLG0_+B zg|c(yYBt=Dy5H_-y|(7ObxyQ}vlid(Iy0*jGmN;6jmK_o2Xv4UQ`yts|-TU6T zNXNW&9!S8Sd+%HnxWSpOmUC-6+x&<;TIIRhZpd?a=DD2(=EcL6ufpoZ;Egx(oSrxG zT!}`3^OyaV(=sg?+7DV^R(@6UH^wmbVCA!!HN5CkhPwq;gGFE3oY`Q#ZTELp6Jb?b zIUKO6b2(V~6>SwZbROq2-7Or~7#9|1!q#}^-^ObcgkHMHGP2C+C}S$i7zXJD%Nk^% zMi|l`tGt@l(s34;VFkv8ZIw@FHp_G01zBozi_n6wTwmpSR$bHA!HP@aG0 z=}er7@VdM1*ZWtGSX(ixMrKOZpv(nXi!%3Txtkr%bSFF7U-#>b)fKZ~->8v^Gk*>G zl;Z_`#=Ew?fa?g({NpcR<5?fw>;>%CAT~PrIqcUU-r4>+?6+m@%>42|-;ngrVRNg56sK1m-~K1ttG`J*rj{XR)M{XR+iX?B<2Cy9^O=I*fb zTG{2kooV;@eUdmy&fF`eBHdgM&HPwc_#~}h^u91QGklVU1oM4uzeCyA#F^E8Of9kBnDOd0!A-t(APM?uY zBHv=tvq?n2DAoy0%O=4bOk?J3?b2jrHGt3t8aA^2<5XSwA@xw8D|PAM0!4yvFHB>yBbx-BWWYGH z(?P7p1}_@I7A>FT(52?LonVx(L)T`CBb&rQY~}oZQ7A#6UPy^j>cC$|wRKqr2U>fu zMCvz?SAapjwkRHiRrf&zecv=@gl3aq-El^!A!oK5 zu^}OW)51(+hAW%IZi@-cCcz2?IbgN)7o;Bxax*s5m@+Gy!~~1EGn>R@Y!0Iz!8$n8 z0!t_cj0^}EnHr&uSXF~(6A7lqijYy+wi)!ZKs^Tp>Nz+R72{z=mIUh8!J?FG8S79ZxqYZ%HgJHE80FQ$?rasXNYWF|4)GnX z48N#d>1+kOddE4;0J9R<PE(1AmZOvvfRY@M!CC}aX(71-H)awpcR`oGsh&*87;{ikzm#Z zj;EVZTeGqU&D<{j#<&~f;A7-5UvMO}Grt0{QoL>Muo~*@YzvW5DrG|t{&XV ztku?>)*W6&LwYvunbf%F409!%jlMwln$rDoOJu$VhoUd65|~r8C);x@ZcpwS`zh^J z6kw6cD*LC>IMc0T{^o28cUuOB_|pfHma#O0Dz&+bH|MFgH_|IAcCh&j`tWz?!_VOO zo&wJ7-n3~`&3y-7H%sb)ADjs{G;{#C3}z$6w?;zK8*hLt0Wx@0Su#)4^?X8M>vUBUBD{E=wP8XL3@-hbaY$=~cO-XC}>{eg3m zzc8ha7^S}-v9yY7`!ZeL+YLJQ;r6fcX=m;CRQi9{L&+K&`y(GEK0EwR`6!{`|M3fM z*204p9+>rbH{f@^N7l31|BjDRhoI*^Jm%@p1bYmx`ornJ>7&H;68?^lQgn==$Ex@{ zgJU|(m!1~=u(4h2a1@33J3dNu!#IS8YdhFBMnDi;kNFWF+UFGIRqz8S9m49MD`BHO9v|iz zZ0}z5`_Yiu!M11fHU`W8&qpcXqs05bf7nM!Kc>WI81bV^jp}N~|K!5kdf>Uyf9vN{ z!yn%9*{_0qlsNB~K1x3k(Vw|?-v5M;QZM97ACw`2se*S1^5p~LmEgUC3j`Mm^4CB0 zUK89P_^#k~L7rRG+b{TkK1yg0ocRCeql9+A`P!fT0ys!;gy0y#iGouE`F@T1vjyi1 zJ|Vb7Q1?&hy)67Ig6jp}65J-ZL-1q41A@H1GrwbkKM0-?{6+ARAjey%&!q#1l?1B^ z))kBsY$BK_Sk{NhEAsAwdTkom9U#2D7TrkUImw>+P86IWI7@J@puHv?Ul>#W3Be_T z*@7zsR|%H&apHgy(|<1bwcxjc7X*J5{3{=(TDWo2UR^=GHYoT;!Y2vZYt`}PBlSB7 z-XM6RV1L0ug0^qdDB;HorVGv#yjzfCV6?A&5rJiW5nq&ej%!kHt>7Din*_HBmi1x! zO611{%la@~61nzKgnbha49q7?kkehsR}!otsC^e9j~BjyU{gW**fU*Q!485q2;L~z zUvQA1Uds;Y#t1(_kZTXn-b}%}1@9MpQ1EfVrv;xCd|r^linQ~VAfMO&9UrWw&6~H> zE>*Jo>+hhqYLVEQ%75*HwXi%63Wi;pbC1~+HSxro{>D9PTwbI8W?yw<)Wr%RsTb>Z zsh=A5%=+I9H6}H7#K;k``zsy+H!*HM_QR{}FRAbF81voUir$)DBaZ%BY3rP8(l=)| z&N&d-)u?a$mU-*4)RU>_PKEc3==xIX@l>P!52xHc!-f9lR9H{9&__;bXF**aoM^|f z@x;r-w#~u0J-nS8M}TwQ$}1TObWXfj@=S4wy7$T-OR|beRLHTDCG`tS)csE$FPV~G zqTD@?mQ41QsClkKC9#)ERJlzbm)vu)L_Iv^qmm~sl&Gl2@0ASvu|&;3v9V;&nG#iL z@rIHMKa{8^`>Zbc@Y@n~Mfi%6o?n-!#oL}Mx&Ls9sxxCr$;3}f)Uu{emW1ysQSql9 zE$P3rL@j?dtEA8N64m6UdrFGmEm3RA&ng-EMu}?i!PJuRt4q|zSrbc|EH6>lH6L5@ zY<7wI;M~ZP_nt0MH@+~mI$z6I{Pl@qb=Rjk z#gjiPRuK=KD}LvrVzs!_55;TVDOQd1j};GowODOld$@Sr(qh$n?7`yAj})sDp1s90 zXBVq!hd(I(VFJ?4-&$-AFILNLc&GSauVU4*WLJv|;N{^C%Py3O@Kal-Z@<=T{4-0Jlr_574O zi!UrGQXLy-6yKaxq>i7sqj*|Ik(#skw&G5yMJlfEh~jNG7O4-yhZO(RvPg}6uYd8r z*dkSaX0PJmkwt2KV%OqjmkQO*r#luue!NgQmt9-jYImV}bzqC)hu0UX0Tr4SKen_` z86Pz$?si|HS~a^~@!C6}-?Db`?g51={HLnLPqZskZ@*NbxI+CxHTIV9;%g%dRqd)~ zagB=w>XW^NMaz#AsC)0dRCID{fojwCLeUp56{wtxXNqP#RG?PA`d!hU^a3?%)YnD( z1{A26T3-~+ZBwAWJh;E;OiY1V^x*Cytm2{ub=pz%(aC&OJ%4jihu!(==-Ri6#=VxW zo*lcksLT9(H8S?qq63rjRl_4M7DWxnR~P0#TU6LGU%k_HVbRj+`RZQdv7+;Nc`D`Y zhl+kYnx|sY?<-pNZl3z_Dph1I%~PAdnNd`IR-T&w^yH$ihvcczy~h{zzcx=@6LxFS zT{ZJm^w!};{qub4%(THp$G-5X_Y?XR)p*mVvQPFX3VFh(WuU{`b^5w5;+>qkE&E07`e|U{)XBf7 zi!b*nEZ6xL|*ie{ew^_S7hx@x%pH^GKz_ypb2wumzEYO_DCCm%4=( zRw(&d;rCYIi+g`o*KEuyIJ@X)^}ytd1>fHKvpU@9$AYZnpH<`UP8NJy@{`J3a=hUD zo}bj=en$(IKmC(RjyzOQdDKs8{*I3e5)*z>7iN7_P~!Vh^=e=DRg2A27 zs}FpS7L1HMudZ90RZ#2DIkkE0Jq7nIIj7pyn^o}K$a8Aj(WwP@G(4xeJU+4D+|Os# zz8l9D)O_=-8tfWXkbl=%b!yYlf`>YuRWqjERPb@=SrwU(Qm}2$8TG=+ZUv*~pHXeI zuP@lx|BN~^uwB8n>Sxr9=vD@Di`Y% zbUb}ZZGZKOf(fsjQW>Kw7W5c@N;RlcuHeh7PpRXdxe99kd{QlWv^c-~nv-hK4Zi#} z=_geU7@Gl?Q{9=oFCMSlYYqGvgQXhq0u+__0xY)ZNEF5->&HoDst(;{Lr7i zSI7JB&7ZUCd-YcN5A#=z`(7>haBKd&2H&d*>Ye;*C%;p@Td&U_@WOX0IcHUVm(=f6 z%~xK|KUw=b6*6jBe(NJA)Wuqh^RIpKg!=x_8ohaJ`jIcyqfLwQZhPcQ^~LE+dAD`^QpG=iA+N@7N7d9JXY*#Q zII4D6`9AMoLyoF?`@YWWA9YmCe&CC|-P?|+V;v6U{WAH8>Xg4bZ+H9=wQ~KAynde_ zR#orVlK1EXhjE{OJMYfchgI%3YxAx+^M#tQ=+(S2i@s22`o5Gmy4x2jEiyZ=O5W${ z><0_;rmpy0O;V5LWexmX6}EmjuSe+T>cL;`%X@FbXR6LBm3M07XKKTknR#2HKU2Nx zPRa9bIi!9(JU%b;_Csp^W4GpwtA0qe>XDik`oX8_M99r~{U&{?7HsX8*Qd^>s`JdA zdB(1Ts-W2od8ru()m!H~HdBwMG?=F>5^+jLB^j+$?PoD94D(_MU=RNKF_Klq?tn&h2|3N!dr{V{F)AK)4 znQ!0gyK(79YRBZ+z60$(Qju5B@VUSFPz^pc$#+40s9t&QcHcbDhsqc_#`o#A57dxq z!+oEmexTmnKgc)B_(0WtsITv6_70WRrHAiK`yJ}Hk}kfLU%#)?HeTneHS2x#O~y68 zb~WEuLz*W0D!#p4eRZaZ@2LUX)yNmG^zHrSJ#~JV$G72M@2R_L)b#ai@}7!5RN42` z&TVStqvd@IMsHI$bPMyfH@2y>ro*>n$yW8)mi*jTT5eVCXa1Ty?!XpxA^E4=FK^$X zmj84rw1hCG~plz)>63@ir@S$K=1G_WkyJZv6%CsO@W( z=00`RJL=urpUQoE^V{m3E9d7v)bDMz>Dzg^70$e+b}XHn+hz7!>fpe;a~oHFOZ`x3 zdhYwn-&92(r{|V$`=+WjZ(MHJ{x?*+&ZBeJk9tGhT5?NnbnXWA_{M>`F%ND~A5QI) z`*rONsyOk+++MG*SJ$5JoSWWpy_&teeeU(2u2Ub5Y@Pej=yj?}Otaj=-`1+zjx^5w z?*6rE+Y|M3@48~Gib<)PyJPtpHK$yS+^wzFsIwnd${qL7>uT^lk+~n;^t$@EU1;uS zKde^Xypl^#W~^2pZpgb7Vy;%*(=T4SYQbyjP~#sj<;T3HMxQ!)Nv&F?@}EC`X~Q+E z)RV)GURv_utEy$qLzj~Ky{f+Y?Bh$bzIjDuE%@lt^xI!iZF;_UDK2-V%5lGYDf6C{ zYW0o{mmV#@QccQSeW};N6?l$XacOJ470T^~Kti*nY?mVc+eK}AaqmropigBsz^Ebso1juKC5F6W;}M~it!mRAbW z&_B6{mKSx>P>b99m*147qA!$Wmp2Sk(djZ`5Yw$mEHAk z$=f;weblnDbcULY{(Z_{s{{ul+0ZVGU=A(42(sLfA_+4oPV4 z+4iN%=9j41@1`YxhnMJRA!VtN{sN7@U%kXW{{q!NUbd7>OGM`;3zx)f6VZ=3c}toN z321=#yQOWG3Fv9Xw@XpA@#vPm?LvQ@@Tf!W8hI)s3Esed3K`}6cpI_2ps;kc1#y#L81 zj8`PeQa!Sy)cpii8dY8jyZ8jfW+*HrG(1MB?lMc)jUS`x3X)6o;z#JSZjq&hqmR(F zmjX-Fw-IR2)s4l=G7;#w)XHLXR53zt7FURXfTh@zaus9Ol?iFva~?toF#lgW!RmN0sBCVtVk1VZJr|7r1Rz*Ss`#l#skCV{E z*EbfuQiy1s%hknnVIsOF>$n($C!l&P>%|j8coa!AT?}!+qqNHgix0|h=zb}k#WN~6 zl-#PZnED)x_Qt3$7Oi7Y3wz~7$QOf_h$<{DGlJ0*)IEzz2El0lV~NF$?E9#;mB?b$ z&iiPspui%HbPsj@^>?9SFbG`^`@L|}HV92NnP2!?5QtiCnp!B?7l^L@7+DAm3qXtD z{srdbU6g3hwJ?3*E_!Z_u~7QWAC)SjEu7x(k4};57Cax`L1|~I7S3_~{^zZ9q1Dk3 z%`7fhkSg{?lX0IG1o!!(NvCoa-XlI}IzN5k-_UI|@9V3DZC1C@pZDVzsy^I82Q;D= z)WvV1g0m3|=E2^mW`4+mB-0D^2?Q3N>3E?T$8ZZ(NuKD~RN%s!KOU&&N8g20t{!N( zzvlw6(j6U8zp)Uo-yJoZyt1$hy@}@MIxO7fxS@)E)(d!JH#9}nbm3&WE2=QAzmU3d z1AUjHy-@CU1J(1;oIr!XyhS@ zg}=|Qq31`oFD%VCp?k8nE~MKzp%dPJ`G4MBMQfCQ^MwSiqM5^U{5tn5Xmlo*f4clK zih7UmukN{wl9l`Us==2~aG1saNV|xJXEOK$hcBW@-ZXwadI2p^uH(D29np^AAN==P zj_9VWQhwG`2lUjf0{+Djdo<|KC;n#xd-Ur_HvdP$dGv2qIv?fPp%-tz;`7by(7eO( z{5>hQsMJ^#e`?+aMRFqe7;77J(Ig*Mjo@~vy)8G%hM+O%{&wI zP`*B&ZDfLO1ZnecJwJyIYH0A^3>%|Ob87r(ZDX|h>p}jpM@DD`MxGCK8KTvv_V5vP zL$rBuCtnjVKu3zV^IuT)(JjQS{JeeosJiaodA$Ew)OmGze&)L#`n+sze(!cYv<>9W zFJIF|c0&{8(6Z-GzdMOOiB6yQ=4+saj<4p; z4K>hJiTL@>M<>u9ZBg@k+m54A2@&(+^2bpxr;z#L+s9B-Szuo5^HKC@H+EiT8xd0zA z^t=#mZaiZLT1E|=ljew`S~0$J{C%Qm(M8X>Feef8-0mB5zn*VLJG!pSeQOd%v9BHG zT!n;Dc@OKk0uv#$S=n^14BUoBj_c3iiUm=}kJ@vb83FXbJ&n0_RRMHGOMQ;!u@&uJ zJ~(IhY71IlCO-!=Hlvluo;lC$o6#Sp5_8MvHlYpMMCJ@h|Bznl);XQe8^~(R-`RoD zzlhT1-?Iktf04^F^Ru>>){&SV?(Fu*Ye;+g$ShF#2T{J&Kby*5MIg1V*K;A&_{l7iaOlyjSJ?~#Ooq(P zaHo;G`M~TkxoPA!7B?$r$3y&egJvs$DTMsjcXsCoE)w_Cb5@!?i4;G&F-sMiM262_ zoz>ErK;)zxXV2dnN8DJ}vodjG$cNXavk6tB$Yw8t*;?KR;-#uHo4I!cq4P9mbu5Pw zvjX*505gRAA}Y_`OB+NS3>9W&r~}Bz7Ma=mOC01ugTyST$U%-<1!i;b zeaPFr8#9#jUc{gCdnT!|2QkW?pOIhaM&$2K&0Li4Mg%oSXLK#t$m(+c3?r}$`CZX9 zBmaVhY8;4GqBk>Z{1)Umm^^bvwgq`(k}z}Fuo>Ae95YkrNk`r_Kbnz= zXhQT8LudAVpdsuV;7lu>iaa=opE)z%h@6=WnsJnFM3z7M&FnkVfK(B@W?negBMFAC zGj$*Z!3sFdWT)04H))PDI#s`r%W*a{z(6f>+1YI7-sW25rlR4D%)y@seq3kfzG)5e zBLCzJ;8l(M#2=YC6IO++8XTI*dHVy=7uY{TsjfsG(`06nI2Fi1oaBuBMmb{UB06(P zz8on~5}eUHTZSB++?Z~=_8s}(2sphTUy2x$_|tN6-;i!&-ZVA81PKuun?6D-Ml@SE z(}v?k$n*>L^yaNaNb$|~Y0~~ez$J3DxH}h$>Ng9%;Vl=&e zH5GY2duEz(=QR>qsyTffPC?+%qtnl0laYtEho_;;SICQ92c~69l91wF*=gT~mk1|Y zYTCE^1tNWK$Mim4BI2aGZ5sKTfMjmoG@T%xfUHqhd9DZI5s!ogUZ+MJ(&{$N+j8zX za$a?uH{ckHFy{t%_uZc%zGdCKf}j{g=pmDr14knT_RT!Is3_!)Oam`7`6+U2u!i?3 zHxgO)>|x~O_glPdCkQEgaFf^U4k9KF*Lm;#0Hjy;5>F?Xj64{&Z=Mzdq zmPy7u;U@&7#!Qdr7K=w-iJ#)#dWl0|_A#D98Wsu6QsF($!XS6e;Zyj5>&UkK=+wLZYse)oX)3bU3Hell znNsY&iby>OnDS#?K^{8#OnEUcBLeasQ{s$ENbH33Q~>=VqF#J?3TnK7G>6(x8Pz!= zp$=A41=SA7IXROlcDX&WW8&=8*OK$dNYUvjgRgc7HT1+3>7y-D;h;9 zyCvipV)YuwJrH~p`RO0To%TF}*y#CjgD$Bf93d}mhN&77+IfTfNJ|yb%)ZJ!a8L!A z!8&sNBo8CsO>MZhHXTBqOPX<|W)C970Rt|!PYJp6S%(`=Q$+lclU&>H2N06|5pGS+ zek5N05SJUTfRs-uaO*Wob`Q=|}sZ3B~UzDOc}I@ptkk|mJ3 z?Dk2Q2Ro5;JbltMKpcs%sGsb;B8C9FYbMnVcOdX+*`(TGQ6##!Xp+4{1o;@AKWVrq zjIgfePG0H}LL^i&Cinf^hFo7xnM}wPMDi$!lQl5{h{VfhlW%Zakx<_!lbSADkbh?$ zOyZ0;BT>Ter2nB!hzgr9DY^Y0-2DFjWWe-aI2`bwBr(=u8@pSRXNuQgIr*EDxk-QE zHQu#J8n_BiR$iQZb8`hAjj@|lGx-hAx?46#MMsh4Cse{-m08Pwd#YV&U~Bb zJ=hBeZ~r>c{I?tK@A)u+?P9~u`B@Xxf-ZPCByFNSiUot0lO~?|bixN!;wILOJ7Ctz z(+P#WOgNbqJ~21n1_z{}6L=~Ewhtyxe9CBr4a~6iXfxfR04=eovcj~BoxzuLxE{(gaFUNwyu(m%tQfs}Ej)O^^`w0hh$ zAP*kjQ#QU^{}Y@(RXCo!{UhvCoj2abdJh{Wz8kN|&V>*9za4kRzJvD|r;NWpmjmyU zP8|OzmJJ`9j2UVerniahZQf@L}VNs2z&Tv= z@iR9PVWiqH2 zz@2J<|RvpF+yL*w7Q9KMgNDf;uHeBrzC5P>xzd% zqSMCO6manBt)#KQeheID5I0tq7W_Z2QDbE{@54W*!p8#k--Cf#bgZo}5H?LAk4?S~ zfcIjtV?{Ua!kg^^$29l(!@m#uj(K$X!5e=(#!O%M!n@mD##onqVEvC*#tul{hJznC zjO}gqhQHmg9-~Bh!D6RP#|~S0!q^=KW4c>C;K>o~vGpG};h;*5F&y9q3%pPtOVf6R z-v=p=fpaeKO)G^lk&n*sAw`)n``g#y)fI^`lLOb_eul`{WY<-g`9WaJEba=-ey}lm z!R|6V>$);3A#e$n*5QwaRa}5=ck)Kx;T+*-6QiT(F$Z|GhBLZ-A3afJ1wY(eGpd8PgwOVrjm{sjfHxNxjoutEgS%q#NB`Hd z;3~h|(Tlbw@Hf+pQPzerTqXZ{bZ4Ov%vw$y{o`W@|7(3VnzYXV*8TWobdr7+4h?@W z$_vqhyWQc@j8nR>`B~zq=$H=tLppd=HAx$`ne`uCvN;V8H{Kd0tZBi|vTlxk_@oKj zqSr^CyPbq(TrQ0s71w|lPM;qo{x}W~?6e#u1RaC>xyGYv`;WrBI=#^-x;iZK_S9$= zqz3Cj$47&Xs>0-Js-siv!*HXP(x}|yL+}xCxzP=6WjJM0dNh7m309~RAMJ@%gulEI z9_=(d0AGf-j6UQlz(Uv8M@C=B!%e4_M^;Vc;I}*HMyh7^!jGmVM|6{AVYq&H{%(JPs*T`*=HRwW>>&RUGDnxtjG@@~N1-b@Y7*YJa3@u)>9r=~K1Z8NOkL)vAguHec zjT{=}Lt67^Mg||uL((mpBNtWXAfddYBiM!+NaX3^5gY$$Nb$~r5r!xavb5SevLlZR z!H0K^tl3XOl&xYTuV=;~#i4B@b1`Gk)9OtlzfX)p!s&m83z~Ud*#Yg!e=(YQLCru_r5kZ>I4HB~^B zbJoK%-sO-b!*n>~&v$6>tHH3y^HL}#PG|U#>Nm(9dvcgxQ4A?uIWmm7R0M6(J~W&& zUH~ob-ai}-eTDuk%M7bZet{&rB!_X?`H=p1(P5lk9z;kM99E-$glfTmLops7AZ54J zp?3?pP=e9I5H8{!B%?Szv>=-UecC)er1CKfx->j6w8JnH60PeV%5HuOb>=XK=H1^w zg^!zu=H}9%4F86q%+ORQ@C15N^@oSZr&7ZeX=Kre@U)}KSC-JcKLj*Nv^CQpZCWS>FNhr)-T>}cq! z5IU5g6$PE-l7`%?A|ZJ?W~krp2_*L=U`V3t5p*oxXK2wo0&*mH3`Na8gdRG(40Qny zpeBPWL!E+Qkcy(i(Bs$;D1NK;(DXhOk{mY~63m97466Q6>j?<5%-0@rCRrUVZ2`l?bIdD-Zp>M1Y)1!B@-2OaA#K_Oow z2k%&4gp6K39Moxagm%Kn;5QowXu*p#$Zb3iajh|fZ8mn$;)#I4fJPfgVz zA(U#ZJ?Nop0C{U@46YZQg$(zo587$!K}Y@`9CXM#105NW9~4m6fedMT1_QHBL*4}v zgOLYLL9btl47wz1LX#l^gZj}G+hx=B-9L0 z%nv}9Zmc;{?wd5iGiO&N$x%;4-GVcfS_V0!I|78sLCdfd+6R!t4w(o&t z7%v8v5ow6=J$8V$AO)poL=If`lZ4Qx4+oz0?u4*7WB|D!4uNi@0i|C%pcj^y0pb}^ z=$A&oK*)#f(6+rk1BMF1kn0wYf&6FNpt>pNfws+pkV(hof%n+05aWma!0FM=5I)yx z0PC~~Iu>U#aJzm3Tn6uKM%QeJsh|fH!|B`I2+~UeIBrlq=#c5di5;o~N1l0b2-d&AXvl>lk^d94yK{web5{*0 z@8rPoAXR}|%&a-P`zpb|8m1h?qyiLGFyJI-mx0GcbU1gne+O^<*5J$rd;>p^sB=_W zi$U==Wsc;jA~38^wkHK-6#VQr)=LJTzOCrr`!Wf1jxFiWU3>u=pkMmA z7ZbtLK_B`D^5emCZdv_LMB_k@^J)F#zOi7Uep3HRZ4Agc64zgOAR08<7uBx=J_WyS zkLdU6d;;pOqWxx?kHL-!azE>71Q^kU?LRQ~5VUIu?3X+D08}aU?Wev91$XCq_Mcez z|BNE(M!&^*1k`+dwO=9|0^LcD{m=da;9EbN{-0OL;L3Hg{@gqwc+1AH-&BwQj_94~ zf9{F{fg_sz@r4-hklfLJ8YQ?RLj#^W~VoB5~Dtk@fDPFUty%V@{@K;}d+7(b? z_m94_bC*CTq0&BElZ#;1>eoK;I7d*J_pvWx$Q}&s&+hxGbspTwNbh?dW(yY7zUn*N zW)1q6#P9B78e_qn|{0ztof zeZ9*DVB?KDeG=yS;892KzTdHWV5X^CUtHfAP*dkx-=Mk<$W*`BH;O+EMk(0!y{^#$ zoh2>$gv2yK13}|HmFpUy_Ns2*pN!+6*|b()==4$0XYg2G#hD{udWTBir%*L;x>2#u zk){G({IRbuNBS^GEs*Xja8m}I---7H=O}?2DZ+iDGY7!Z*e!ixXZC}S!`FK!5P2{V zSnefJ_WciYuD3#LFG#w@?Jc|_1Ex8T^tz|)2D=^ld#eU_fk(}|dfQc{z<9m3-jqNI zaHmF7uWX?>m~n{GYrV1qwB1+Td(2Q26qYFKtqa`__6ipDN>PNsy0yGsDUoep-Tb@W zdV2w|d;D$h$>&=@!Tyw9d*&w4l9|}MU*;e1n)<9a%lR*`z2-@8U&Zx@04ad&&44)FnxC%1e59-Ie!Lfm_my=Q??qI2&? z#xzhEbh$TrXbM=nZQt9f#08w)ta|G`CII>slU{847;x>pes5df2=LoXyLU`(7|7Gt z=*@Q?1jwhH@OYPG@8QTU;HRi)uL`9T zkQNZ^?cLk~fa@DQ7KZJ>%Hm3oH;Dm6P4jzn3R?i3F~zJ&I@zkegr8WAm*FkjpLU zIXqhlWWD{;^G&4!FiZK+v+h;~tR`gjEGLu#l$f-hELsVW`#7m*+m>P=BP^~*LAMb2 z3Ptsd2Yv;*2oXKLnV$ja;EbV^J0(h@}tmjrn0-$$TrANIz4j52W?8(^r97vVl*VB6H z84xTh-BaKl4Y*2+_gKe21#U_R_r(8v0uXm>>4}?v1mp;>cUvk(06c-^?tF)bfX(K) zZWLdLt<;48+~vOR8-g&9vB2uK(EV*ZyK>% zob3i=HU@XEZgK_w)Zgt+QgZ?BP;PfmIbH{5f4O%r5S)OhTIcRBsaJq=KQDJH{kjB* z*4TGjaW4QfRaV_f5{|&c50maM+V;R|rGEEfNgi z7JzEGa<}-j8IV_|(A_0r3fPv(bYDAt4*2(7vis>ZBY^f@v>OW;0QuhqyLYCZ1>S%E z$M&ew1<2u5WwV>pH75h6|7TD4l&;GHz2dJb*vq`&l1F=ny z*kc;I0H8UPz5To-0JVbb0pFcKVjG?v_&^M(XWnDyr-=d*tUK(i@7sZ3wl~{>DFkqP z+}L?Df&kEeja?%w04NV$WJey{0t^q^v4spa0p(*BY`v=+15x*RCqD&yMlQW`E__Zhz;<-JABXb);v>kpdFz z+9T8COTr>-L6a%6)(!#on$sj%U1Fo_UBEb5PkNqHkE6?j1`#4Dc zqd3-etC~ahKRnQt#Ox#U)w{bwCVI&6CzxFd>umD*Q_WrXc6N~!bQ`(|2Rq5z41acM zX*0<}rWIWoR&8WOtCFq;=T`Ei^Iy6$?lzNOU;NOe2{)1dIc0U>W2j`ZYg$)OdINcf zS5lYU7Yg~CZ(J8r{fi6+Ms+2&{vs>ycbkgnm`ALMH&(6#qp1sMv*bqR=< zlfOR=>dKP;PTm>k*R^`&8yQaW>e{MTOcqFY?fPk1NY2c5>e9aQmF)8ALf1{t&*US8 zwp|86dE{MX=3ULeN3wK{QP=KA@5#p-bi1VD-;v#0w7P23vdJGhk9Dbk$RvyPt8`fu zza>8zRqWbbolaJm-q)2(O(jzorMsBS6!Nom@vdL}ugF0H+q?WGUXpL^*xFSypGd|@ z|7ErOi6_67|ILcq8b|IsG|v**5lcREe2S$j9YcPvJ<8fAA4NWG#9@6^jwE+kvRQwR zJSHbNwzK|eMv(ol(^sgA%VPtpz8kUJg2pPqev-a2_+J=IyglMG zYv3wC#y)$`>Tn^Emy^8za`{uq)(&E4nP- z&`V@v4=q+$$OUrA-D9jvr~}!WsKR2w=gIsqMV1s~OD>Mt$Jz{7ljD-5Svf>Y^5YzF z)+W3;`DKAHO9Ep`uKuxw#SA(}-b`EXbhv9oc4IAf!oCJ%#_(LHr}tU1`y99P&rMzO zw!b5tHZD43%63kt{ngXtH+$Hf+b(F43)jbEsXC?63*f znbo+H%oh*pRHzaoe^v17v@H@PKRM>rdHnr$GN|v`S(hqAeq`&^DHSJ3{^We2b9cm6 z@|2%#C!M^RY)&%o)DQeeDtTno>E`j5WcpIKQ|Iy;X(C6fv({pjlv{GFbDQpOQYb~G zb3=WJgzr@B{3N$P3LD$kxl?SO^nO{oQ*C30#ND>Db9shGvXI%{N#<}#-&MDE7PL%| ztabl(yr~)^%~}8MF#kM4Ds-OjNKG3eJ@cRH_!vDv3I|6!?m_*e7g3y!3IASFbt=0< z#<`m$@VUKX&9aN+RZZ_mJl#p^VbphwC^1Qa!!;d~;%%h8OXVGzYb~UKZ6zI26LeCw z?3a!+Od6^D$cGN8>PAwlK~_h`$9mE~hqR9I7j-0S&!mo_&|1<*Y+OftKn+PPBC2E6 zsftvc6wx7VQc1#m4Cxp>Qcg1b0dxdNeve1u$so17JJqpcE}b-Ae!PR$kxDwzs@h>(o>g)b^;y$FZ`r3j}7Me)hH4bzrqaajU+8a@|hM@ zk4b0W@R*FZ5v1heF{bpxhos%K0p<>$Fw%#CZf2QP2+3uc$y88BNQZW`Fm*&A()NRm zOu;EKX}fMM^9hYeQg*0h)_%m3uHX8`EPRS3(m2D zXMUtJqlE90_{>*K;c-7w!&E%;Y@H9ObW05LVCF4S?cT@Cst_;IjEJ@zJ+DvYUIcZCX22;bu zlvI(V&Qw2jj`aMiGLtQ8L<*%UFpWm^Nm0WxOqU8hQo*_;^Ju~u(!%Z?%!0exBu9;H z%vsY@B#QMW=FnbElC#&J_NQ|vNZX*rb}r=@sU>lyedF~JQsL)`_6Cd^si1MF-Nssl zL?7;LM->i{wr+H`-{mWjF3U37#p(}`sW1zqh|`FFmz`C>A+vGY?cp{+v z$@f1*O99{Z<;N?;bVbkhz1NqCy9{r%^Hmm!Sjs(Z{y4qQyOuS8d_48@s zpU-CP!R}MUl_tY>_OVH#6!%Q~^6D7TT1czCkupMjb?8|8rT8J@HdB@M=k5c3RpTdvQzq`oVVM_FaG5w5MB% zS2TaO9sbr#EOVT1qlGjP4T7fHRBfrmo~Y3_yf*-M>xJ@fA_T_EsBB@+I-; z-J5Ot%mm_{sOxQ>FXD)`d6(LZuE!GfTF$q%?u{YR<}BOx_WVD1OPRFoef@-Jep89xTx;YE#=z=6#~Y=Rb_(=Rrj8wnavdLjW;tX@=1* z>Q7vfon(YG_!93J3^PU_-X^ZP_c8vR^CspzU@=KaK9^_{V{dsessm0D6C+(2j}B@QzkP9H2zH$y zE_YsFoQ*z4y!6+WaoF?-k)~|Hpe(BrJ#38`2R&jZe!nR5>!l^c#B^@ble7xd#%ACuX~d#UDf%=a(di zciRLQbvfch<3Ag%OV@S~H4d(}_6my-4Q&@%$=`*DzL@FOraOYf&&lJhoqM+uchwHI zzHHn?Oq}Xz6(?^HPD^*T8mO%k<_ua}l~}8U#@p1^ityirs+eD`;-{AgZQp*h?iu0} zwhWfGc08LSTo5U2wKJR{l%2|JC32?-rf%zSl1u6zDw&N9D9JYKCxjF((*{HN{gL@<6W56`)N!< z_m;p`f^{1q^SE!T7Qcn?^txwjb_$*F?7@xJ7IPZmYyQ>NFVhW#dA4J#)e8#2LD04} z(dZYU;iP%%tFan_hpSQR)tD;6?#H^V_1cw$@j|WEx!y8D7w1@O>w{9lsHkeI&yf;> zgsxI+QEMT=`IcO3Dd8)jDt31(M*cIwta4}TNX;k0$mI4`G2ah_%sm3FJkeZ2h}lL< z*q3YqaDSzx}_nB3Wy~@BEMR4#A68Qx<6WEzC0xi_>{I7UwlF^PAq8I z&yOIK*M4d#ihD@7%Fk)pd@76}ru4Q&pdBR)JEpW$VPFCaNo>)S0tu6O&sv|&IA>E zqn0GAYlJ_rZVP$n3SlZ=t3?vNMEJuw*5V;^fuJU-+T!!oo`5q|YEibcBlKhCT3(J= z6MV9FxBP@H2|HLjTe9|;6Iz8uS`0s%5DL!bkAHWyAFAcSr%Y~F?_5RPi+HA_m#5%_-Z zn%lEw30<$>HlNqqL+EQwX@;715jF|FX!drOB$(>OHgD#O6EXrLo3B0GK~T(i*nDe` z2%)kQX;#Y>B9KMN&6#?Fgv;l!%^lP&g!A~o=BgW;2;Lujn>~1c@vk_Z&85&9ep=eK zxqing-ow_ZIr{Z7o{wH=7Cp9z&nUKSK36`E51uk_K4v?McULlQZt3FT1Fq>cAMxel zUq+v5Hdq?R57r)U7JM*@xA~*m93e4`Z#{XixiWPCPxO^<{&b`tub;N3`SQ0O{DBUM z<}YS!ywVQQ=DLGcV^y;K7}E_R51`*j`uX+tmlv`Q^LYZHrJ{<#|8qsyTG(fxtf45ra%Ys&FC@9XHV zZNKBs4pq@Nx0m2&_Lb2UZWQ6GFBj40hQ8vzM&;8%|IhfEx?FnY{3ra}Mh3lv^Z{?I zn@acn_YVIl_$9q1JR7g~@i~1~G!s8E@{~?_{s#Yfe+2!iOd9^x^$>c>>lA!O96(P} zdWEMp;pp}`FYuB=_vqh`B;ZLVcj$fj&+!|eH~qWTGkj)=8~uDq6yA6K8vTV{B;NMe zC3;fDBfP!udHO};aQwXtOZv~6F#MOkb9Am*2wrlpKAl-|3^e+u0 z{0vQ<{>_GfZxT90$5XL*s@Z-z*ESeGhRV`qX+ijd6;kwd+WFy_+``-EuQiohdEr&2mYTFF?)U?0b4|YHZg}0>+@^~^UH->0(zIZF9beDs zZ#rLj6>q4(ZgM?)8P9ZSZ#w+#0zNW{-jsF90q@>f-_-lr4u4hpXA|wH4gSuhiYClE zOMF^vNmJ`Vb3DKKOVfC&3I4X&$EG4#WBjUJcGKB-1N^7R^d_R%Sv=DCswv>n8GNvC zLX+%fZTthPm?jv|!WTz8ZhEz#ffu5LH3bA5$CCu%rj?N+`0WYZ{4^#6PV!Y`U^(Cms~mZG!PT@R2rJO>W%n__D}jO-nb0@Y|bInk?D{ z@MJNiCVQ(bcwtAmCb9B=xYF3&O%G4}#XV}<*;M%U4~{4;(v&Q{f{SnxXwrMMgeytf zpvA88ae_T7w6wc(IK09F?RMWZPS9hTHtaBkE6y0F?W>-^g^v!>gf+)-1hrmT{@Y<( z#NAHX4yi%hxBOO`QdmDum`|n6&iCNR+I2L%CmSb1uA&vRcH+t_zSDAznYidpMYOB= z3><2nPb-&i!99PROY4ek!u@K>pyjPJ;$$RKX=i=vagkSF(n8vQ;S`de)8KPIag6?_ zG_AZUT()uqEq!k#F4-@H_A9&$_c;%sy`BGt8{y+poArYnh2Vpkzg>{`>|<_BEl= zWz%pAdHS^Y&=g$sqBc#En}oB`KS{H^^a6J%>6(;!N?#9;$EYi(T5-fL95KU%n#w=Ys-ubsrb^ijLzje=Vryl1FiIHs`2?foiz6#Iw}y z#>2SNL#L_V4=dwJPH0dsgeu}(Ky~VyUImMm?=&9g>N=}xSwRAghnZ#y=@>tW-r@>cA@ zLZorCcr&(bE4eY(gNDtzf^8HkY{0(E4s1LiNWp$u_HCSXs>Kdjc{P%9tFdQaxi)@Z zt;7~_of->m%dr;>E;jn4lw!qV>>3$U#aJH4qH#&T5Ie1Tu95Nd3s&Oc*+$=7EW3QJA+0GA+qrY9 z!Cv+;cFB9Rq1Zbdt5eEp=*SPlzS_~@=geX3uj1y0$QS?{Ez;N!-9^Nb z+-nuRHSMArJn`DCpWxN~C_E}<^gWMXHmCUiGlxq$C zJ|tLf{{e}mnr?9OZ+70$=C$ZWm zPByd{p1@W{9BB{@|K2CD_Jbl@o)XaqutoJ_rL42>!q;Rt^E3ZLK0Yl8?WBlQVje0 z+gSa{a1rdNvzv>%T zRx$Urs_Lt?e`7vIf3LrfS;TCgEUahe&tsmL=hv@sXE4X!-*Dz+cL|i?*YY^ib5LLfy-;e2Oh^SY4+=Ia!4z1tyvkP-H46OgQ z)`1b`;OnKe+cClh_v?=awPKFE@~>aZp=0hX->QGWp<-B<-Rmhb4H)mQ&h<5pbr{K= zSL*SPeqx3K9O{RERAD-)*7YLG6_{x?vwH5aGK}gY!}Yx zHZRQ@-F6#*c*x}&kqxH zFPT!c&j-`MNT5jAcw;P2KcmPIJuu@ho=`YhZkUg&4=8SJE|_>%gp%;@8YaDpL>mg`rDdqj;P)$1q42 zDctBQHc6}|AO}qpU30Sn_v87}h<7$NbZ?8_ zGjB&@$z1>VNv2<8^yV$`?awwe7Q;8jKi}rlXgbfD zWEW4`{G%b+W>NgNye|#e{?_q%|N0xi2&;G!v8Um6>fCtfqmBj#sYN`?x4mKh!x{0i zyN?^HhW>Hp%xq~`v3QDeiQ3SxFJOYR{%K9a3gmCjSb(9SDrJPz$JaK@7Y%cMTb499 zG=1Z&jh8jN8T`z-@J84GojdS;FJ5v6^`{yfe?8~mmnSyh9G-HfWpNrv{%xGPQCh=F&_j+4O>E#E zZRTj2F%3_zH*(%@fj87>>N&mzzy`uo6Q^iyR71m%k+bK>{)V^Kl^l!ium;UqJ!f!l zNW-rEWt?G6Ktno7&2e?}ZOAxZ!eL~rZwTirI6b4Q8w^Gn=LFWXVeqwtv-Oc{!~cMb z;}o!@;pieh$4zY8@N{hfXWya)4TBMPIk!&FX{f;EaprxR-Vk>B21fvzG+(-Pjf1TJ zWxiON!wK3rYz}G3;)LdZHmg5e;?U;xo4cnjaP*1q%w~u49G|{7X2OP4PHoH!b4^4t z=ai|<{0x1P17H8Z%uh_>pzoQ@-Z@7(7w6TO>5_QP^P~zh*~sGT8PJ%QJ*RUzfyL&W zPZZ8AbD_Cn8i{jki_o0!5XU(o$TtVB#d3s;^32zFp*TY+*UVB7oP!(6GAGa=oN@F; z^TZh-N86Ta-f=yKb3Npg*}pK7lUH)g{JHWVr_POIhPCbE*j%BR&%fWpIX8`HCXMdq zxNtCLi@CcvFMD8SgmW-Q9|JTq*Y4m{*GHPS2XEsH`tCQIBK}HPAF~t0b zvw;(FDZs2cyOv||XN%b_*PHW^zTUi7xRNu}z1qA+Q2_B7wGbLX(?UCr)KT{-=J zOU#>loH=I;ZOwnbJ90u@7MRcfwdbt9JjdKH-0tTKBGgkUYiC^y#RdOqgI-7rdx%PWjDt zuzOq|l{Lc7z4)O1+O1)>|D?J8vfvwgid|D5uKdjY)K^hoR{oJa3Deg1)b_D`9~aj* zw!CLw376FqU%X}8RtoD)-JNXx#)A461FzX>lDvA+P&@nB(%kxWuT6LpAhR+ zTdLTpd$ILR0Tt|zHSqe|Av$)#R#5$la1DE9NmM;;zluG%@<2T!Qpp}K2(Moakh5JJ zch++uQZ_DUdwm;1#BQ78S8u@Z+1Qi~^_aKb@OMVZ-!4>heyUW|wUKS~qp#1lvbBP`C7CBD-bP`?_Bz64+M-opl)}IP7HCmvyg? zGub(LPwIM;XzV7thjr3KGTSSsv2Nut0$Vz-whohkV@F-6tOLfQ*={p*b+gzAwtcdy zj=_Mk*H6gnu2Dg3<}q;{hZM_x{)1a*6&JbKn>Ty3EvC+T$x8N(!-wkb*m$yGk0R>c&2?w* zIT%{kGtHF^ZV9Z*A9G^o?B7~vKjgsv(!8l|&ww49y>D&Z=58Cd^Z!%so97GIpZ0px z1-8s%_uO}>gVxSrPwjQ6+f+V_y|dY-&a9ZumhH2uvlaYhZF^u*=W^>0>+Ak$b={d` ztmc-9T4c&7>%qa%+FJ=fSU>-#8JXnotX+|xYIh*Muyp^^KXK$BD>~+F?Ss&MmhJP` zwMBltta0G;+C8h^vF5yLt-a^m#R`Nq*A~xz!@AX3Uwh(jJ8KELx_0`|GgeKHzBa7q zF)KSxQ@iWwBUb8wvUZ~G0qY*Mu$G}|Vs(EN)ZP=CS>c@g+O*tS*7K2DwLa&nS?NjF zYBS<1S@_AUS`k*yBBWfbJrPyL%AR$$)+$8J>P$aX3tm^kidm3Yi*`}4zFp zDhGOP!7nlE_FZD_%U%IX=8mmxdCXSfB{{yvy zskyAcs_@$Lj4P}yp*w3kAla;#``c^3?#^J{I_y_#Sbvc<^TmeRP^a^(8*rc63o}z$ zk?*}~&woA5+CXuu4SsooQ{nWJWTqNrv?vd#;`5>$PbCU^ncpvM)(K^$)Eqho4f2&NC zCA(Qg>E$NNsSwr;TeXSM6UdU>QsWiEubRI4`LMz|Gfm_rt5_t`1ru+=lU4d7#dNLHo#mN)(zL7El~rkZ%p~VJ zvrgV%o7z$wSvU`xNrkm%v6TeV!O%r4NdU$qTyD*p*$6Y~W>~Q<#sE!e@8_^Kzl}64 zteeHMpzk*U`O{f{$HGjYl)p^(3n3<3^dBbKZo4TXXpH%a=WD8V8D+B8Z!jsxhnefE zyiJgo-%5*&ZvnGbq#!T<}TC?EbL#8|9W6imh&CIux z?`z7YH8LBsx@rV(>XS7~70hpsnrf6GI_6zeT}}8B z4U_%7s^<1k36q{uUQ>8q!Mw6aU2}vdV|EG@H4}*vW~8sQCMZ(K{M5j&*|CzxRDkc* zj85KT-Wt4FLwk0cDLZ+!CSP`w*}EXC=6`z-GmLkk#us>n*}6Hk=C)5Z^Gw6Znu>py zm=MUZnw!rrFrlB>H5+8-n5oIMnscX9m`@iGYjUGcGxv)zHRu&5n4h-6YX-)SG1U)& zHESLoVG1x&H9lN6(=f8Xrk}%LPNav|Aj7Cktn1F2D-I;)aOw7%|0OTX!aaU9J_Zak zy<w+*Qec8Y2fX}@ymm9Ydg+}hM&!oy>b>|0hTns; z)f?CTW`xF_u6{o9lacf{vD(i##CVw(UmcV7m4VvAs9tmE6JtRusoG>e!0036suy+k zGWusCtKEd}7z?@J>Oo2u1G7D*nziu_)vmo2 z48X8MwLzj|WL;iVZBNxOzOI>H?Y&OLNNk>6{pY)a;X|5UouQU7EG#CCFA^jSOW`kL zr@xTlw`@ZqRU1KD{+KnfSIgH!m zkBx<=vlzX3EymoSOAOGqMq|KK8so=HlQF;QETcTJ(pYu!3`69oGv;kS#i%S-88?k5 zF($x8#tY>~8MraA@z&9J#?L&Sk+6luPzKyJ4h_*5SKr()ZY?G=@=sndZl@6#PnTvI zCsyGY8>`cdi62mma&(GO#e*|Q(@z>D2nb`R@Td{81jq;tXB!)zMKc%!RO64!hZ(h( z2*x-24lqL2VvNbN_A>ffVaB)BVT>{k&^VQ}i=niSGQQj#%xEj$Z)ASi&Txi@8*9Z| z8JGWt7@weg8EXaGjRlUI7(c@OjH@26W4s^SU}UEIF#crw7}+~lF@iR)Fm4?4WE8f$ z85Je&jG&Xw#t%eS#vixE#y76cjQ8e+#;oTKj31PF#y=T$jI|3bj4OB9Fmkm2suup9 z&v1cFRB08Kj3@s_sutsBGgRX5Rlbfh85IXURV{q@kN$c1LzOgTlD_AEDaNGlIK3tK zP1S7yU=HdKwc zyr+*m)>dt3?WUWPN~%_+bkM8aeOyKBuqeaH~#Te?k{K-Kipnx6;Gw zu20-WL=~N2ptC9xs?OS% z)3@MRRls@;-F*SI>H|kb-&!75waHycPsF0DcC^aq@2y}}(@#n0$8>&Cf9@WAZFyK#^2XbA5-z0bSLY4-!v))`d@fz1!z+BNmipz;?FbvHTHa;S zf7$p{`DdlmXBfSz&|A~!+bC{T;qO!Fd5fK^K4vA;J?iYM_HI2%f5BW>Md(SSYh314 zg=8ks4fkhNz4YbKza0Hnxu%;zkMNwR47y0AKYTn=X|<6=Kb8Ew^42Rn9k}*W<+~IN z9rETwW&dgi+za2JL z=Gg6{&*j%t)>eem5mAQ9QgkT&%|C4=(jtU@wxp!8Nxp*)K+7w?M{c7>EfiNi8}X$l z)^ID2-rhuSV%@2H9<-hw>VBhgsKpfH1 z$a1B7+&EEr!`7L8d(Y8Ik1_{(;25it3bvzL%Bhu{@rCsN{gah`cjwbRtTC0kKubEq z1gjkFvY_|I11pDK0Sw^#n+ z4%0luewDb8Z!{BRV`WzNCtAk*HI)gc2WY2FD=L>P{Xn~y;9hys@Q(IjwM*q4NEZ#< zwYW0z*K6A7RhvrN>+Lk-9;-^~re`$OAB)PA);3zJYFcG1?ICS3@sFW*PBSgt<(FZT zsDZZP$&evvXC3Y9h0liBoz=9rf>#7f%ak9USAwtCubS%=}7QcEjCw;QhQEv3ac zJTWZnRnnXvwHWrDmeb~+Z#3+3l+wI+)Ea)Pgf#Y#N&|I2kJc;G8SeJpqorU=4H>6y z)Al+k4E~F6(zZX57^72m8!2AO6I50j?=OX zkA$f-hSx=dY}`7 zyCO5&hBg!Sy5g;OWK8(trfLfXVcPeHdjP8%%JIj=88Kp|ESiBYbr!< z|4?(ES5(mHW7N>=+KL}zBUD#FNrivfFxAsuUa@V_H!ASCsABBiC#w27x8m690qS<( zoeH(4m-=n-jS5BZJL;qMoQk;SPU@>$85JF|uc_A1w2Fn@FQ{zil!_VTr_`yA6BX*= zR;n)lXobhg7U~@|yW;Sy`&79Hts)@XOzrC>RJ>nYOFbyTRO~A-QoG6U3g$`!_1+p# zMNF}ddf{7C#fYDVdbjjI1;AKB?M&EH5g(?Y?%lSl;&4kL_1&Kx6@$@Ys;I`lV%IA^ zHTT@63J9uzS{$*qV*Q6Z)KRNd6}6OGRMKOQ3cK&QRErx+D?AgfP}`u66~kj$)P`lY z6{k;MqW1UBued+`0(FaQPQ{b7vs49hM#XK*Gt_9`DgCnSlT?q1-+G))64ll8Lr=&} zpzgWwRlmZ4L%n_Qqh6H9pgP(0>fbw4sSU5Y^j-Ie)O_A6{jFtqDv$I`Z^J`V+t#=0 zBRmk)HNWob0|gMO+E}muz8pv;q*d#&!f0yPp$h#q&%@Nn#aex;a6k1zSFwJ*X9RUn zEYsf+?4~9$MS8QxPU@DeT)mPPNOhieM-Oldpss7auCK`VqcX1L=(}7tQ(wU|^rqYE zsjL-gdaUCb>i>#ueeLyC)a4Z?^luk=QG?GN)mL72r=}fZ>%ms8)Nx0eUUkuldiy;= ze}AR}m8it%xo2#ts3f@F?~gV0+-{Km(lIOQbL(jR-QhXZ=r;%Sbowmngm{mBvVR)2 zjk8O?A3H^P5)`NhcZ^g1S#H&P0)J7U?VI$<)*qC2g0=cz5#K4ftX2BIrq7i4z~y># zz(-25rK^6Q`U6GR?x@f5>7h7_Z1p*UE{dG9Kp*A&hC&LNt8cs7PKjPHQ*Ukgj6&*| zDz{2$qsU}q zrSt6T@@Ew~3NYq*dDD6g<&Q^Od6KY%(mLE+KIo{RJgPO9J7pD8#;(?s&zUBsMB@zQ zWk>jw_RVGG9s~K5i!)W_2Vr+8gy-^dzehJIY_Yh!J0zDPJ;p2Fqt2mN?Y&!0_sXK& zb-Gy|eKVZ``Fy4P*PJv;s4=q~dOVc^&ACv1^3!R`J#1<@0)B!r-}hAcWXmy%Y<6Nf zJn#r5{xzpONx`B}6!dc7QaUB;45@rLlT7J|!IdBU6GwrpM3xh%SjzMXaCz`+B<0nk znDX`r7^Q=MsC=CcM6o)yw>;Ds4-Y+fI4y>Q>&G=}#&6=~RCA_h!oFX8ZEh_ze^V zcVYRF)-{yhN9UC%2dt*B4qBA&6?swYJ*SmFvG$erRJEu@In_vp&ftte@;J9SCJb12uk+jW1SvnY>rPjrEG(V94y zAWtP1>em11CAUI^I&bVd@}tcKx(|(=&DkYCqc*5&+qLe9Q- zNw){yN@gaW*BNUbkWa;&(f#ynBJ0(w41(Bly%gaQ<0CMs&by?GtANln(Wmyq;Ga1(_EjwJgp6uKxC@Y<}hWxKE zzw9}F71=f`udKYvlN`&+ErTw0C)dSXE~{iLC8PW=m31{NA$vQYFRON4OkVysxeRl3 z5qaWT#wXDq4*g}f_ zxugv3bf09~VOLg7Gn1y(TbFeiO(fSM%QE9aBZ-_ls|j3GY9og^J~*8*ZPq`cVn#*W7;Xt8gJH?Z-Q9`3){9w6jAC?z>A`-`K9z z`R0-Ks-9@u&s`^7x${t~dwPX5C#^{f^2jDBS#??+>k=siX4JMD(@1B-_1bc)vn0(% zjTQ_|CfP16*6JlENZdIx?dzY%NbsLRtzqX8Qux~fEj*h=Lbcr18eh{$lJe`??iFOx zQc;f9#EB!Bu4HI&Mhq$Ubeh&Y7fHH7P0-npC=(qkX*P zFp1$#*N&XtPXb$$w6B`>kl2%0?Wsk(N%~I+?K@ZqX~S!<)rX`{~P8QlajU z_KKe`NiN>29X-8~)Ny^cc4^~U(vI`N+8Nf~qz6X=v@+ld(nY+l)+XPBbR>3zcH0M6 z(&gPgTK6^1q*q&3Xzz0zNYP&I+D&>}(wM!A7WUVg)N0|N4GXjS|M=QQ`|Z*k(wzUT zPLQ^lB+BdA+H>~PNPiwo*Rr6K#LB8kjZ488QC|F8bMgHMv6=Tnqg^>nbjbax;Zwg7 zucdv|L>3PcgOYkR)x&*6M_RY$tM7ZF8|t;DGqIZpj()DmGQ1&HhqY;@CfkXCZ4Wf- zL!J?x);4I|Q`?C1-A$UObuGjV_LZ9OS@(&lb9I{I;b!8DDV2tC!9-LK7im12s)$$n zC7N4vDu}!ezUEOx8L{i}Jx%?^QsTbGTbh$iN@8E-HOPHCxggY6{K0Rgi1uaZ_~KO5{ajrwrDov6dC}Q}0Z;fUKoH%UZrKt=A z6CeItrb#;%OKcx^(%7gXi8dql8u;J=;_+__HKgTxiME6DG=A_f;+tLzO?~c8;?wSF z8rz3~#PQdE)XQfD5TjoFQvclHM{IvQtWGel1n|Q(eUR}Fn zCGml&OAU%#P7F4_QY+Jz5#LulQ#VvP6U%h1>VjbhqF&Ri-nPn)_(^3}=OPvo4;I&` zORicGyNe9!tj0M+uB=S$^JgaUid3b(v|$>tR9vK%;U@_*L=tu8tuew`0bjkYWrVPq ze@}h&?+{@T@0Pl3(^rBA_nP`{+#mr{kgX2A)kkQ{Pgl#EdkBpDbLwY*x(I>!$!g=e zH-zo^$JG>cJAs^^pl-kNl+c*ZQqQVuB>)Pj>YqOz5Nx>wwa~MP@Q;g8F9y^TT={Ty z#Q7QmRRB`&&{h%#gwg8Z-g3fq@j*4oPD|iOBh=hb6(Ly`s?Osm2$e-a>KI-jVRi8~ zb!)4L(4g9)wwmG*u4&e*E!X4|a&+G6X2@+qRfU&&|AiX_C!?D>OLLVVF*&Pq-enW; z=EZ8jf($~`eH(R0zy$*1p_O_$@hrjcc(!`YwPeE97t__hj3)?vuO~~-4jv=ab^k7H zvp+(3-20=nJA_5B9{gHbOr;S{efwA%a)U&09_cN;R)Z%Dj(3+z2hoIqf3HhV+aU-J zvtN|j2SEr&=RYoG5CMc)b}gkBbD{|KPK~8_{Xv4py|#3E&tAf_RaK>E%W#6{hVs&s zO}hvpe|0Gi8bkmFD@!d>0|@?m3QK8)euRj_!qTg4n+TUc1*OM-tt0$F-7fWX^&u3H zu9xQQUP<7vb4sfy%l}U}&nT7WEF%=2O)G_$ITPk*rIbE;<3QluI9WPvnjL|_JytsE zwU7XpaY_~YtOzL@dg%)09KuT@sT6%}CINXLR|?nti(C8*S-RxSpSY8ylDaT1nmY2NkbIE&LuO22Cx z;%;QvmCkul8wbj>F6|jH#_g3@mY%jZ#8I`gO5beJ#To1VsU~97aXX((s5&{taiecX zRcEfq)PVbCcp;)~Zy0JQL!`&x%x&!R$DnK8dOZN{@5>%~ypbkmGh)=Bu(U$Hm=r$y41Z z#KgI*&sAaS5OGg;URHhWfW#SMFR6k?0ddcW=T(QTqvMvIIHOv=>QLOR>=P<|$iBGU z{G%!xNO+uk8C&JU-W9jLnWmbZ9u&vuBC5pPfVl2qtZH_-U)-75NY(1rO>xmK5Y>Xd zb#cIrv8u8^-fhgHjLSH=y&_Nn%-ULJRm9j4kAyeuyALWt^PtaIGHd)rkoibLEH zwVx^{**322{zlb>T9KaIkomvyWmId`1-GC0duJ_GS2lmgYwpZaA;Lf7C)NK-K7j}D$66*zwo`lY z9v?|F{Tg?VJJ$nnIgQ)C22|1DIR{ISWsflxQF+v%`Z8hmxs^p$}5>I zxsG?3$Sv8gxq^SCZrIkoupU1CZrj-2ZOTjBLPnOL6aSD%? z9V_XaO2Y4M;*=b*Jc@_)(MulMbMS(hdw2RYLJ2;6-R?$)gY~ zUXu(c8QF)#kK{*|bj3pPMC1OF3?vY5)fHYcPK?I)OztdM!#;!`TpC#7c6=XxdC=C9 z_SA6vW#s0PsEl3sHOcErvabct@y)$B|Zc`Sls-@0^gkcp_nr~9iJw6Tih`^g-d9BQ*1dg zj=S;cMe+F5C~m;|NwH%34;+2V!(va1Z#Yj#Q!!%hC*1tgb;S^?e%va7vDnf2Juab1 zUwp@=8~5{zruePx8=T0tq3DfWs8sEtWbr z;^sfSS)A-rhxlsy*O{F4yR?FD?YhYjf3AzF7{knjPt8L zUYzYB$L;D*C^k4ta4FX8V!4w5H{?$%MlC78<)VqjFC6aRDCyYZg^O?EIHic<`F7WE zMQ^~x4{a{v9B0KAM_Fg!bn6Zm-?F-Zy9nM_%%6J}mzf$?%(O_x)fR;m|DApU=iR=& zIOgwBoOzmmF=c{-yS8Ri@$O#?+*Q!p;+|m&&YZfcIP@z4=dD~`O#Fz&nO?aTAMQos zGG;jyk99$D7dF}#6JG&wWr&5vc~7Hp4wvQ?XFoiIlb2Z(hd1uSao$fWHr0gVs0$~R z|Ma_XHv@kwXQ+d4Ba|P?CV2oZ?bcUiw9pT?x8b8Q|L!JS@XubQGIt%0f5HQ2t9-1y!g0k}bhaotWGCEOt0tubdND3-dz~^FxCm!MH7ex? z7U0@$>y@{6S>jC18s)*Q7Pt@N#mc(1({Vd|2Vwq9dN?hj$toPY;PnUHcH`>gkW5)*I6u5iRDZQ@K=`F^DG zJg^FjO@=6|_UN$()v?O*ty(O#|FH7dY8BStyk9xKM1c*C3|H>7EX0nU+o{|?F2ugo z?@%rogC$WE?TPe40PsBRTpQB{2I)Wwco}r}Mv#=je zOexk*r(p}!V+z$*BKG2^pNg^9IIM8_cg4&`6!r(~lj2z^40|-UPeIBDVb?r-r>IVk z!P;AND&8D9jNKUgQei;t$EGAcRUr56!Okpwq-fX@immu`Uoqqwj1_vB74PP3$C^+z ziris8tj%qM!m48v_WH9jMTB`B_JDP%Vvo`r>$gv#n0IppHuk(!aV^;cE2 z??3s9Z-ary{`1Z67JF+-T;w(4MB4(?SrCbeM#vvw=W z;Vqb^mSBZTNE7Cw)po`1<@J~o2mBNpEov~l%#Dhk0Rv{DWsL&#K!-`6ze57T6s~9e9vdHCTHfBry@1p6)E@A$>{ZUi|OvC(I{;kN#FBP+bI9PPh{xl|C z_Ms^3XA;Kk>)WDfPZKboHg*)HsMwgng!ZC_%XG}riYG;FbTa1L)Wf3u{c#xA(ECLj zR%0+U+33`wZ*!Jo$kJ0q4|-fNiQf~8Xq8Tw%B@F=o?Ksy*_^^Gnq(}( zbl;~Gec7`BQ@w~##B;O6JcVJ3oW^EhoJH^=@Z)KiTVFv%(85Xd-mNi39w}q!b*YDn zl;9Eco|e5uf7cJ8a~Fpd+0FifUW^GT`qnvsZjo;<%GUIv%SQc*eq4Hse!g>4kqf2+ zy((*Mk){7jbn(koMO9YM&{R*)qAfkGXc%i*5nJ~Fom}Zu6rb6MemQ4x(KbvSIu2k{ zWcIB_ui#r1*;^XWF5hMsd3Tke_w1NaG^?}}ElQt~3(qUjTieIvb09MGKhF{QrZr;p zAI^8V+g~1ft?85e>EnCotJeMU{lYx753)y|e)Kwetf*6-5pf0mXX2$i+9?aYdH*wc z_os{K{M)Va4OQpR!Gq26J=tf_wgCVNU*hu-D#*fu8m z$O*MPj7vpFwkYM}Od=Y+R3<+Xj6;hUBDrP(3caj`E7x~I(GP9z%Fh-7(IvQ>@Cw2XuCPt@-q(m(AS~qa@2<~^nS%T`3&_=wC}%UIqgg!IyUBn{LaB`=tA*P z`DG_x^u}?vJfeRC`rAReyg|JN{fM*+aB;lZGNybW^Tv{BUWUp{hf^AM`_&`NpnwJ)gGA`kgl_(zoUTm1$xyNPP>VvFWu1x#}XydA?fK_vtJONLI=$ijz?d=0e#g_6ZctLnOPgdQz zVA~WSmlj6;C)c$cya}5X-0(1KfnX!`8ia! z^!HK}`e3l^zIF-fi84SI5O0r4TIeU^Y_LHAIU8lnFIFhhvo*5KvN@;{zg4nI!c5fK zyyY^h<^PaxCtPLj-4nII)JUO*{Tzww`Cgdj^B9TW^SRLVLksdw zQGem7{3hh=Mehswpn9b2SXW`z!Wv|1=c~e?`vzoA=<`BtiVpd-u&r=-n;LmwVN2oY zkP`XlXk%ebp$z%1v$il2BSuc_HWrE<`N#uB`og-_d&noY+Cp(!9`f>ulETA**O4jj z<%Px{Imp8OlER;bnaJ51e&Ki2MdWRl{K8WEb4dL8yuyG7$w>Uy+`{xTCy;rdoWgwH zW5`*ijKbrC9HiL$LZM3m19>VpweVaF1(`8*s!%0vO`KOT=yat`OB7AxFbChxi=YGXtU!0vTYDisQ9`EnGJ*#TJu7YDYdbMTVsNe z@^z7gD`#y-&bza}u%pZm$(y~W5KP*Hq#xN;cxTBvB=cQhp|E*1QgUcpVf+a%qLG;r%cS%M<_qE{ zVobWr`Xd7R=%-X$*^3wr`Y!!Sev4=-{v`dnxC8OntzTMJ*N#|twMQDtdWtwdqf2_r zr4_Lu;gwX~)Qniv|4e%QNCUzL(k2aZt3@1t@Ib0~P=)v#*eLBisz+3m)JosEYY~d& zMyaT!1o8ZaUb^8}5n_v_R+{22MchACBE9`UfVe&+mnJ0?Aa2D;q|27wK|FrNmu5EI zK!hC1m)5YaBKm6cqz0#KM6LgI>8ZMO#PgyYsRivkVwp##6kwNvD7bk+N~=7H0M0)v z-HT5|gq}Su{W|Xmf;g5Wg{YYb6Ei`Y38f;U`&iQR(})Ns1Wg()#UdP^5v30gArXi6 zsY_-AB7=WGdT8Tr#2n`cY50p^ zMCG+msl|!y2(eYLG;5hZqUn5qw4-hl!tJlGbcnbPQJlC@`f#2%B4K!qlwItFVAEDf zJEGkY!oKCw1*0yA1(;>h*?EqL;x|sx#_e{93&6$F!(G;h8;@Pwh{k5vDa@Me$07w?#mJe7{X8ResrM|+3hlUs%*mj^$?>r`JP zju`{+>UAF_B%faR4|%WT%!6(?a`jsYlKKYzSNujYb6z|ArDwZ@BYOfL;6IT__CA8I zbAKce4BUqo72KEn4;A4USF>cu%LG4guST-Fz7o!KsgxkG;l+WgluXIN8aiCFkt$(8$?$I)f&};z565i9N@i!H;qxjHlH`?e_~&4V#8?A@ z&#aG?m?1Inn21P8?(iY_>z4fzpNxI*TTy!?>C406Sub`;iVZvA6|f-5y_i6_>$`1| z=ucbW6$D>NYw8ww=I0F(JEslso18Tgca;zP}BbL|#O?0NQZ^c@>Xo1YE*o5y@fOp6sX_?cp{ zcuEW-F5!y@viUH)_?~#!H6M0sbDr3&%!AD`<%&^3*I|W+a>TU{b71E?GQ?ltnXp@w z3*xt*F2H(!r;6_!KMNyXI4yRan+)?qCY}tT z!vbSSV#*^DY~g#HI3I?GImM&IcLq=}_zajBodAQqxCRt|nFfNTdq#^xv!h}0+Jj<@ z(;?XP@V(+a;=QnM?YqUJ8^d5{$RT1{RS0a~#CCB}#17bjEPt{3sXr`j*=F%s&TELDToi29XGaVK+Z%P!|Itj&d$3zD~W6)yX z5s_{8Pw1ux-$i`Fcjy=NXVKV~PtbRx{UXPNe(3zH_o9CjJy7=YZjmar3p&5zwa9z! zYv{Yk7b5EA=g_bHk3~oAA44}MKNLmWX@Qn3zAx%^Yl6lp>qQabI%rIIjVQsV8k*E) z5K&4hpzTL>qE)_SP=>WyRIFD)1EosQRG^DdfHs%WL{+_H=&~4+C@(G!s`!Qz z1@@t#M>0_&IROrhUkwwz>jOb$4M5RbLJZUiA1#vh9fH=j-65C$~{ zhKb7XJE1lmAtK)U9nd?+cZh)4tx(jGt)gddH$!3Nn?+8j_0Sy9dXaahH*{*$TQmc< z0xG<*LL_|Y4o&s*5LpA4LT|rVDhhq-2pv4SL=+rp2aR{I7tMNT4c$_{P?WoO9&|m# zO7z)m0sTKUS~P#xbm+r7Gep0tCLx@_ze3rzG05TWap6ksPe@$KsF1edJ4C&FSa?GI z39`N6i!f$IKV*XRQTUVF1Nk}cgAnQ51zA!2R(R$5E6A1T4q=w{bBOO~yD%ob4PtZq zsjz2y3uHym|2m12jgW+%W+8l}7V;;pK^V?3LMnY~h2wpCh^DPdcnqb5^d;zp#`Y3O zl(Sa&@Ng02XHAJv+$e!OCKL(x1`8nlR#Ks+EFa>l76=E|-iA~{3WNi~>yT6bZVOAC zuRxAUZU}c?&4d&lx+=Ug=OV;zG)q{0`Yc3$FI`yl^EBi}*m)t2avY-gaz^;RI|1_N z`bpth02^{XC{Y;FOoQy{j~BWGlOVftn8I2$4svuGRk(2#3i7^(Af()dLeev_Li$1= zgye@5ZaWtRNqGwqKKgY4^5hagxRx3LLHI@q0bQXG_qPXx5mCVq*Nh0^jQRiwz;Czk zqMsk6{#~%JUAhrM&)P2h?z9$ic$>fQN#-gD<-;c7sj20V>MQGn!^~xn13})xjqjWw zcAvb20nv*gcDLMxR&_RzgJDaB(#`WBHN%d=1;RNH8rM!3Xg3oQeQ2T3@7!N7`_DY# z*pG4Wec5c`dE6)%3Yj5%^JEC@HRrEjV&@mIw{BeUp=1C|B#a7fE$an$*$)dAXLo}y zo4*JUe_n$V6Fv$Ulo#N;ULOPzFCT+{KYuIu67~>$IjutgQ#XN;{x1dB-0H!^fv1A& zS=C@!UaJ5zUIAXQ|AF8ap$z=yPlEvTR0VEU)(TRB72qFequ_{K3I^C#2sSwg!9!-P zK%ZIwZb(!K=6$^le&(YPtbp7AFYT5J=G9*T7hDwz4C}JM&~UC`OWsBB;qg0yV>8Zy zPb+T<&eM~@eb{RPc>8hiMTg6R$&jO9e9I*PS;ht@rKAb+ZRy}9zf?i~NfJ2n^CrY(a`E5Uj4J3F6bD!0;0!!G^B~z`>jFf-*n^`2Vk+ zV0Kj~xReVMxO)bJcY#3yi;MuU)xsD-*^n=IVbdYOdhkZ@!87{=9OD{r{nl{78P8SV zgrS`R@TKKov@B3C@y!){9=A-k753nhFE$7Ymf3(0<*X4<&RKz>`&J45 z4a^2}XL<_I2WNoYs+S2eR8yeWNzQ^~`*F~tEe?X9q!G}cZ;J#?9p6DX`2vA+$Y;H>w|ndC=5cm-+&jqz`#USOGW_~Z24;l(?;1`zP1JVDQ_yLZ2pykz7{OiYZL3YV{e#MK+ zpx|IFU*?+u68`+Z zPZTDoDeWeo&_n^%M_l8}y$GNQ%gcO2Dh5P*c!__b8xC^FN#pO>0S5hvPURQfiUGMS zKF#m{c?fj$RTBS8_d=YL+Z z83f~?`RXIRNzbug%~`&Tj(tBmVNDadklFRTDfny%Bh6c$BAKPyyUr zHOzCxYk`X|e&rq1mjHcZ26=lH6alkb`*`zl5}^CwJ6^ty5B#R>6z0xO&z^B&L60mk>Y@F1`ZAW_rAQ!3MdH&W_(52vL9{~oI0>0(a-1um65 zx+D>pI;i7)9g7FvEm!jb4lse=(~5b~`4nI>K+g019tYg(DdD}}i2)w^!RH~a!GYPe z`8<9v2sr2JZCf?*o%i8b2(X)fp7*VB zJJ1lH!mD%e2R_;T|FVj>3AlW560fyvEwH5j2+zV|HSn08#hVN81SVzBctwz<5Cc>*?SHUc`}BFNSpzjJbajEFi!zq zF5l1VTQm;%@++Lzff@k>w(R2FEBX$&&kf>vk9`7MP6*(g4eJM7+2_ZTTm$zqeOxcz+L~5?^)Ywefq4%AM-DFK`2iaMww_CPpSdQ$ z*Ks=@<5MMI#*>9SgKs$?w$O_AELjbBdu9$#e_siZf@kt5wlaWh!#{36Tm%@H^M|`$ z%mrZH{o;mxy92PV_`zMi^(J7}wQtd8E2?6XX(sQRR0{~bTwcMxpNWg2nip!Dh2PE%Qa67(*1O5j$ zTwC8=fa4QFuKn>qz>}9;Zm)4G0AF^OdwRwez^2?=+z)%!19ot7xsI9MfRxA_u0xv_ zVA}djZjY@yplbd_ZW71^p#6N7+i}|gFz_ImJFjaI04P7fwQyem_;=|T_YrO`ppO#I z#foPFX76WmYX|aJK$>>+N_&sVW>zkS@X9D19zBzL19dL;Zuq}~vv-qY!`A*O2z+%scD3E_f;#)7vHK=|6xc_zW5qq+3btg^ zVuPDM6}UAMV{J?O3trB`#V)`7z5uZk8Ou!VE>NC?#QvhZDQMBf#u{SU3(AHM$5!lk z`X57Q9u5T)$MKS*2%U7OkZW1iu5;}!Yq56iX%+EONJ*iD3Q45B@B5CB=+dDar9_nI z5?x9uBu6FC?zB#rc$lwM-u^@3 zzh-NPCTA&+9?-RVPE!=b^+N4f+;_@Y(MfHo{2S#h_qf*nX+LF2?lJ8Vy-$>V2Qsum zSPx}c)FEw7+AGQ+CRqz9e?eK~y-!=+(?JQhPtfYFdPMnZ7OS-iZl>JSkJcI;ze~9{ z9ihEnRYx%x4AY|ft0~M^B&~G)RSNbYPJ4rJkrG%NtUZ%oPB~r~pbf7+OZlPl)4uzv zp%igoT4xIdg`MZ6#goL8>NGd4cL9&GF#)6+>l$;9Ird zaK|Y|u3NOPa*tB9TQ_QjR}NEB%+0kMKBZ8yj8 zNM8#ti=ya$(9u5V+D`H9{Hw9h52f6AIHy5+;wgy@(;D#JU`qIn3C#})ic(NHrpbAL zpnNO(rg=H#P2tG~H1k{CDTlaynlTE9!ae;#b0y!AGIac{22o{8$;;^0C_Y$H!jfNT z?k~5X>`r*1sqrzVT#0VeqI;7WdkD((Nl^`8!hF10?VIWj*Gdd=dj25H|Hsx;SX zUQynMHmp)=;3r;(ZZVN+4pwxA-dQHpq`rI-D%0a?;0upJFE3_lUI8A2>ij*e@!NJU zR5+Kf$vjaXx@#s^lXd=PXwp=cCgjD{(5mrF&CvYCQ1|a?n(emdL#IYkG(2KS==irJ zjqIp4)M;psCZ$LbdUh~Qv*M9BG<+aNb8?&)itdlp++EKKP5-i8^Vpvn`u=mMrYtEx z^z>(f1}``sy6-bqbHCozyf60-eLuHSBW`yK-S*d5vwqwq)Ii5jb6~Aw=!~Aeh7Gk1wKdey z+BCo^f3g zy3%DpO%MA^ws-GS4`lu#=lFb3ua-}djr`xLjqARX-voE7yWf2ye<8k5r~K(B1H+%F zUu^zFz8ce})~>G9jxIV!mbEF> z(7VNCXqQy|<-MA0{!ysj`CCSIALgphZ4i+;(@gapZ!XzJho&wLXOL%&PpP+M6p{@$ zXBa?#~5wc-($EV@Hdw|)sEH?`x` z%?o~Ha8IzBw*f}(84gebJUqz{=Ka(H5|}(}1Xn*y0+LA<-s+B1_T(QxcXhGGn*0>u zst&ldi9A9Cs&717M@GjwsHcWjlRu={sCAZ@lCPh#RQGN)B)3Q`)J%6hvf24{YF)x2 za%tTfHDS*@=}^ZCbwchmDf{DcHBK^4YMflEUbr|y3Np}BpK2Z?E#0_S-Sw`Iv=sD5 zH9hg3gbw(n>RPX#H5>B^Ub>Znn(&UC0sw-d0Nw2|ARQbQolIAdN zDr*xh>A%<(mB?B_nmc-5^}gF}5K8El}Kg#P=cXl#Kn0q%>Nrz99KD@rB`f~at z>Du^Zm9rv;)MR);g}!)%wA!Xz<#IQTRD>u|^*>K09f&xi+W#eyl#!-V-JOmn-Db&D zpO@|=`JWT1x;I3UbQ^gpIdB_EuZN`q_>xG0Gc*;06hdlTRj8_o4I<^ZoK)RRLy|H= zj;jg_V5AFskEtw0o+Qgt87g)OnACaZkgD}MkkouTS@pcho;3MppQ^IcniM;eprU-< zL^4_%r+PH8jx+^{QLWHfL$U~sRN1XGCFLL7t}?PTB-wC7Rrg%Hn)k$~ z7hP1e%Gbn?9geE)w>pWS?{=z*rYFSPE4He3K6^x@L$;_CJqMJmU+or0sMpudUy+*2Gvx~%iI!jectjmdCZFN<{z_Y|M>>^c(mxfrJ z@>>Z&$%*d-v&xfr5pmniDP>tWmuU3vhf)>GATC-os*K%VNOZFuQck7k5z9jQl{<2? ziQ$JnDcRIaVxaWBlE*tlOuPL?881ITeBall)GOXgq%C`)JX#S)Jm~sFS$j2_D2ZrO zw$(-u=TEdKFEmn!+H?1n(T@nklTR9y@1J3a#nW|4=hp$mh0V8=gkE2wCiuD%F#siI z9lE0YJ>pIjDK02klOW>A{c`2EUyj66|Lo%H7ugXb&5D%f`c}kLq*^&(WI=4)FIN_> zG$&FdV&#O{Dx&p0zS7mgmJ>hlpF1q5DihMm5&_%61r0Im1xi}!UsjJ zQsg#8ux-gwR(X9VT%5>MYGB_8Xpq8A42tw{k32Nia6{P+p9a5Pl=T zN}qT>!SSH8QXbDD$cg~UmUt>5;DxQSIX<7@tZS_l#UCexdu~>O zQJE=wV^avYC##g-ckLq_Tx_a*vU4|~)7?mUB4#HcbDx3o?|+em2=x*rDQX+x=(7dI zp&cYbx9)F6TzCi}13Ig)-WEg%O`THQ2t^W7N`5HJNHD^~*CPrH-jfh-GNiy^!30=f zzhW~QNC?aRq_~f=CsbCwS9tna6Z{6>D6(Oj2x~TXD|lY(2oBp{C^Fnu6LQ#36pkPh zf^l=3qRMd@;lq53!oW_KFy_{zaIspzBa-hb>@4Q+k4x(nV`e|`iubn^w3R>bWo9=N zKa7U)KS)&yNBseO4&$Q2ebFa;P}6yZ>D)U!;ZLceezF@c@hVn$jXuX)9M&ib2iozU zFDewpy{-7KgAxVr^?khaR-uCU{0{!=POjqpqZ)jMlBq!4zm7lBO;x1UUB=&9bxLvY zS_R&ll&A2oEXB{Vaui>R&){bs9#!m6DDfWp845LDg1;7UNO6_M#~;j3R>)4U@CWYh zQxG$$`0_sqimn6scx!l^!a4ppz9&0I5x(OnzNrq*=7$;QB~>uXligXtE72%JNhE)gj?&budNV3>IHM@1=M? z9Ef*8xGSc5{qP_EeU2XN^ufQl2UJ{a^}sJ#0#KmpUGW(~wu*|&PIw!-mEu#e9e(xW zO^PA06&_`>LD59Bz+VkDQ>12_<9A6`DZVAI!sFkVD7;SRMumhZq`!ImTOX4t3FT!qc*(CU9}Gc4-R1sMpF*~%Lr{I+WUu;jLbm!0%FaGI5)vf*Ec3mT z7E=DLS9Xb?9D)t#k&UG%h5*&CWs4)?Lr6bg$_Ah@A=ik{Wm=0JA=}S)$m|y=AyAz* zS-~elNOW|Itf~nU(s=W}tg0*^WY5aGvI3fKNJw(M%q|HUay93e>sZJ2d4wxB$#efJS;+AA+Jf2yPG^15VfNvEC6U~(_k0=iY^ z))9w&rQITflt*J<=vv5@>#yIx*0;ecOCx5fUzyjDMx9`+o@>{;3&jbA>1fn+?A+V_3LAU{5kHr#rL z;oXEwv5OJ@L;mKWyuznO^M}9nmdmy_L;&J4C1dnfsTJ{|0L z;I*V<#mV3^UtdZDZ?l7ud!I`jN;8AEe(8{iQVsNi|)YR^^4?Q7`ZGtrkNs%-z@ zmG3JhL=-%@Ii_6FwahEH_CtvT{2UzoV^@(RRt^kK`lOcZ-en)Wb+64OefaOI zeQn-LvbTtb?k#kegv2w^L=&)NiOp&BUzxLn-=Bvbw{nzBoXbYrUbK@q?8`)}J-15S z0Ef`q8n;MRecO*F;w>aCm3z?4SL-Ci1F`6(yVpuCIQ@ryIJQ#qet0{&E!#x$`2rbj zVqhd`IDkWoMFx@-Cp0?RQdctZ4T;`+X^|wP5{AC&^GAFv$rJ7O@RvB-0gN^cpB9G> zI-#w;Oo;!K*`YHJe;4N_SfPy;kBDDbTcAJlzKVZ;G(-Q{+%KNfu0%&({v>`9y&OG@ z_#i&A!2tcbbf2laCKpynHTPP;MML~JVJn{NzP7p) z#8WxYpj!po#RCxcpm7U|`0|iTQ0gtB7*_-ca;D(KcfxIgK%>E8UE?i5>GVLcRnz*Q zxvl=<)mdwTn(iXR?_5lSp8n?}KK5l<(56{W@vuTS=#tn?3?VH9o&>v!$+~la(kDQ1 zKubCQSbPfz{d%bqD7_3K%V{&(ad&9p!EERsM&xY z*c&n=N~~oD9vJNx_3l3%=)><5Ia{0z#Jly1$Q{{%Mcwa2Aty2eJ+ohn)`JcOuGriq zYUte`2)zGX1m*7uWbJ(-VjyD!osAxgs(wTTuB>VmT`bxj2;JT+Izc7}mdxD~*)75a zl8Ww#O0NV3`l0JYvpbQ2X(Km9Rwl5(0pWF#)g6yOEwoBBeZVzP@$sVQ>;|X6Zd!$C z>m%F12+%oE&QZ(24X@6M&f9Jbw9Gpry3n~cFv(smD$HLI`17e;;&zv+bN zq4Z-w@xyGYuC*@Bze%+O<^yIo;7BCiX(W!l_8n=BcuP2jFlKLt7N^w3i}! zgi!@pa7m(%6Ow=naJ;BP%?~&+j1dXYtN^hxNaXnAbigPUB~mF)1~7j4iaw!o0`^tF zM1O}f1DKKCqH*z|fFH{|MD>UR0rEPq=)ZwI0fh%#L@&6p0oN>?L|eT63$S@&FGBTh z4|tPjBZAY&0nfo!qU9i5!16DfMAy560$9=wBJc@h03K^DI&BLJ2>rcUbfw)RKyhV- zs4Cqxz-G6xh_=BgVA9M`ya2_;+6m^$vHTgh#vnA-12P-hf^RP3qcE z@n4?^U&cH@fr=js4==ul@{4*X94M_r30FT5f-%)7Ku4o6Z1@Ul39Uhh<5r@q{Og4q z!DXm|`CG!q&NC>xn>U1hN0ca&w5vkVItj`Lcv;v`$3vYTtQ6jhW}>1>%7u!*g(&i_ zQX#e|55?G6EPUpljnaRu5xRWNK(&aK!rg@jQIA4p!h^Q^Q7cTv!mySEl&YOCG)~-w zN@8+^T7xK5HijwGKfew2RG%gc!jMq=9-IIbQb{Jhc@TJ-Fm= zF0~ep$Da596um{b;rChp?^`W|8)X`Qb#1NiY`f6^a`q}AAd%z$7-cG? zFQ)qgjg|`=R0aOeI+qF`d*u4psP%+bpC0x9vPValnsnHI8)!kGvn0iT>92XgL3N`4 zqNZ8FHII0I80V+p$&+aR`iKcZV`7B=3G43y_9BY^>Cs^UNP+i%R`XR*0S@-xRoE|> zf8_5EA@>Pv3*LQ+NLa;xo`nBLH0O)U9&?WF`wDZT4UIto(0U zJQZ|)-{`;R+hf5Os+oU8%|k)^rj`C&>H`7$hLQi$?e_&XIDP-tt#<|DPmBB?P1Fl| zj?N=j+^-SL8&4yZf@;BJ$q!^w+%-WHbQpOYd_}PTX+QGC;){ZB2_KOuFU|}6=iVam zC1rv%UKjFU##zBJn`g-GpfiFUwQb0JbG5*f_yBomNG>?jcNbYwFA?Y;twV0$3I%AR zYGijTPq6dM6=atiTR?QHM6Ner2+Uebk;QLM3vNc8L8e?T5V(vfkhukUg1me&@_G1i zLHQaUa=%lS;Cwj)8NBF-Am67Dnb>t$0O>e^Y_B{hxV1s{dx$jR$&f@9XJke9ixf}yL+k(ZL31rUD&ZA}eu2NY3bu?*`)zw|DQG)B?pJYRlYnS6;)fD!5L7A#{I;Z;3wrH8`T674 z2u7;k`JH!IDR>dk?H8tRA`m=(=7;)XC~(;I*zd@F1HnIZyx&-nuHa+VJ-^Dl#R46J zdcO-h|MKTW)qdlMdHxg2D!-gfv;3?}m3|?ArucuLWqvX5$N5n$XZ&v58RPRQN+mrpXz^NZE%;Va}>e)7TB{M%bI z{8qPh@oO%p`n|mPg3o~_`Mu#i<-?kH`&p;A^Y0UP`dtlw#J760!|#+&3qNXin4fBM z6aT;{!EZ+A9)J5$jGt`qHh=x%0KeS!T7ESX;dk!pO}^tAZ@;y&>-;PY#P8wpDt?ij zv){e=OZ?(1_I`gbmHcdPYrhkqaz3!p!Y|OQlwX52_apu(;%|Df(og$E^Y7ZX+z-;O z>wGac}~ z?{J#`T>8=X_^JZ_)lKhwvwxr9A1LkeZ5YVm|8acgi++BLpLDg&clGT|{$;NRzP9Cu z`5kxe`W_b^o@TH-4^R1#veLX<2{D@wy zFTf&(pO~QVjb9eUCl85yd#A(st5UhX#b3hsmnZ1H6)(tqo1>?Ef8HbT)8})2saHby zs=Q;q(b{0XW=Xp55l$fg7%j!O`?x@ZS6cNrbOH z!h@f;j^caQ8NyFj;eBs!2J!tj2m3CV0{LHy{C%m50sN$`a9_%#Ex)I~tn*Yll z>|6J03*Vs9$#;931%J%R&e!wKdj6G5mcIX0nejtF8+{*?tmfaXTI-uBTfsMmtnf`@ z8S_1_8~T>y8S=f{^?a=}4EU?77ZCmXbomcG<`82si}?{Zrx5V4zr1^%-w{tS^SmXu zh7jexv%D={Ul7giKY3=iJ|OIzCU^s$ZxBzczVrAuI}vs3MtEyHpCCp|hj?k#4-vZ! z26z?jO^7WEeZ0EscMz5{y}Waf8pPi3J-mNVLd3-28=jHtCB*%Y-Mqrf<%rjBI(e^v zXAy3l&v?2Q)QHaZ4xSM}hNx|6{V;K?uYgp4Re zs-%MVLT@`lBs|9($tNLx^GbN1{$LRoI7PgwtUyE&OT&x&>5F*FQ1W^XK@pL384o(* zhS)?C^U@Ms5cX67ub|HXapW|YcQ9rv!tgYU=kam2SlQ zHUffsU%4kDMqy7j_j5P2 z4Z=P;_i+XAKA1P6m;3p053CE{!(CzZ3RV;ShPzJm9QG->n>(-D4kPDwa%+#Y!1TD! zxM5%K!4|X~+}6l?7_zF3YyP+z*3#I@MZv3J!p>$c=29iBw7-!H*jxsipK0LsbI-sO zhPS!73kulrO|{$~2gR^+t~a^9AGxr#f!DeF$P8FpL=`vr-YM9F1DCjX*Ap=Pla*Y9 zqGK?&xSXpsO@~ERlyX<(rNELKin%dkiLmBQEteV-58FMY;xgN#VZjS>ZW1g4mbO;P zwW$n+^*M>Sb?fjjIf~B(($Fw*B!`>z6A62Dh{-M94TJ5X)3{~NJz&m7h1^0vSD1fI zKG*M(BTV(|1h;#GEet-C!^P0Iz^rw$xRRgiVZ@C`xDD}ZV2$qS+@_}{uq@&sZV7xD z?C8D}?#_xOu-gUuxzlU^`UGndxk&}HKISzE+*@N4J}#Yc+)q)XKCH2w+`*PX9~Z-D z?juN_kGWkWm#XdYL8HRCTMS?M)b9-AiZY-39LXVbKYx7eb4*U)n&Ml0?pB9z&2QcF zA#?_F=dJ2}ti}Vmb?j;%m??_8eddaf%GvK99iY<39}nklZZGw5IRNDnJkR*VF+I5v zMGBv{6>eN#L$QzIkt=sm2G>VBobK;r@pYq9Zbl|2`<@$u-Y`JIFAM;5| zw&q?eIPBBS*}|0$C;ObdV!{1yTcS_e^Yz?6x8r;&Ce66nw$VOzW^1@FIpIFvyjOCU zO_P15{xjij+==rE%roLHZ3*&ucXlcFg)`FUR*N3@sKm$T-8UWXuix%Ifu@VN5eXol zDYriy!DE2Ww;gkwa)^zO{fQZlLb2JWqGXD*Z_#?6^he{IRf(&83cinV6dlGsuh))n ze!DI8$$$@WU`idIh}{F6@I`;1Cz+o)#Jw}n?^i!^tlGz+WpCbdo`XlA#f#r@cK)kG zd;z@XwEX@EO`&vgjN;!x;W;ljz}7A(rSvJs5%>&xrK6prD`0vcq!MVh^-a#RYZ@q- zc%8G~Ob$)SuHt;m5<;J!yTpOKXG3%TS(xLHG-&do^PH5Dd}xVt8E3oxaj4aQXF2PW zjzIhAXE=3_4?%z2RCB!lEuMeBf+OVbfxcNS<2;(!1+77eIq$bcLEondI2|{)K{3T# zj$$1NI{%Et3CPAmCl@g|kKP49-M~~15aA20jXT9Tp!J4Qg(o?*1qf8pl*>68>kOTo z%I0iuw1^K6t-t4 zV?osBXc5SI=#2J5;?!?JG>qD;yA}QJoL_0V>oY)-S;-@4C1VQ zb=!M-Spdh;h$NW2_tF?f7Oj=jE;lZ@slE|6z?)Csw<~;>y>V=__p|Ju>;%ku@0!{PHuLOi?}6FxY|d|E@Bh3<*{R`6z1JQ4 z#s*gDcyFv3WItT?$7|2*7q5J?!_X176#HzhSqx ze)L-G`--iweCIWt_mUlu)#U}g|D65!`BSg!x=-1zj%{AK!R_qyf@Uu+^ATJ0w!y2v zqlGPm)Or=JY-Xo0uY2v^-pID^yW}NRG_V_>=e-O+)UzRivtBLMwd~Vh)m{%1Z?dcX zWL_&TU1v8*1zyDyRqV^7tba3lnSC^n>LovMfxTIE((6z2d3MQowpXRmIkr9~)9VbS zgpJl7^m?l(Vkb-`c}0KHuwz3KyzBrfwolPcFRwH?d*bH~FJ7&LO~ZwGx#)=4b43KN zH8?&SKOOA#Z`-qTa44@^@0o0R5!@@?p3YAH>FISO?KB%60`|IBU%>vXb@HOuJ=CXRooW^8~F4 zVNa&r@Kh!Qv#XjedlISx+4!{;p27MkcFW!pPkMwOdvlG(b7cjby=|G?^V1xZofIYX z{Dt>oM_*uj?l|MlcKJ>9To?zlKj8B{M*~6ZWKE8zwH(NPGn(mnW*ES>@jc|Z+s~d& z;O_T4D6(O1|B&E$f6$5zbJ^t?1K+}4bRyEzPhi0==?L>o8d%S^-9+?!3o~a^lQEt` z!5VgRJ<3x!xRTvxi12)iFlB#;^zuv+FK5@B2YVuim$B1koIH1;4A{%icAm`&U3Q+> z((@nth~3$@!E-Nmfn@+*>seC#o3%dA)YE?M7t63?ndby$hV^EHuBYC`DHd(tUyoS5 z3D%mMvmQFTzO(X{OnQvejIbV&M?E&L{>GZn40^~?23d38K6yku{KER^)#DMnwU2eK zu-l{RL@z7k`7@8;w>_-(O^-e7Jm0ch_CN3-2w$;MZ{GE|J@%5t)v5D1jC;Xi6K{AN zI{%cFq`d4=t=GY_9XRh1u)B?Q4_xA5-q^~5=4w3Lw>)48AId!Bx%XL*Rtr4>d+xG6 z?qqv-!|t%UDySam$~so%)Jc!&U$emNeEk=3jpj7*Q0wbxj2FAsXSY^Y*g+q~c7 zS@tDX-@XKox_6bVAJ=wzjKI&cKK$O{u}53Rx_}Pzuv=8Zir^DGK=DPazBj=hCz~}a z{8p65I(rpMk_`8lWyo0#)t(+!qY_rjUsn%4S;V>&?Bs#D!DprOZ9OpSxU6+=ws`Q4 zvsh}Y4IZ06(OHZ3ukrX9L}dkBGx1n+;S_7{+)|I675S`0)DjQCkrONo^N+h_PY!G8 ziy8Nws4Uj`^%L%2&L3gf$BnpOH_c$3K0o08@JJf#{`ZgWb{|q%y`Jyf+k=u>J-J=( zb(fM@x0;{2e_xx(N;hhAPdSmmGNv@UyA8&%Xz~VkBzYI>(}x;&No_Q1gY9*9x2;hu z$bn1l>o^fC$E)S;K{MM}Iy1%Yb#W9{EnMw>w4KBv7f9WYdl6VIt$g>kvmq=CW0w0a z6AUYqa@rl99mLuz%X5z#K(YSo$#Q=}L9#$r8Sba+5BQn0a53xL zH(g!Bn*aBsL1n#)#p+w`9xpa!&D$8bAJR8wg(NO^Z#`zn%C4Aq+dFK)VhsOuBka^; zWjX(FJN{gUg*o`mZ8C5XYqsi(+x411OxnZ;w|d|_bH?qBn^EyB6P?-VRKnF+%Ca-nWyI!ZtJf1Ff(Cdw>HPOOmq&{?ZMes%$Yj6+tQ6)O!{1b zn^^RM`3susmbm;G6PI<=?bPWGW^PTI+t^lhdCWE=ky&FRIqA{Nxdfkd;%>%+_uHG&R{#%x&C#5XGV$%*NJuNC<5^bH(BqNPtNg)6XXYa#})W zlF~yVD>f0C$cs40=TaPVReum<0f=R`Y(hd3s?p4-a39D@-$3S5t~*4()t_nG>H-NO z`!S;z93bs);LJ>~tq|32A7<*oO_1xOUQA56Ib_W-52kMKN=So_8?)GKIi!l?%G^xU zhYYWCVdkD*1W7G*V&1tu2Zp%S z>H73NIQzQ=^OoLg@ci)&%q{R2;AX>h%%sEZ;BNU^rucjd7;L|qS^VK1_+|A9CT~qW z_+Fq1b7x33_-CgP)8yn8aQg0L%%bWFFmzI%xq7$+j5(#tOtjR3i&pC}HQVK2|I!7< z4W;BaE$}1n`ZPA%?^5onYsvL57KJ2l)Hw7e-eb1w5DE$H@DO2NTRbGL}Jt z!9$hr8AtZ`gP;1nV>HWQ;6E>4Go~JUfHU@YGxQcfV7Emt8M9zVFkJea(UD*S<^rEG zPRTZd9h%x18{5`_mq)cRB)?aIy~kS_KU|E#m+21}E^!9nWXmQ7L9`g0UUQE@crfqU zL~dZX&ir(Z9;#W`A*gf8z#&edmL#l6Z~rdhE4p(bp>s zealYQ?**3_YePF+X`3!E^b1;D_tl(dyuH@wDhNBr;C-%l)%{+=uv>G}^&YdBaVD_J z^?}_P##~0F>*^*o!>g>+wQ`q|5#FVBW&V~iBJ>ol*A)_mkB7+B)=R`#NZ`1Be932= z6VqJ39Og1W&H1k2m28G;GRO7d6$az0^%2){B8_2AIpq3uw2%SF-|yN^t!R zJjs~+u+w#+J(qF8IMNlLlEVmshq?9{XE7T06I>fFA7NN3f?bD58H~7Af7ht-G)Cc1 znCn{6K?Y;1r|UY86h>O8tLvUu`x!oYj;`}r`xpZkZCu}4>}6!W-R!D!Z#QGWV7+Vl z?l=b2W3{V`!7fH>ys<0zLNtTQGjKgYiej9+z1VflR0JbtXdW~v-_Ecwn+93Xpvj32EZK*}yGW8>6okn8bahJ$4%XvNkb#(I1Q2-=2X z3?FR;T}VSRib@(miR*nC-cRd62O43FYjf40+9W8$)UFCdUggCgg;s*V_3n(c$n_H1sUJsd_ocX67gT z`Fnkk(fLVwquyc=EOMMKah`X%VfdYn+y2w#=eOC6@Y`4%qP8MF{;whxos6F&X_p-@LEgrL(AqKFV!z`LyjVy{P)0i_fyx zbdR1omv?u%=$Cb>U0M!z(hUJuT;}bc)3Kxqm#p_s=m#=OT#%x6`k{Yvf>3N5J+e{e za&e)RZaXM&A>VvJf4Q9P;+xV$PlQliGHn{^?;}pSOuuWOd*)`l+!NiVA3mGm@)B1^ z7q+IlKy+*9l97EbZ*Eu9kFVVA(w2Fhj`oak(FI+lPew(!(7#@$7v_b!Y(IOEK3jrw zNsg|hlOG1TbeNr|vqt<}jy^A=SFZRMtFTMx7v0@mDuRpYf*md{u1n6)qmDbcEWWFz z8x&c)Y|K&8Wla_?C%xo!qd_wl=P3z2-f*Rh?Nt$7<80)zH&sBdC+oS4JMrju(ifZ` z46*4Y(qGP>%bE1#+DT{JUOIh!bs8!El>@1XPS=Tr2}R(;Nhl6?A+fF9?^@p<%X zd%B%Vt#j$mY0sQn`m*U=6>ZLtl4JDSkDHzUk!9)B(FW&1n+&>#X|1#CKpMT(^}6%@ z@`H2)<&yK6q!hX=z1;bM(*b&yxY*faY#)8PTIKw`YA^kFx5RlOJ%Qdo!*fP@#nZ2^ zV>-W@+eJ@+7CP57#L$05o^bwL@E`qf_A%#(;7IyYq(cES!0^Kkba3!E zFa=>pH{LT0e6rMr-cisG%zkM_Pb=yL9xU2IpS$x0csY3!J@H*9&D zA6xqnXy0i@U+Q)r$SYby*C*cwB2!nYr2+091hVFS($2k20%F=HY0IW}14-I(8foQDV9}xP|61<=!UINW z%wP)8%50dH7mo*$hrZHwS-Ezn^WnITAJn6W~W@pEgIudgVUMi)wEZi zYMho2UZWY#U2|$~tfE=1y5#ggeVMk|vD|6pv5T}tsA8vcVU@JjNR<-}be@);CULrI zbdILS;5pfTEurNUF`T|M7t>zdI^{H4e1>NJG}p;LPeVft9Ci8-t)gN6q&crR_LPbRuN1Y3EfKC&V@; z?fq4h(@}RiZKf6OG{1&Qn|bf))b{fft!L8J>2r5J?c6daCv;67Eqsfu)085YHtfE| zX(T6ywl`$G6KH1^t!3A0r+Va3no*{)lW=P$&68>1bVEO#hCZ{{$@1GF8vMq*V|Pa? z&HT|%$L_1iwAb&yJ6cKi(@snbIo`_NM>90|;wasaoyW^jqG5^BG7RS(@|7dn6?>Tq;a?9IgT`-XvoAYM}rC^?R8eVV~WU^ww;~gxcLN}R-;XHT%Y7aTYNRnapyK~ znrqX4j$?kFw4ko-j*pz&X~;p66f7J2ilt zxG5^BPX_pmoS>SF3joocKd9FhSb)vIF{-Z#6#%pzpq;D7Z^S z`u}nG!MQ_CBFs1}V%1ZRMUFc}(QB!xdxjkrPT!*9()u07PE}J)a(f*B1=p!H^fwNd zPhO>lh&vrlt2=PN}Gd#zKeNrxnyxbGCyi zT}G|7qB>k;N~pt5CmqBb5mnbS+o6>&pz0zs9D>9=>NjkvgNd9&tqI%bV6A3RQ)1#B z@{1T$!^CI@r!pFqb12-wvhp-_CX4K_>&huA_Ed<&w;TD?e0HG2-MTz#vBcNm|q@TKa>4b_2h4Rx%ob-aDLhzZnc-1wq)EM=#)V9 zG#a+w>k&`=ysF=R*e{lPbVILweaKGgq}3bySKFhh;ebwiL|hcL*tNrcEO`gD)2r2f z_*gh~#JABNa(WweG^pObSwNw7@rC7TO1XA$=@J0+&qe!x7DByTNo91YomehxdlZn?5aAv?Ds_69sgAOVEsL;1_44_aqO1?qQVD}vDsH7%MgLGR- z6r)vSpt?aLYFh{2pmVocR8}{~VB)xHRMk(Wf!A4;s89V=1L-{Fs5iq?`cq{}QMdk# z>M#4qi#j;fuV3?1F-m`?SN{@CA*z(tssBR6iCV_^s&BqPF6uI?QNMpBD{7SePJhIY z88uJwwZ6k)=_oh;3;l0rq@p$|m+M#MQ==S35A`Q1XGnFmBK?Cc|Hu}NTl%(trpPF* zYx?WClcch4j(*{saq_f&y1uv57&%~=r0?NBLR!vA&_8=@hzy<=qc2GrAc^^e{-3*j zWYhvgU$y=hxp!ft{)t~dNPF`L{S~ZUa@rz9-&wz#ytrhiezJWRIoHZh-^{;*%(C91 zF9L1k)Y1+5t1?PIbPi0w-KGfiJe%x;DL<%!QESiV$WTGUAHSYe@mXGsIO z(B4%4%H|K`4|`+%?#OrKNe5m1{i*dN*HJ^??co~|b(|G4|MHq_a^&f^{;eU!PHg=P z8r7tu6GK1Su8Q<@qUaB9e@=QhP3pywm87}Th~9x~Pf4m%pI+XpC**y{9zDbUQgXdx zyWSA*G5Oh{S&zB+A?fVUptpN#37KVIuP1=_$*(JF^f;G`Nal)XdTVP6NtNYgdaeC; zNSO=y6WwkzDI+J;9x;WU}Q2z1^QKlZ++j z^q4c3NFR%My&?S^GGoyRJ;OEGrjB#SB^>2_?~PQELVs(+B^<>I9Qg^3;2l*== z=%#wFB@Is=))ghXlWXvOx*b)kN#En4x|9E0$<2p$>3T16A+5swb!CH{NoMd?U3!iq zSsJ)e*X6T4>Fv8l_lx2Rvdhy&w|J!;xp|$v?l)*d7P&6d-SA*3IcdLGS82$KG+wqq zS2D+vbg-DCdnj-*={#RgS2fd|Txh7N%W7Om%4&&p9e8GBjfk&Xv)Yv0&*SK3M4ON@ za!lPv6>~{aimIzSZA|`}n$&5sG$L(AMs&U$Fd!p;_30QE>X8|pJvvYObjTac?K+p| zXp^}gnspj>OUUTg4LTlIG|2VO>UC5*)kxOk8XXgDF`0MwnNFOah+KHROvf@yNM6k; z(J}ohAf+!9>g-cjBHhm1(4qP8NO0ncPD{EXc>!eWNVUk5*#|G^98l+w38Ck77WvAN zL4ol)Hd!pvWa|l?bKjU`%Q{TQT$@22Sb0oGCy-A5u{o&YeT7B_n(x(V@1c+n=LG58 zoijsBX$9)k@A*gQtN7|z7ETe?@|$(~Mkfesx`$4m3|C9ZBB z)OOElCM?{3YH#`3MBHB9rCqS-Gr_lL)!u-7BK(a%YdgIBNL8-lP4J@F~sF zW`(^VKHf>!9(eSOSe%=rt;?z;$m9g=OPih&r7W%W0RorW2{&(%QVN z3&an%8Lhj+DTIOTgjV*-WMYl!tY^rs>mhj_sYni$v5-w70TJBj1g!)L6 zR`F;&(cJk#D|B@n5%uwnR@kLjLhZ#%t+L6JMEd;-t<4@M2$`#owQTaEh;7ODwZds6 zaWVRi*1#5=s5_Le_2@22bnnX5ddG&uPtQy(i=7D3c z(f-549AT7J>6=5uO9s@+G&)GE89S_1L+mFiy7p<=e~TcrK89+^EDa}SW$?5_DPctR zU4N}ZBcVij&Q>kSx)9>^nT=Y?w}OagaE;bxx&Mf(VJ=$TyLS->eC@TKzSu#`cUz{_ zqZ>$kuwJaS72i(mFkYag+U`fRsm#&RpJgDsF!i*MY#$``#Fia>l7GxK z#F$5qWNnZef!MW6`d_aihUPU(n&!I_>%nlzS0KsxWkcLcx-J=5w~W|_UzWraTN7$~vm|@ft%ySJ zRLLcL39-=StVHLB1(9tYC+S;jPE2S;OBf{!2^)D-60B)PgiRiih@(x3Q{VSXRQgSb z^Y8XZwtLPaV#;<)#-Gd~g7ddanhcGJB}v{AR-z#>h;EV)Q~E?w=vv9D9eRX;m#bu3 zoeq)f;2?QosZDT9Z6qPN5+XpnM6yFclgMS5N%D`V6YmD+NS1yV6Th1EB&r^X!{ z#Ia0;=qwaT9vcgZiVVI4CJTtT6C6nbU5Rkm$CUgE=MmjLRLS{PMdIMfDa{x+1!Bl- zRP*&C4&kNVuersTP26JkYMQ6Y5`Ba1n%*)jLfqV}S$~L0EPBzPnb0jwSly}D%l;y+7c@9A+$_0E^h{p^(@hRtvZd*UtXx`dFn6z#Q27$$@C;{t#n1x zWA6l>`!7qgvi%P}`8`z=ZXCmx)}Pfp`EmpgdJw1CYCVjTInkQf?Lj;)7S#;b8Nku~ zM>TII_u>9N2QaO3&7CDlWzcexz!gv$&75-=5VlxnG1U7sqKR zTinGt8POUp_Y3er4ArQyxPw>hKB|#id<%!}2Q&(n+{EWD3eyliypBH;{iji5osYZD zY}cqMy@r={dTR*nuHqUsn>6lJT*gCguhmF$%*C&sbJeJRnS<9IcFFVUE{Art>>Xr^(tF&)3pnXBRGlZInMdKwPxskqfAO^t+IDfqWXA`PS8N%;P3 zzJ~n1^Y|#i(Xg91iwFG2)OZ3C@h5InjTpumT*holJtyuoZmT@1&J@Js0kefTAEckc z4}9%WFVT&~4^*_POWiz)Z@<#4o@RamUmDY(4$Go&`ks3ALT3_xxUNRs^evA2nm<#Y z+JfQzDrM^YE{KQzEmn^V19($wfx7YJaePtbb#+7X7=G-^W%d1vNAZG_S?cWc!}y1g zRP_OaNW5#!S#|BAgLtP|occw(19-h4T0Nw8AAWrtsuNox@O@v7sP}g7#f{4LtEU|Z z!(V6bQNJLy2lvHyt9P9V!CQ80S3fQZ##gQMRu8!SAAZGnllpm^-FQEHt-8{iow$C# zi+Zci4t&*Hd-d_(0l4qoW$Hf2cHH;;Vs%9Yf86cR0(FJ#ZMd=59QCaWeDP5$J@t_a zZ~T^;rh3zct@ws%6?IOx7v9^-Q$KZhGamAkt?tG4#9MM0>JeER@nr->z0qs~9rH^<2E^x4YV$-E(k*+LdZabYpz`jTLHc7Y*@Ku}jrFYz*+rK^AJcU-a-B zE~aYshjsBBLu0l1LLEGcsjIg8o)+%)U0tnjy#yCO7pgrS(!gI`;;OZsQOAR@*}^vq z)bMdXX*JecRs4YMj94*Tgnv_?5C?KqaI3#VV(CI<9B=w19`O+14@$lKz#H<-A2K%Q7}9Rt5(cS)Q!O2<_-GQ|5XNa6dYW>xrXY51eY1hHHf z1s}Q>BYqV#g9*b9h?%9G*rL}gvG~6ZY~rev_?Vy_yNUl(HLm!Et=;xVRWGa+>#!PB4ORP!?NI)y zN~>wc8U{O6yAFN97T11N73eo%(bpPP6F)R!RrotqZ~PNB=KET8zgYvOWc5O|vF!t< zEhtxwIrAQq3_MUhx%?f*d39Iy<6u43d-wA6`}6wEhhizV)JN480apw@6c! zyZ;I+Ry?ozc~=d#;%B_-sHhry{QQKf@9Qc|KO0k30xvLd^b&w!$H;EU6mMh z{$5o^Y6WJ*3Q`?h{S;f?5uj>BEyr9+eN=DXE5nv2d#YkVrI=y(I@KJ_$JmVPDpiG# z53v`zj;b{=53pm?HmdLJN-&+qC8`F0?qd%M%v5V`-otET=c+yoEW+*u>Z|?{-^Ii> z5>@nl0TwP)RrQL!gWVtCt0MNdv0v33)q$y-821uW^-j?Z%-|SRwKViPHh1HcNNA9c zX`76So_xE8F`50MyBDrv&8tG7Ap&k5}9ZxVo^(>=v-R@ zW}|dOZ2+u@u2>-%%IQsK>F;XrU}z*Un=GE_F)UHzpLCE3CDJEzp4Crv=@u*{;U#( zhhf>J?^U+1+Jjv_TdNYs55>~{t5Tsi2VjWBc41`FHI>eq9hf8}M`hmmK*njW)%~|P1prn50#x`8!&&R)ha)qt;a;Yjw)qmJ+R7BTb0)B>oA{0OBFY> zwOH@Yg(@<%HP{a8c`Dp@ZrFPT1C`x5tFZ;05*7BoRTx^LsxocwidCFaQduT&!AAV# zRcgLFV=Cq{D!C<2*jyG(<#miBX4Wz#T<+t585N8Q>8AD=m+Th`q*h=*HunnmHP~VI z=5`1*@@=ublop{1VuPuFXb}2(EW;jOtrrgKFU3|Ltr32lvchWJp9$%2Eiqf|G9h|p z33h3;Sh)JwVr=|nfiTd+0<%fKF03&$#}0;F79ukXv8)wYLeOA_Jrtx0-`re)z3534 z29c)Nvqz_d8+_(tcjKdkvF0Y&Ie#crl%I#~Ty#X(@qG?v#N02Wmm6bWKZgp#Q;jh4 z#xCK!eTJAi@E2OR8DLk}Z575D=wsTt8-->xJ?!+DyHK}92kU#eQW#L8joGBF5DuQz z!eHo9;p;F7R%B}-99^Y}edd}9gAFyXfes_#d}(!T;+~Gsu3d}`N2?37pQvK3UP7T; zh6pR2!xcIoRl(x^$qEy^gxH!ox=??KGDf>Nt;`Y%u&WW{%2s21%*J6z`N2mXRwekQ z9CeS2E${A9&OWb*-70BSmN}?^v12|fmu-^Aytlqre!7^0WzDTs=84$Y`+qN#3npc; zi8tlSnawPWoBdF^u}lUNhZiaPU1Vay6}Obl2?i$3zoxu-mo(PZaZ$P2m5vn`r752< zk;0CW=atX#Xqefi)5`s06s$@Aq;k@i8Fc?2O!-v#G)jGWOu6pzKNO@KRQ8Mgiw^AG zt85!Sg|4>@QV#K)M6a;|mA@~WKnFhiDBsc@M~(75l`G}`pc{{@Q#KeLMfbU`Qf_P- zL2*?_vT=#hs@l*`TzqW&>v%2$pJpw?UFDmU-wM;XTY%6@D5&}S2x z%4U|o(F4^Y<#js0P?c1^avA3*dUH2N`S5rzx@ZYg8SUsnZ!xLLjc>Y9@ux|_v4`K$ z!&gQGd#-e$uMYGHZYFl3@{TQV zs1;3KTP=vw{)(Q|tQ7PqwxD5sj|J&7Ur^`L`+}6dCX{#Tj-ajOGg`MLUvRj#5d}uM z0^ib4sMdIfAn|4cTKpnez|Z`M+MGWlXp8@VJ_v{vOoR8Rz8NX_FZ>-EMF9e>fVb%9 zH<1E^jrFKzMugy~a~Wn*u>s<`eYD5e0!TsSIs%W(ktxN>M9;lpv6Nj7GQr zRRYH!p;foXlzI<5L?@07C}rgve><|2GUwbtkKIXCN-?~S_8mK`^i3}x-QW_ZbWkS`y(NfN^3uA7 zPPRd%Sk0@b)vY5+avE3A&?Ebm8r3eN=bZK^jfiv6TfE&$KH^L08GNJA9R%d8K$7h+3HI2bCc2dV4+gz{3LY3f~%yu@I1PiCZ{A= zd=Aa8r7QVbpG5~#ruiebiKublIRCT58FcgfAwJtR0X;nVlOMO{G#dZBi|@TL9!*YY zUQ7cdnS|UlY*;!vupx&J9d%3H4jJYoznPk3o+D*d!C>47)1-d#PjoB zKvdz%3BK%GfNtN5@gICa&}&x5`1ijbN89NK`P89fsA63hKkeU9bYbd$e2jGzbqNUI z7YmM{>*x9Kt+WrL9)C9R<>p7C4o}ze=PW&h&WUy9r??zMr8he8H+UXEKWNzSeRk|e zlY18P@9o=%x)(0sZ^0taiKBD)?q|Z$R7X92LiXNSvV|sJawiNeYEywt_J(N#L# zydIZbXwa{3Ji>b?dhA{kFDz^aiX$I**RVhoIKSb|PYOW86kqb_`PKYmB+OvEYXmPOWdF>Q@%bt?o8O-xE8y(i~HC>8fqq1he_*1+Eu&_hu9H_a_hTX=EO1p1GPUeR(dr zFVKnm^3@#lim@HHX~-C@8?fYBsT!ld?=R%`EH^?a$LDc7|1(5c_6FSfi3TW>rNw>u zP#>LoqsqPAp@(*!Q{r~A_0Wnf^4#4Px@eL_hHK@ggKqmyBeZGs) z%*JZPWqdI@lToP{VyB933Mf_V4Hco642uR0~n{yZMS1)g&M0;j@zJzXv5Fr$dFc6dq#{qiL!*>|Vx}V(4fztO z7^{SSnnmfM(653hrg&urq5`RB8MVj0-4Ga9Q{V&M~;IuyoHD zEdP2%WS*!X@)?FjX}w<}Om$FVh1{c9|$dyL7|T z#)b+#G2fxjZ!LwC*IiKSj#wc{z6&--2o&1acEWgb1%=~hJD|n5jKa=_cKGojO(9d% z4ug;XmDlxYgMVztsRi=uvKnFK z*6Z@`zkh;_>X+p&nS6p>t(o#q4>rKwiz)IZPd>tqfJFIT=12HZ@09%T+7Ga-o0MO5 z;XTaE1M)*1@8JI6!}8tp-oX{~_Q@MZzJ<*G5c$Uy^|12JPWcQ@Jv)XD zz;}p={OZzbXklk4zf7(go}p^XAM<(%J1fNUve&Ah2_ca09(w`992MkwPA}k921`En z{B!uJiYC9l>lvIr@s|^1{tT+Qj&bV9N@ylGz`+_Spxx_U4q;FM9pXATA0nSZJNFjO zzM68lNZ}L5Ppuqk*4J~=_dJ2LGc_E8r)98t-80S%zYN~wm2nJqmBNGXi#Zt&AH&7x z3ON4qk756Y>zw`DAHgiaWzNU@51~^-CWn-J2)mL}IJn;fc+@kIQ-7}nvQ$oSLgY%| z=|+;X$-fw~QvoNw_&&tE4s!(Z_hFxCALmElJ-EIpgd_jB2;RQ1lY{b$pww1B&Whl> zaE*8iXI*6>O#HH*b6Z>pYt!5~-unw6#oL+VS$hZ0QCrTrsDB5#H(PNm;cd7(eGx~} zbPFE!HsNesbPJMdhMdpwH(_+M7Uz2J4Tz@ChMgR4zUz7)bZ2ilY0nnxU4gNx zE$q?G%Wz&(1N)%;WmuJ3&vwkog;P&m>`-~euJ^kHcQlr=W6N{kx8!2>c}WiR z@GM~eh8JO}@^$vPwrnVA$Yq~gkqwWY&t%tL%7S$pQrLddSx{9ek-dCZCiHzD%MP#3 zfEN-;cK@6VSho(aAIGP|DaFI=PlIVtQXj!yzA+8joDN}6mRx}A-FLF7>KC9t$B*ra zro!E?z1UM-DR5`(dUl^{3iNSxW1HSdhHflpcDW!Kn!mJTXB|y~f@mxD>$dZ-&v6lZ z<;wH0oNmJA-#!OVRvNJ9DxZU^F)jAl<7XjrxtQ(Rl?WfsD6!YLCBmI$^6Z>@XQ1qH z8McGQ8FmfXgPQ8&>1u<|omL>O2JqA`87RyD% zoP^TdcjWy4oPgGs^W`!FPr%@STsh-+(eSKRrku20G`!cEEN5~n3f5(uk-MT61>3g9 z%7w&|@VAJR!zKwh^a+vc`j3DE=Og7(KI8EF`UtsH7aV@%hRF3kz+hS34!LM!3}(e` zliQz$!XvA^zhlXN5p0s#-0_9{{kGaFVm$4q(O#JGp`n2;4}qk~`>(KAEnO96`v2)$W1hd_*?HWe*Jfbx5}4c_>_y7cRSgMJP1h87#Z>NeGMJ|>AQ+xY-z;0VI2dm9@{k?A7X%fRSIh2P6a=5YbCfl>`ybqQ+E#Y4*?&;H z+EO;DU^gt4Stx72U^m?Se6Fl*!7lh4)t8M~unQiuk;v*6?u7Iykt}=RP8eOxm$fh2 z0j2hHWUI}0z{93Y*^J^q*z=1bTW%Q$J@O`5W{(5ly&WU0VVeNR*Y0D{Dz?L*uiY#^ z$L;XZg*Fzu+8;7Jzp!N7{NXD8N0!H1KX|h44eRGdKUfj_lJ%}>8yt16V6ptRK`r`Y zR(zK)Tv>jPwLRDu{&(y)ix~8Q#F9ML=pi4NGLpl(H|-6t-brUYBfa6BkR+BC#~a=? zOklk^w-w&$Jjr^gwiRB@##y|}TVSg9aaR7kEs#(-#7eyH1%p29WmVaFL6?Le*6Qlb zP-k@@OLP5ZIL`ECEuT$Rcv0!eD%|A>PlI)=h@nl;!+I499^V8N{y4B&WH!MUg*L2{ z=QhH~Jxf@GWFyoyHe=P^*Z^y~=CF2HZh*lT^;oN4tcMIAO%}R-Jxo^-u^4S0aP9{l z>+>EDc>gq;HT8ELv|7br1;?&~4;d8J9MyGjVa0@uW!_qN_4u$%(vr1M+48r{@|SBM z82K)R<1IIuN+|QsJ+b1 z0EgN4w@hYi${rpIUMv%T&K|DTUm$Z}o;?({8OvOMu>!WF>B^Y;t$-PuG-RYEmqRbE zij3a541Ijo41li5^l2lp(Ome~<#2bKR$Gb?6n;e-3*%&;_D=ovo53|edp z2j=`@-hFQa$?sjv)q8EA(#2NhB90Br-1?arl)nt>D!*s;J1>Km>t8b~yOu(&*cZ$$ zd?`$EEN6OZFNJcHhfLv9YZ&?PE>qvn8n*4f$s}g1pyT|j%mrCi@N#c9bDpggoUK2} zJk)9lH~F4pDnd(mRVAJ|F0q6o@1mLWE0(~eaVYa%z!C_Zk1|h6FM(y$1I!y&7sH81 zdzhN8i=oNE-OO*lEZ{cN?acnu7Vy-MtxWfY7O*IHBXg?39Ded$!yG?i4#!knnD(0H zko$fGv!!woG>BWue7<`TT;goO{Kr`Y9jT^F{O&^N{>X^w<+Tuc9MEANpD}|T^VOOC zm(8GiuQIb>wHb80q{yroUH}*S$TGFk7C?O=omsbH0aSeZk5T)>6pqFGVW^xng`XS- z8F#HsVbSytMn>m+7+2EC_!u`IZjboN@L4<`n$2xwENnA@(_L>Fn`2Gji>z0SSLP-# z#_KsF{@Xn0!hgcZj-3akYfBiE#q;3fs6xi=_PH?3?gry#{9LFpd6_Y3H5XRj&0-{V z&w+bGQyK8w9LP5~%Xqka4lMk3im{^K7_Pn$#Smo}!;aabWxL849^@Qh6ipaGdeuHg zt;IYrn zjEG1B_%m@iL_Lksqpu4~PX3jS`l16TSBy#TOVEK! z{`O1XcGQ6p_j;wRrnF(+o(^fH0&Uo0&?3Ebmo{X#HAvr8*M>_j)JxCizd-->HPWYJ zwO|zcne^}qEqL{Lsq~de34D$eOJ6ONz}CeD(&IrAI5vmGbvqrTmza@fb{t#8qoAXr1bS+b!Zq7 zAsiS&v! zs?a-LReD@r73w%EN&kBzg55J5>9wat@LCB|dU%Zp?g*z!cPfgY#CVFX_f7>iwvW(@ z&Z@vuX?^s>jVjP)Ll6ClPzC;Cx6`eggfRK}7dj(D2EB%h(5xtlE>IM}MjuL$8eu$nq%!k&@ zaQf9pe0cXs5PcfwL&L~GdhTjIykP1}PZjW?Y_BK1@e<;SD{y(jqQ|ftqwp3KxD< z6VW4ID?-DMJi2D8B0L<&rYrAMgjJ3Vy7xjw$eWl)(~t@kISKD<$YIeUhsm>CN2 zyZ&#f6Tu45u=Tr?mz4tCmHbUAlBEE1*EC6eZh}6JS^;aD0TA(2Y$;gk{W%)fgG<}Qn7IyxR`rQDtsFU`c+?)y1ak`NiO z7A4wCm0XpDk6f2YeL-a56WU@a_f4|!=|fW~1(R7DVJxM|nC&;#l|sI<;G-E~2mWKhTv<6OMSB)Zt)NRysIlOwBhxgqKQi#R**NXtTNxPgW000` zLk4=~{G{EFmVpjix@g7$GSGzAO8adi1C?tUX%w*x{ENP$`Tt?UHp|yE?gu8U9DGhw zEMUUiyeBl@cqSzLAJC?Pnb2Q!m)7mVgv;LEplKU2q44At+6@L14%lVW$Sww~8c(I& zc*cO~ch1suav5;%?l@Wx&VcrkXxhI32IMzFnx6v$wx2#iU|!{5c)AcN)^n^64-mU7KcpnhrfTsL@XBr$Ys{ zGRYKwor?YNI{C_C+eO6DR_OLp1Oav6x?{NhFWbd1*f+?qlRkE zJ})ez`mv;-TU{~r;xG*kM-@=bzS3Z_&2=iTng*@Ma;bJjG}v-8lUkNVgJ4GrH71q@ zCF+UPD~D+C$%j~~VjvCro+7E$YiaPWJ)pi@MuVwSkyN8OG-!S|f?B6SgY`in)MpGD z4AS07l^LZ%sitkzv<@mvKjTF`{*DS4xvZz&dP;>g6gR3#0Tud{I8py)Q{h;c9aVgW z3S$hcsL?1DYP2q-+DA}fLDD>`djJ*MyBkoiZlJ=C(puEDPSn}Bg(}r~$?UlOO4N8` zDkSI1Q+3p-P^ptil~JU^oHQ!cT8auy*H2MO$0)E=c9atTg92SD`Y5-*QsBqKJrs@i z6zI30ozh%Ifj@h`PmM+wq>!Zhj0qbfdW6|9jDx0MuA@bhbT7|Q(&`7IOWfR*?H9mQO?Yzz>erZ z$`Jz!+-d7exvNcqyhmz)^cMN-K*34^7RX#4{;yyiku4CryDzf;1^#q$qGoOGJsJQD*%-j}kzo!07}w zC6hvdU?qcMFl)zVX28{1ux6n)Jp7CPHbkj6QcbWzx z=Cf_xX;8wS2D-FqU^nm&$bbC@;$Hm&k4yf6jLZMP{KS7C0{I7a2K@taoBjd+<^RC$ zx&MGf_z#?<{sXx`|AMfOf5FePzd&^DFZh%27epWa3#$D8f(I^t!PW(T!EKelplD_a z1bv?Z^{=NuPvI0ONSOk2kSVY!Um;h^EO@J@gCxGzO1fYjZfSgqmV9#=$z(anLmO2k_tj0n@ksfD18yK=+P6pv&$LI4AxCMn=bgbp053 znKuTk@iDN?dkmPHkAX*=F)-XU3Ytqt!NK#Rpgd$0JhmSN|EZ3Gs(}&E@L~icrH=ra zh!J4yJOciSM*uc342qu(gUpm+U=cD55Zhr8$r}bbT|)pA4}nuBhk)zWA@E@C5cvFW z5L|yV2yM%)eqL)?FV77AK19{ zgD0YXFwoTp-WT+NUB~;tjg@`iBEJu;{Q4VYU;7R6BYuOxrN2R)^l$L%%`fmE`4?E? z_Y3SY`~_AH`~*$KKY=><3Aj!_!F~2mz<&P&D5d@YuYG?23*8@JZEr77yVVO)BYHuV zMK8EA*#j)fdcYyH2mI&I131hc;9uPhcExrB4YzJU%6Egzy6<3j!gtWI_B&AIeh0tn zyTH*|QHe)uy1)(jF5p(%39@55L9RnKWR6DRQZU>tC+QAKz zcJQOO4SddR1BbV@fmfn7Q2YKHK;yoFE~jr`YNi!bl(Yh?@Kz9D)Cz3czJltMuYj@k zD;Q>c1&O6CpnYEp=rC#l=Ubb>#JOg`acu_gr@sJ~yI(-~t}nn<`~`e?(*zW-Ch&Jr z6G-j;40=*$vFbBO`PT?0Z#4pWzeey*u@N{w{RH-ee*#WgpFmxG17N`hFk;dG5?Vfj zme`M=+43Ve)%^kdKKB94EdKy1`rZSJwD-W<`8_Zjeg__Az5~N9??B7QTM(J`7Cd)( z3o3@|L3lXT)q)N4YC+cf*C74y zYv8K+8st5D1s?qO3LKGt1%4OS07cIl&^1{Nf-|c@&hlyy+xZgcM!y7MMlV6|t16%p zS_KZuSAnS8FM!k97ocR|Irx(B9Nad24$SMHf#9%bV7>e^@ask;uvk?I7W7ttuTd4i zTDJnYK79&geV>A(ljR^YsT_oxm4mU`Ct&V>Pk<8r3AmA22F8|@fq{3WAU&iMOiGsm znXJd)<>JS{vi=d+y896@p*#YG$qzw~$wN^0`~leI{Q%qRxv7*wn* z258HDFcf|tC^7DX?$moAc-}p5vAhUGuP*|c-|vF|BJY9#*}Fg?y%2=VD+EW%3V`LB z0+8Q&2fPZq12SiB1D(^i!Dfxy!1m@X@X7iXkks4+;>|a~i>@0$XWtF5fN}#2p1KaU zi>?FWaz5}}kPp5*&I8<)d0_nAHIU$Q4Sept3O=L;5EC;x)$^pr5FM>qRi@>%e8>DZ~2G_f@KyXMFXc@=^lmnUI z!*~YpI+g(vX3{|0oPg8t`PL0eb8Ou$_GYM8u_nh4QK3a(oJSDW3u|;*)`n zd@|S?mjvwDNuVX>JTPLN2YS)xz70j-LVP`_F)gfdnuSoB$Sd zp9bRXr@{T^ctG=v2Q&3?;FfC~Pwch>?FXhp zw}I+6zQAR^FF11A2YB~;g8_GMU~y|Jn9JD;J_c_ACN*Bb($EWxk()tahbO@8Ji&&H zO`u_7Baq#+5%d>q08yL`;LYy!;AN!;*r(wE>LS;HmUnAG#@w|)K57jxZFL9qCGOy4 zf*UCBSq-k)tp+PnR)M&FR}kam3YKKJfRy2tAkSqb2+48=-$tAO!_^72WIBQ!!ww+J z*#X3+*#pD=72wc{S)5-E414TAtd$+eK4lAbezgH#=i2}#x(u|xT?+PSF9p{ltU+3Z z6|m-6fp~vQaOTbu;5@S!+;m$EUZh!ogkEzXx7ZvkAr=AUw+q1)^@X74KQr*<-U0xq z3qZqaQ_zw;A0)M#0O~vwpmAs(_*p&|1k26^>FehJB;6SBx{Sc)c}8H(0YfnU*Z_FY z4S??|eV~@82Vxs_!F3H?fCTCQYQ8pD+^+>R7HNU|krF^D)dYVjnjp_X1IV0E2P&`B zKods|xUUt1eTk~T^@9k!6NmuYQw5AC3&HtDWzeZIi_HR%l%fPCKk9~&VFBm)EWi(v0cUcVp!_QX zTvTCzg&xu%GL{ZPpGg71KN{F$P6LNSslfa)1>`o*AeHqta4oTxz=!>#6TZtKoOV zd{Y;)4DUq7Zg(L5&Fu&x(~h_;YC~$beM4qqT9J->Uy;M#T99(t7UaRAW+c$}3sN54 zguJ=)8HxYgh)`&ah_3M`WMW+d0uO&g9%O$&E>*op?E2mz@k+C>dW+cl)gzb4I;153 z4Fc+Fk@4Zzh_=dWWXAdx61S}esl}?1CzoF$+h0~8#XnvkW$YKoA(Q7w`G{FF~$Il_19? z#Rz@bePo%}J;dlh5%MD8E+V*5h$vSTAk}Sm5R<>R5l7|Q2*>mm676ymxx4)aa^~oD zMC)8W5^y6A@qBg-`TON6vVQmq;v;(nQPH}Lkc)GXT(?We{(v0hPvk{pPJA}PyOf3G z7iS_PuQHH<)^sFuI1QO*q#=r`7myEgQxO;26eN6IGU6JLgf#3wkMN_;A++SP$fc`^ z$XM|iWU49wDg1OA5qHNU7GrS;O*#%i`KOQqtytvT{20V=*-0eK^#roZGaBIrMj@el zN#xiu0$F+jM{b?Pkaw9VaxD)crbPe=DnpP>FOMT5Z;v4kUydS9okx&~Ux$%xqmjs= ze}|Ce(ua^z_Ce$a{{T{>x*ze@+J|HtL?B7?!jWYQ_aezl!jMbL_8|T%LXo#lA;^$x zF!I7Z2wCm%A3|*0jqKUH3z6Nr6WQ#u1KGSS5Rvr{K=y3kjt~L<$m&2pq$+S5G92iO zybbh0`~$s_+<>h}%JwaYt-lwNylpd*+m+9ns*x>*6%X(KGxU(U)f4yN_+d4!1leLDlQYQoH`WnNt^Nxn^#~lohG^-7P>{W)Np(_nC zpB07$uJ#7XvgHPv*)qeDF@)yuXe^Loddl;G$88e)bo% zR{ayY95wX1CSj11={4<52aathAKxsLJ3WM zkj;%=DCATRw2RjbwfTL3)~)J-od3Rqy54p|`%5|?N^Co{UeE^R_`QYR*uQ~Ff4_o) zn_HozycQ@nsu|izehH;)ZGv*=H$vi%&!L|3XV9F)2I!;UDJ1uK0^PK#hcbuipaV6v z(8cqQpsV7V|JU&lda<+``ZiDrRXunB?N6wHAa*&#*?u3IF}Dl~d3O&&72btrN8Eu# zsM}DKLkWcVbqjj-s0f-$ya~N$6+%jn8&H{X0aVhQ2hlQep-Sm>sA=~#C~#8R&)h^#7LGQ_!+M(Ga5g1mto2IP?sD3|eY& z6k7b|2vn0A39X?;Ksy`{L(}^YL13N%%8@|Ou`M8E{Ywv#?&zRUofewfp@DFJR1mjZ z39U0Ipo_cZP|aT{bg@G6|5yxhc8MVDpZ^J*Qa%)-<3R*ZF0}L)8;UAoL02VANVkCj z{rgOVwq2n@4m1i>ZAXSI-VmWB2?VGCj)y!C6cq`j zSs|c{jX_Y*aX56-I}mz28UV%RAB5&H{h^&U2cTt*e$dURebD$0UugK-UMMYV4>X1K zhUU-P4K-KpgaVXakkV-fglyXeb)E8rR(o%StcKm82N`aVP3RWLY363=Q^_U>&vt>r zmu!S^wa!qlYCW{daUEpQ;so7}SOd-5>>vLF?~49{#uiiHjJuOyF>wO4Hu?>2 zzA^?*`j3LT!Jpu@m=W;QmLK4%*6*M|^9|%!4}nX{20<-x06aa_52DjPgN?gCfm84L zz;}jTP`Yxa8t3aP^iVu(!4l3?tkC4d3!X zY-AqTyCfHMxPA>>x+@1Pe{mIDLcap8{+S7OM`eKMrRktP=Msq8o(8_JPX(9bFMtcb zoCj~~lEL|==Rlj}MDWd;vtU3;JSg#v1O1y~z-ICp(0uR|I74?5%$XStPK!Sd&Ru>C zd~z)c-05)yq*g|N+hK>nn$|<$bgBXT*$;x}6#zK=M+g3i(t@S)HQW>gq-3GRT)oc%N zX15#ohqwj2`q~wo5wZzf+^`XRUB9>mSbq>vkA}+Pvvt=Q1Pk*O`An)xRlVuk;U~=$ZiVh~L1^2V=nA zO{0KM+D~9~?g&5zh5>#5H{f8{5YSLF2u$BH01T$}11IKu2HG?qf%iSVz`5WaV0zgH zVC9-F;AiYR0GR9mN?7ec#*4SWzU^;- zcnTcut_PeBJ_f>X)B>k09|3USAyCy-1@!w>0yWnw0MvqVAW2aMoO*o^*y?o`IGc7G zxMEZS@R_%Op4ywh!gYnf_vixP$Y37O0M7;L3a$a_1v$W5$yMOni!7jYQzo!2CLQ1n zT>^sPX~5^)RKUaR0$1$KAF1J&E(fZvHRK=1HrAQFBGc$E_k zbj&ybB$1B+#`mItH5NyJKf(y$Xl*#~(Ebomtc3tv695#g(*qTUwZNgbYGA}w1=t=} z0AufDz%dUg@bsh@sQw@X#GV4+*(n~-^??IqZ)F3kPBH=Hdph9mMgyK4r2v*~B*0=L z5vVMwkW_~P8mvNq+dKq-Dh&dzn8ATuJPcr7KM1`1eE=Bo-w)KE z+XsYv^Z{bs_X39_yn!{1yMXXzJAu>u9YD~XZNS4Bp1{{&58%lKH-PYIGjMr}E06-Y z00$m#0CLQofePX};Mi3s!1%i(uywlwU>mUtD0#91m~LSY7!#HO_cCmO)nBZEy_>B7 z3+)o%e8pm*+1LW83Rna%Viy4STIT^ZHgkapiW%@L(*&^nJPR0go(V)rW&n?ijDQEf z{^|MK{_3CT|L8mKPw21w9oMhiGp0u#{-yV*9??IW{zGr$`(1AnIi!D4J*eL{eL#=i z+pk{}{z;!#(Wn3Tr$^tiqg$`mcIg{R-sxZc=+Gx_YS)_x-|9Ezyw;obw(3*tTlDYn zFZHhy8}$*5&-FcK&-CN_p6aU%_4?g+>-5s$M|$-78vQqVwSM=7O8wsE3jLT_xt`%u zrjO9w(_;$n=-+)T(c3O7*3Ur|=?jk+>dh(&^j0Hz`ZlLrJ%V^m55#8c@ikZUU&k`_ z9?lv1&E(7a53ypqtHDvv~uS9**VuBvF z6Q|cP!t{h_wEjmSO26whQom~|SpQ>Hke=WlsMm@D^ssn;ebepz`g!g9^izL*^y#bi z>L>iX^(MSs`X?v7^m_}o>qU*8diW0yeYb_X-q~Y|ejUbD-=TKV`<~mNr`%bu-}HK| zzIb$ve#p{M-|42A}ebQ=An?rZ#SomK9b zZoK-J?o``|u61}=*KG1#chr7J_tj%iXBzlL*GBuSqiR0tE}ZJsMW=V`TyA&ijy-v& zOMKU%!~ST~HO_pi`(yQ5*Xi7P?ky!{-OO<74Hz-|SE7Xig_|$6Su-7#>l&pI(u=9X^M39{z`PeQ-z@fC6+(tWM`f z(&+BeRJvi7Lie60(?yCTx(=yG*RK%h^3*(?gN~y^0xX>y#Lzu4&~!_~DLSjeB;AX{ z1fAFaKrS&NOt&Qhtt&r_()|rb>P8L)>(UHx-Cq!C)lkW81jk-Nv&bn*v>vVM+opdQ{ z9CfSgSL>)tSL#p;>~)i~mg#VRZFIt4Ryy~=CAy;S#k$@%=DLRG3w8XO`MUCZb9Ijj z%ybc%Cc0neX6crlGS*ETnyx#on5JuG|J63*{%DT|PH2aAk89^{9@V~I^;64P{6l+X z=67xK=vVFDPXpRZuluz{b)U4roj&dFt3BF{NguRJqTXvu6rEaAdb`#f@mAZk>$P^j zbE{Tr)vOJk*`)0qey(+S*PwNI@m;`UaJ+Ks?qM#RBK<*Dzys(E3~t=-q#k{ zmuf9c?`qfoDAA6!-O}nF-qaT6-q2o5$k*-xa<$3yYuc*^v$Z_eE86ZQnc78Dm$kpT z)3h;8%Q?xzt$=ZvWB<(!nS*_cicKy%y1~)fSeiwT~_+wK0HPyO1E&?%yHSZm||>o5y(C^{+Tu z&tjH#B95VzOK95kK#KOrI+AwzEP__tjnyhDFj|+CP;HtjMEeMV(55>FY29W8YJskU zT3zV@?S`{{+9Z*$wq*ZaZM40&)^dEO7Tvf*8qnceE!jLx+ivt%bGvC$}b=h&3U7- zQM}ST+|{C4W%5$9_2mnVQR*{I1na5ho=d&v>R7ENpt44jdAwRvgs9YLttvD>-U7QDk7*j| z^;FGyQHn<6nyi^SlBfwQNzmXlahiqOV>E_|Q<{vjXbl7&*UZ~>R1-QCsR=1RteFWN z(nxkfnwUwwhE=N7{Lrd39-c~#%P*PcU6DkyPb$(-HwrXvU$~n4SJ|3LI#V;eoUXap zM$!CBBx$UW1kI;8IE}Ctqsa*m)m+#SqVfG1tjWlSYwogPnj`iHHM8FA*LcV7)42Hi zXj=YxYh3T_()ftIG;GR-oSt>(i_YYpM<63r?8VvW+yTx0%xfrfo(o<{CEN8|RvM3eh} z8MSS%v8Hm^NJC8jr!GKDsqg-qP-_du)kDNlwe6gr>VJ2K)#usY)L$&Vs((~|Q5T9n zs~v4Vsu8t4YB%`@_0whV)wcB=>Xphi^}FS7)FJh)YEaRvCM|1H|Ehhi_LVlM{jHy< zjjQX_8vY~oW%GyX@X|{4QhJ4&WqM!DE4-(62)mou~fR#8&5und)V8=;{O66t$BtNnP;{|34OpRhwI4)X#6A)II@7wXiox4L1a; zKQ0YWd)z#r-WlMh{@v}P76W_KDHglcV6K;XiSKqbr){fRB6C-}m~2sJrEO9-xo=e8 zezIPTq^?zG{&H03N3T|k?N_Ql-de7<^tV$_wp*){B}>&`r(3FjCz`9v)-F_gl+9Cf z;B(Z$?@iQ0(phT1>BeeQf|1(F;h!q8_>b!Gz6sT>mN6BY`AbzW@NC2P(tVeO2($Qq`OJcU4yBN>mH%Z>cJ-7OEUw3RFHN zxhkuj*Hl^6S5=?=vsAs$(^W~KmsCb=sj5|!6xE-ebE;F^L{-aRysAYSt2+7fv}!_g zQnh08xM~VIs!Eu4MD;%6u&T%Skm}M=P-SkSSM55XQQ4cRRQICgDziCKmBmSss@Y7S zf<<#xfGJx=Kh97Y&8DfsqR1-N45G^UFiw^87o+L~LRIzSNR?O>tg0UlRCS61R5|?z zRO?xODpr?|DvYp4HSN_d6%FB~0-kJB!S-!cwUoQ57JF`1%`J3Mm95>NT9v*|wb$B7 zWfkY3$~IZ0`g+J-H85(Yx-7C$&F@{Ra>HAy7B-rzuJ|of{V1KM8r?KURg`6-T4Oy+ z6>@rpYO9fvs!91*>G*k4=}P#m9Cc>~+dkUWv<6E}u+S zBAAzy+n=Q>+dWd0?rG9>%T(jfKC(LPRlW-%D<2jT zlr(dk^0oq_tZ6|hqdkyHlcXT!?opU>Bj%v8rDVU-&2pa-rrfKvZQiZS+`LoS6SG~} z@pY^6G|XK&nzLDHHEWad2YrL`$b)st7q(8yml_Ak95N@{8p~zSnWj0-Tk^WC1F8!kzUo@fE!5dS!SN>Fd zTJl4I5`9x>9u6u{)?XB##h(-&HN6Ti>u$ww(R+oox*$EKCejmnWQ+e_pD;enK(s4+ZjdPnp28H z@)HWPild4k(<6$2(8G#pmkbJVKcGl-`~R8?sTK3;6bkY}nSzTGE1WX~imP9^iuNsR z#bZ4~A+Dw>o|%#ry$FJ$~;4VdI><&d^v!}v%sfS`1w?%O-b(3QB-3G1u8jlF`v zu~XD%TPwbQTB3O2v{=FAEK-zSov(P*H%D>8!BjDeF-zfeS z+_-#Y%P)EU!V&pM;CK1(@vri0HDBa5(>}}hdG*Pi)ZOxjh41B710C`;j&1TG@@u&y zxkY}hsY#w{_CoIO+aS*e>g5f$YUNo259J=KtK^6974pcqGP(ETyYiC1CGuYPTk>c8 zLb>E}zP!Hmy8NA4jy%`Er}AbHjSm^@73FRw}SlYgoAkw5wA zEoa#8lHWeKL;g_VDL--1U2amhS-$tXi`?CMgS>0+I{AM78aX?DwcNXOg}mv*GWjx7 zTls2ND|rvbQci@-8BG%Tu-+%SB`(`R|CovOU?8vOQ17WfMcc zWFqqsS&GMZ*=o;k%=WmTEI%?sw&Btx8M`!9hHpJDGx?q*lbD^A#X7{vguBnkjIbwVNZD~2J~~Ra zEHgruQg%r8vKf>;9MH+cGc>Yh8>MVyvrN|DFP2d#0$IL_D=R+9lBv?^vf_ltnwE|=3o{o^I49R*=z}t<@v#6<5+*$UxAXKr>vxrrCpOByn>ovN+OC!PI6KOwd##c|0rs*YoSiJ4Yb^`VERp3$S;(FyERg{k_slh!0Xb{5vU%(Ju89zL5?qTcud&rBoO7LK=FyLHgxvy>v%vt<*2`q15bp zr8K&*Tv~IxRC@RR9Vw@}SlU!~Q~Il+K-%1tD;2)Vkyf@{kv@NyAx-MOB(?sSDh=yD zFAW|{k{W$Wkcx+6rAZ^FrMh3yQp>SpQqlMk>7n0;rGXO$Y4ZdiwVc#S7fq_9^%HXG zjtPmB^IIql8s|yBkFuqKzZg=+2vzDaOp;a&;iV>nVN$dHP-$HsQo6f4NGg2?laku} zrN*!Pr0gaiX=H=9lu)-*`n77i)a(9Msqbw!>C8e`Y2>wy(z1;8(i<0?q@=SB(%Mri zrTs^iOCN)_Qkv3AS|YHN*3iwRXK)Lo7Kpi0)P7TG(9T)X8CzyZl}^*7m+Yn_QHv%d zYi5l}A|^&8=ZC&a1l?aHvLd+I+)eDC*4jBb38=+oax3KH5S7o*-t_G?-tx!jkM zr??lAs{sv?onG~l)6TV$^R^Eq)H#)s?uq-76<_X2tlr+1JgvJW*>Ss2!pzE-_{U$D zd_I&d@fBrBaQJkI^MN$U9k&aTfA+}|qq&Ka2V-%PZ9Qis!sjO?#Cyjjv$LWk!ZQ() z)7nE4J{^=81?nWB9%>1FxkBPRTPi91CX{@C&65l~U`x`o84`;as$`FvBw0(sOP>0M zN!G6qmF!!Hl-P{ICAsYZlCjDIl7CnBNvfmwO7=*0OY|r&iNtf8#NO6Ja`NwHNzn%v zNn(wUTRmvl8mW#iAPV{{WkK*2)U;!HH7wf#y5n>3PLs z&5@hpYs3O^l6$V$dv1<6t0zlbQ<^SLk4qD8=Uxz>-kmH?U7RT9e2Ei(dvHd)CGn)# zm4943uscdjvxpF%{bUeFlmX%mF!^bTyg9nmY9U3i$AWS zh@F2D#2X%A#r=tBF`XSEPTCqQJ~k^*?DooEoO;DiT&468r~7(~cbo4NCv|NT=N5Q~ z0dR}hBw&;H|D=f+-Mdz7dDBrG53LeEJ!mhkw6qh;K3Iw0c&MUV}FU};eLn$SAG*6=pPXME&ME!Y5PQ%y}L!H zX1y1=KWi5yC%h5e!?lVM?O%#q`ksp-uRj$fN*;^o?vF%+<5eQJ@(Pj1;WE+BeRo9? zlM+$()0?6TX9`3xWUlD0MULo0YnG_?T)K#hOB2=FTo84&pA+3lJu3p1xJI zr)-O8K(R@L+OR>S>0K+rraFp7QL99VIrbt>wXMiYXC-RbWGS-#xJa}*b-t({IY%U# zZ6eCQZ!EelGZHb@{1vvfO$g`3j0vZFehROTeivF?|0>);`XXGm@RP8-x<_cE>Jqv+ zbqdYiz7<}KekJ_s)hwJCd?Bp4*dT=cFFJ_%`$!mDP%VU$9|#}MyD$8A|E}<-phS4Z zrbuW}Um)DA$rU;|<_H^JW(i%w(}nPjX~K1FDZ=Wb=Y&>nXN4Qy#|r;MpBA3j8ZB)8 za8%fSDpGjKGhDc$8x&Gb>4b!>YN17!TzKMyM0kITP?*=w72=Mtgf$!J!hsgDun{B( zPog3NnQ1QwV&f%lJxg7s%A1uxf?3p^j)6X2=01zwXyg13n`1n#bRf}kfk z0!QW*!M&+;!JKnx0$bM$g3pi72^6%mg8RQ?1=Vq<1xMFK3uadx73{}G3VgpE68wz< z1!_B;Ag@Rzxa=<%Am51vl?s92s|i=|<|0!NzJ(_ESW6O^5%7Y+A&lT;1WM3vi4YiH z3lwyE9TX^@`w1RXeFSYkb_;TkcnP*I*(Qj}b{Cx4wpoCw-zez7trysTStD4fUoGe| zT_GTyw-Y3@w;`!nB8+{gF){ei#m$UA<{{C56S@@xL0)h+z)yhgr!>ob1kgL?i` z|5|=xQ#F4%{sEuaUB>6~@A9306!Y_RH~9n83izLoUFT=b&*m>n%;ckOFY{sPsr+e9 z=lSxyM1JPxcz*otGkkBallw>fBIIy z|4iWWt2>!|B8A4k)kWgh)A0PXZVZ1j1I3T%3FgN!0{PS)fBqodkMG&Nm%oR$n{U#! zgC9foyG@;+|Qk3)*)ZFq5%cVkZ^ z@5jwUypdHPuQ)-=b2C=)AF_ELwlH{Y=@ef4LL$%f5SF*+Ybeiy zfaLW*hVzJ919&l+`+4CDeR-Q9Z{Fp8FWw9EHePv^JCDC{Gw)UMMxK%JdftF|4KMNS zD&CZ@JmR>LY`OXJf3~IDX-db7SG|#be`YnU#=s0lKbe<7}sIr zPp;3|@7xuWgWPgjKiB$kAJ^Tbo4erbJMOjLZQSXU*Ie70X6}!*joj$d4cxBb$J|l$ zBW}aJDlTnV1-B%;l>4~nHuu8*TU?iGH@Ju9&z)Et!=0@<$!%#l#-+L+;pQfUb8r6uxrdQD?wmpu7d>CjB@4w|rzd=Fp%aHY zeuTlD)=lBo?Iv=AE?~KdW1-v&C?uD51J3&?}vy}0F#p4_VS z?%b#&u3VFM8@MpfbzFF?BX?o{N^bn#<=mF@Hr!XkOStC_T5zq>7jW_8bGZ0m6Rz!5 zV{Yo7Y21#GDNbk3Z_dTPzc|Z6e{e|GhB&0ZUpRKCPn^{39!|&Pdro_B2PY--4aa7z zg@X%d;$Sa6<1GDN&pGE)%XxLSn$!BRf^&9T8OI{}4hPkKixaY;kh2KNXe;LlZVP8&h6`uum-U>^%}yMqZZ#*b(wVV<+^~vp+f1vL{&8>=#!n*vwC*>{6#Y>_*Nlc6Rm+ zw)dx8_PI4V>_S!+`$X1dwnI-U`_Rhs>>oFFvsZoI!8Tvv$*u`=V{eVw#OBvJv&mCVYzub>b~JwlyXvwX``#-n zwqmX&`|I9C>~)%XY{xuPc2Cz#HqCN6JN@8aRt7Y|V%{8Oed_(ea<=-$a)k}BMxjqE zLtziAw);J+ad8Lh!u~fbCv6K$b*+&V+19{9&8cVgdOc!o6;`nhrk1moH{4?tPnNLe zI2W;2;|o|*$FH-J?_6d5?8{)8FTTVY-g|)+CppI&Nljo`K8ayXjGkm&T78@~3vqU}- z``C&l{<@eIX}*Ys^PI=}PB3K!gwOnc5+l~$$5YI%f#1wM3r3mrEkBt1(L>Au%@<}! z%10(}znjT^_l{{kt(_UZ@-?&2rUGgdJcyGJTmVKyPMef)|sN>&d)S?Z(V}yNSvB?#vvXwU)VanFG_`Z3T1bK|AI( zvK8}>VlmVF#6sqmi*uPricFXvYK@uG+NUu;4E8faSU1d=^7_iS9@NjU zq4hCfiVqC$s7}Uc(p!ckrL8H{Ic$Aq-^939?950ib7J^auV&nNY|j{YZp-LtS;|Oj zvtZbEEnpD(<}k=#W-}bW&0rLa{G(5dP0~&NjM3ZvjnE}CzSHYw4brLN9YS?htn%&fOOYs zS~}~Gf=(Wn&~1JS=;yz2=pA1e^bdU$dTtki?%5tjKh}z(r@RQJOY32Dvxf)h-21-t z<0am7VSyKYakeMjaLJ9He{K^!EykH1dd!L5U|3BzQQOl^M7H#&jHPrW-hzGsv4DPU z{~Wr0=WP1?Ei>qBr+>5vyGa^t(HPBm)(A~7F+@uo`a+B7{z!9s)lJK(e@E-O-$v`a z@rst3@shS8@i~oi>pa&3DqO{&>>D zKDyBgUu>d1zw1mZOn0JTqF2)@<@U58ye+NEXDKady#;Nd`2t$-Z!;RQYZlF_ZaOV9 z|1b4N!UT1uew5lt`9anB4N>2$|3aNw@R8d0^8+>RZ6|el#apUpMk{sm(I)B;?-^AJ zuczL2eMGIYsG`P>-lwj9dzY#&E2bu0ETpOrEIn*OQS=5`WFHnPVbJXTX z2~_i|G1MhTPf|Ns$EbY2NNTCWA!_3cfO@T4P4%ymQ?FkVQ(r=SYB_;T6>q0gyO)ru zc0X}cni|_IkTzWz0;|b`+q6>&Q4H<1fvv^?+;3> z%@F1Ia6iTGaUZ2F?E_`Ls*_?3drSGUqLp%Jw2|`mX#-{a@?%Pes)iC3P)QkCexI^t z+bN(F{Vv0X!@?D|EZIMjqun&MFuUs^ClzX?WB zPwl68KJ}qgB=4q}v3F2x-L_JO|81t6ZrDf}N?u2?WI0l%ZC**a`Nxjp^w^5RNLWl^ zk{43eubWG`Ju;gzyJ7}q+3|nm-^fYw1=}&QQQr^p#)2WTz2*z~mG?(7%A}iowy~3( zn*5f`qqdU&?;4X)-x|oW+mFeiP!0KyZzY*;cAuQqc!zv0=@uD7yg_bTnM-!~bd~I$ zmq9j_rIE8dQphtW63NaLapa{Dr^%1~PLRD#qsU-GIQdWvNInpvCAThClGnYKkbTb! z$g2n(a-AK6yyYF4OuvLDU~Q`iUvoaBL>|i?0!R*|aH= z<^6F|i{>W@=k}eHIW#~jzV?Z9lG#IAYyX~f@@*TbIN=p36aJEfoBf>BQdv)0qJKnM z=2k@-7`RUg&$>%$BNme;78jB}G~|-b9LXjb?aU;3jiixwTu&iQqa~3}FO4U?e|DNQ z9(jWFdV3TJ{1#67oCT6>@LH1j0wt;Gp@f9d3P>3nIHck(I_cC|GHJa(o)kNYCY2Q+ zN%=H5iM9A3ske3?X}xX_$-{Xk$)wYhboq=MY1*DmB*)?PB=d|lq(>pENV{h&CmC*8 zlcE@wq!5cmq`vC8q&;#I5^be1$-nU*am+AD6l@$LX1D(!UOO>FlzV<58uj%NvGE^> zD(_ArcJK{x#`zYa(yx)2JN%S*{bC(aa_}MX&(8{C@a0k>7j~O?aP%he`{jHh8Fr0$ z_E#1$=F(+i$iY-%$B%Qw4XFvleSR^-RYTFlx}>8-ckc)y=MzMv#psBuJXOT&@1(@v zQ9|N^ja=eDGlLkTrw}Jr5QrPs8Tuzo;%(Us@^se%ylma&Q?zebMDj*s}ptAaejZ<8E?<<(5Wn9n6b#`_e41(-yDTg4OL#it2N5GM#% z2aXV?j)oKLR)K`+T~P~i@a?KD_fTk#`)%i z{}N3JF3vLvj+N60J)wW_{QfcgU1$XVV$nBz{*^Cy)b@|~s)i5vF-j-?*N->& zvZxmPL90gmrRz`etM_AOIxk+5ZMx+_h}(MQ#u#V_&pmxaCioOr`bOoI(`DT)n*jel|GC^t^0~Q zQ}`Jd@7aqZSG>oK>}$s%p1#7VkuPzq*UxZvqqfdv#qIc6Y{Y>}8uG?9=#sY^B*XEEJK2HJ-SHMawQ=C7+Y9A(VLR-`3MuW#9?y zt?DD#vTfnm(**!_or4B@=DZwxf4&%79Ld9~#+le@A}TiY0|6^ThheexAz0I0LD#+Iz9I?A^ufQfd*{nON_q)3D3D{)9ccJ{GpsW+Y5@Vkk^K-XFG)(-+p++7;%#uOm!Q^g4{T zqB(5Endf2GC+owexR1hYUR8z}`Q8sJx^X9Lqus4A`SF6V@SoShaMUYdlTR;)aXnMR z(lXA4rOitS<7v-?O?96LBfz7=j@$_kQ?CTWww%<2-TNsIGbM||9O`&srmn28JIT~A zS0iGWf)^GR-V_oRwmm59_vM3OOcTGb6v>{jlviG1%w3*g97%w+b`FbAP|m|4@jurd$Ru&pV^VZh&in3MEL46}9=W4itaMsxZrrtte` zOfjk#bNKdqjJ0(;1_WMVu5~tH(!HNy=;@C!-=^1K_A?(~IFCv(s5Q4SrpIn#qCe$f zULDB63}$Cy8fIU@XgDdDueFJojcejC+oDck=Jy`M6!=79tkMmbpnp0{5J`oxE|X#k ztb~~PY7S<5GacjNO2!PG!eMm%p_mtb2+a3%7^Zz{KPC?6gE24Jg&{56j!_ESG3eS& z7^9WW7%i{{Q`))`Q@d#yChde3W>1d=reNm+%*RACO#jeK%$);97{uj2=;HA)bPr+# z-I+6l&Y1QEy#?EcK7FGLeQQ<+I*argO)Y+j{$%zXy`5H%4!cu>_MTUX9-)_^Wp{6* z%jOlK8|nGz!aF%=!rUx$6ZI0>q9g^q!ZZmzPK-leC_IHWH9n5^4U0tkUpJtwrgZ3A z!78*(h7=w6Q-D6WpMy3}rlYU+lh8B0aA?<4q3AW8!RSvLVQ8gcKf2-hUiA0nyU_2& z+tBAL+|c&(H=(7Z_2|=ij%d~73iP@FJ9JL+QuN42bF`_)eDpwsDf)b)G1`3jG&Dvq z8Opvp8tOCiM`%CtYbY`8b7;z!p3o~>--qfW+CuG~w}zguZVIhtHiXvRs0&S+s1DuY zR}q>Lb1(GS+v3oM)rFzwM7g0ZcdmxUPRj^=aPVU2z4+wNL+uHn3msxY#lq;&bH!1i zr~ZV8!uNrpZ6`IMZq4#gtc^JIAdMF~Glv;^W{48n<4y>j0boMES0Y1mX2C-@2Kt9W zalWDFU+oT!u-y^rN%aW5ljRy}-0vK^Y@<`?blIxVTgA&lUB|6LbzX}@&lnbjN~_F5 zml@9rJ-6Q|wDb5M)VC*NsONJ>P}-m&)VG*^)Rv}Rl#h8AY8k2>^(f&LYI{o)O27CS z>S*X=6y@wg)XbI&l*XbIRT5HydJtELN@~nSZC{X$x(3fc^_{$k`dXiis-Aro#q^6o zHAO_D=2k|b%%{RpAGd?3D76OlqezZg|4oE)b>^XrI84;#3<_$_J3PwA8iP6zibO4q z2}G6DA3)g~`=ZdhccXCH?WlD{?x;rtn^2n^olz|E8WiW;N|a}#9je*H3bk{u1xl`) zk5b+=Mfvs{qu#HWhVsWwh8SW-L&9r^LxQIULk8VGhoJdAA<>uLg`9r%HiR^{HRSi+ z#t??)X~_A!+K`JMszO9d%0tXxcSDqiZiVFCDhMh3bS>nt?UfMw;L9P=5f?%pmL!Ed z{u~!_!S-~>j-cZq+2N5PT}6hFPrbU3vL&hzqQ5lciB1qQE0-NIzk?RiJC_u4Y!^0U zOoR$?PYVk1ets}y>EC@J_c!hdaUpqyh)-<|0m?RqpucPg`D3*f{YZLTFVejHJu>!l z8?wXV74p~aCS*IW0U3L?4!P(-HImw2j)W}kA-TJXkt;YikXK@_BY)q!g0$(mj5L{> zimY)zhYTXcBd`(lAm=&i|9>W`kO>MY@??qtiKt>Ddq2^Te)CC4 zg*z50#iNj3;X%meD+iI=pYB77zI!7jmR?Bj9b1u|4R*2TzMxCO{6&@mcWbw3c}0bdb0!p{iDGd&2|jdzHX zjc*Z(;TFVt^F~C$mZu0KR4rnaq6)Dn;XdMd(H#WtWf9`ma6Y1a;Wb3lrYuBa&?UrL zQ3~St$wb86Yq5xux|4{*eMb?tGa?X?Do*;JR&Jg0~?0f`y!}V5Olw z7?$`d_mGc=c~kI9ul2zXVUEE^2rGgY z3v7cG`X#~XCl&=?N}d}m$etZ+a(jBPqGl>6|K)hlovx9f*rB1I?SJ}%ZkqN5jW6j6 zn(xpa^wafK(6wDnK`sFeK@pg`peyw1pk#4*5MF;bXfWzl5In9R2ui&c1Z8Ih!HX^h z4c<=)BGe@Yoo|W_y4rp+D6;Qpkn6X@L3!g~(72H{Xz?6H&_4@tP^ld+XrCi9C~YGp zsLlf)RJ98o6zzuyS_Ov%oebR{^pLPO=qY_?PzKL4C_uU;s7k#t$OKv&v^;Wk(99Fd zgUZfW2kkw(IOyE@1wrL$WcO;}bV{S)B`9U9%28y~+VjF1LrDyk`SH zUSbJH-&_bE$(sYG|9|jb&NPA-ru_+wJwFz>=j@Nbsxw~$Elzw6^oZ;UTnoJm98kXv zJS1%i?BTr#v|>C7Tuyux_%pOJ@B+Ln&|?4XK*H{ufy%9Ufn=BLKS;0G#-S%HtQQ3JoG5dwP? zFoAi;k%9Z5z`z38fxyo!pTH5^uE0k4wm@jFTi~R-OCW6RxW; z;=rXJ7X${rF$?@(#Tn>)e_CKm{v<5u(kSeF>@ck4@E|Nx{s~5Bbi;n2I$@}NZ(vdG z&9LJR&tas+^{^SnH85bL0`{=`9;~ye81}gG1}y5vb(neD6`1_gWmty(0xXN01k+&R zV0QaX!QwX`gS}lI0sAorf_02*V99-QnBz+k>_`O{R(zcSyPZUaoru7}Hi|=GS-4=> zz`g+3OjkeHH=8}MyqR9G9p61*DQ&K>r!~&7=LKtE8ObYQ{tbuxmVE?D0szRN+uSOLBhz6y6&!&Uqi;7u*)W+}autx~wr^sqxc* z+%Jy;7By7{9K2H&fVy})U{mDHfDUe605K>#pujC7pvmfDK;6{2fHU3k0c-0{2PEVk z4`_;s4Cqq)$IxBBHT?tt94AIMjBRvm3^qoL0fUV(#)1u%5F|w;lrTY>Z6CxyQKZDe z07Ov<1r?D{5Cs%azMynTcXxihKj7|%d!GB@p1aqZYx~7D+BSk1X1k+$&en-9*p@Tu zZyVj1F1Gc5c4BICVimk^6(RRGc)Yhf~Ya9I#W6R-a+d3W7 zwB4~(v5i!N*?!%ZwH+Cdu>JE{*!IB_ep^Fek9GgpChIq8g*Bu+&-$`G$qMTpVQrQT zupI7ovtq*kup*pVSafV7YfQ3^vUlnOW}GF>%RXr)(rU)OGb&y5?PC4wY6MeozFkZ8oUz3f*<#1nGw8M>R=C6 z&#W^mu-=~aJ zhLu<=&dPcq#JU#3$D%QJnXRfDOykuhW?8LLxpA^k?1d77HVY=vYp#ilZtu&Na1M)D12 zzVB5g*5o4dh7g-s))m1l%MW4R;ssE>b}ga#iLB6T34p@?ZeCt|3m-C1t#;a z0F?=ECo#>Qn=v&aaLhisKJ$z`irF#(X9~SjWy)MqV9q;&nOW*mOs#nlCbtU2e05{r z=B4|V4M%&`2EICP^Z3h@%}nyBjilG04L`carfKbuO;Bx%O;>WGjmptF8xx%x8;z9; zo59beHeol4ZMt0wY~(fbY!I{AHiBgjZ7SpM+At2K+2lf#Y})@O*!1Mb+q@6w*!Ys8 zY=(s|*qFDTvGL6ewDI=$voX{=X7gv&&BpGNlTGGTJDW;7mQ68)W)stIX#;(3Zgc&N zvCU6o1Do+}l+B+n2%9_C)od^hiZ*v3@;1MFrEJD>L~WV_1#A-Zd2ApnTa4(BtBg0? z1x6)xnvp3y#;|W5WOSzXFpOQ=87CC~V+8j%GH5wt2XUc5;ROl<<=*X4KygTY~>2}Lp9HiR->TtCAIu?=KM ziTN?&8@(9cZ@4i=4>&Q}#q1cFjZB8g4JzZQttDez#GJ9$fMZN2=ral!D2BBFf>Btj z%9y#Rz~Hq4GbVQ>8F>{V3_>)Bk!`w9?_1ua&%Ifp|2{KMPexDC)y7BYm!1yLE4{nv zjY@y$MIFEBC)0n>m+ijMkBC;&Z+gSG;*fS2~qNchJhDdkkdI z&F`ns=MLYXM~Yviw||SHivqE9IkO1*;=*})?#okjjPFT$qM{GIvelFRHPMBhW9>+H z-a0_K6119j0{qTUa_D9YepqjiiqiYtUhV%5-&AD1En0hW`4xI2}(G zqTgQOrPsaOq5V3xPAiaGqIoyW(8k&0G&**O7CqWai@)DNJASB@2Ig(1J$_eD+YR_a zGg7LeS^WG!Q@&V2YsD4PyvFiqpYG+*R&5{Acz5s8hKtf@na7i8IzszgYiGOKc>Kum}em9EBvARI@oIFF7P799Kv*lWLvT(66o5 zN`cMRYhn%7FJ6DK#yVA5r>uRjuD@Sm{oA6@x@;iN`a*n;wSd+m>$CNDt&4)vtiOsS zS(g+hSV!2$Tgxu8t*@j-TK~j_TF?JJZ9NtqVErEAYwhvjsC9>{tF`WiqqWPugVt_l zHrCiqiuK<}3+o^#-nzaNYrT5}V=cOhw4O`XuzqQzY;Ex$#QNDe8S60#aqGQ&LF+jd zul4)!ZHm*CHA;i#B1OJ>nquxXMlsnMqzK*Zp%mlVDY%vv%FWY_luF?`%Gca#%2TTf zibwBz%0%QFik)0O^Nyxt{JUf5ls{FneJwec~O+sfe- zQt3HLm3=S;GU-pD$9q!_DS1#Z@0=+^2kj{#qby1XhenZykSV%F<`fvin9|p$Pl*jj zQRc-F6pLI{iVsnN;?*ig!3IfE`u2q>K6m&jRhT`i#V;FHJ8sKXgLAW1nU^Q53>1g0 zGGF&u_0u}7HoID_X3sWTmGL)N9liI(suNRXrCamC%JoQzmFHxE6`qr4H7%WE6`A|c zsuzFP3f7ovrFZP6mEz)6tAR@wt=JH@)#8f?D>5;}>O}J?D?jg(R)odlR+I6bR_DPk zR==J(SP9_|SV0@;R{L&NR@IXPEB6=^t42{nEBQ>c6<$}%%BVukO5lK^RdF}i$|P9I zDs5B5s{R_t>JN0ET=9I99AmOVmianIzIb?&{C#kkJbkvGJhIbCE=_DB`@nvZN1rv2 zDY#m4M0FMU(xEbPaCZqA6;Md7Ud|(9<8sI`;*ZD=@7*QeL8Os`-`pfaEE33>^%u#T zhuLJq{s=NTD1@xDa*903JxRVK;zM3b_as}Zx{w22IFL^m9Uxm&(#bP)D{}ZR0=dJ@ zge)^;K-M~iCd;lM$enC8a-@JFc|HkDwt`5JPdyePpGAVmwnclEJf@qL$yLji>$Evb zv!)5l!%oANjP5>5IiF6;kK?VDW@no%Q&;LOzr=j8Z04!5EV=r@@|<{yrC?ftWh6Au zvgTp7<%q^Z%faV&EK7A$El<3;VL4}f)zaZ(oaIeYtYvmhxMec^yrt{+V9SkzCoC_t zcw06&d04KsJ6rC#+glFwvMld=(=7FeEG-}Un_CW#;VeNx`j-1sI+njr!!6_IR4hf$ z!z@oN%33}Tm9VT>7P5R5#%CG2xjyEmEDS7N@?GEYvN{EZ&qDStx1iS@>jXTU?aV zwBTG)ws2a9Sb$E+SfuugS!_58S`fbRSh$*P6CLtbiEz~g;(sYqL=XN^;^*)I;@)@{ zQNiOkQL^bLae(xlc;j^~QC8yIcRWJ37LNM{Uj%D@ucjYg#9W;u+q=J$?^jW2iIn!e2Y$x;=~N z`iV+R#aI$wJTN2P7se4!M(7cxMzo3Pj+(^fPs&7n43tQ}FGIu&iW3Dc2ohfp@DPm; zZWC^otrGr2ED$DBrU<<|BZPv$0fOuAEE+WjG538B~SE699D+f0By&!2G(I#vjfa5nePTw`_ zUs^Xid3ed}NAZlAsLZ&T&iTJ)@LxS<+j{M0uWz=PQKo;Gy=Hwg+s^xJ1{W+hL;1fm z6Z=wR)~NQ~HrYGc&V$W~VdK%s5Lo%}&`Tn3)z_H0u{;oB5xJFsrLMZziaE z$_yTJ!c3*z+iVrT6nXNyenrUp4%yeAL%p{79%zldLnVmVQZ8lY{ zVMbF@Hj531n5F!ZHj77znK@n(Fx%_h$6qtu!Y?GR;7upz@b1==c=yavUz5nkvrjz34^}?GYk(i%txny>lfK-- zLlv&$f1SI8KT*fQcPU5V(HBDT?%z-2PpSpr9m9R_ijAK58g&;uJ;DK>*Jz6$SEu6z zBglBZMss|xnlU~-OdpT>u7iK10>{sXsNmJ=pm;q+S-iqoar{t?AU;u^7cU*OZ5m#= zYWhKH!L-A7%C!Cch-r!Nfaw{}E>ppxHd7AIPt(@J4W@$6zL>(+D@}!2A57aH6r0A+ z&N8hUd|*0^%`hF0Pd5GD_V0B%;<70!oNJo*Ey|P+a>0~z@{H+`(g4$g zg1)AjE=NtZaQ@)tQ_g0#u>U=Qah83F}sLnT86MJrQ(KX9tD(8WT(cEnlck^Tu@5|Rs zXumF*2rF_;^8KSs^j?RW+}b>C@{<~1GMnUMGTq^6@?FEl&_=sG;v9Cv`v0ZknvBE@?@mKwNW4rJgI)PG49qY zW5wUO#zP8EjIVj$HpL}kc??Fc;jaVM#f{I7-PXwq_NPZy74$s$vBTI zZ){T|W&E#JVT@#ej89(M!(IKcfx9BUj5}dBi$kQ0tg{T&K)ooQ16i@s-iO?lYrzC!ZLx zvhN#x?nyU-KyDe?Ib1UeNQ^f+{*`S+*o!b)!-p89g`6^y%0FRrdc@l(U&X_y(Z$)Q zDcR1buz_iGo|kF_CXkHoh2o9&USW;s!@5SNm5@f^PU=S9Hx!M~wP2(6ElDFkBN3z4 zAbul_>|N~P&ULK6)DqT}F@x3Rj9~}g4q_vxy0P=>f3Qr~U)W1Y-?5KtYq6P|RoEDV zGA!Xl3AX1!0oJSKIkrY18!Jf6#Oj^Tz?wWu#;SH-$4*LK#%55tSa?(vHmx8OJ3M$A zD=!~_MX`LasvJ-3>YF3jq7i#66K0F8JwU^10G8O}C1%*TQ6p?TOb>hVfHoGx)xfsB zQNkV_mdDn~OJn7jqF71{2>)Ynk z>d!S)>4(pM&>xU5(buym(D(9vt{-wOOFyvafj;&3ZGE1tTl(2**Y&mNm-Lf@Ir^Q+ zk@|w~L-e8Dr}V}5Pw0=rkLzbKJ@mbmK5+aA`t82s-l zJCUIm`_fA9X9Gb`V8U2WL&!i+9f{Hd(cyYcekyuV@lZYCY#BYyXED7$eFA#2JNp=% z;ugl-Yz3p~GKX2XFoDTQ9m1Hu?!~-oYRAY;wP0L?8ZlhNH_Q#nXH4v|j~K_;w;0iT zg_sxb@-XQCvN5T%nV3G2I~WOM3P!^^5u9-DZ-erSA3Yw+8tfLzBS$AwFTW#scGF^ol)Iw%7AX4N0)Byg*IKso6WjIx%Ikk zRW-VA|5WI%%)ZxE5PYKxSAC@`XPT=!e(14o_KADCWKNoH?d_Yon1ZXiF|~2JMcpyF zb&FxTUxm-`7a8NIdnx6BZryXb?rbGlcdON0cXk4&`)yB8 zHy*5`i$H7Y7Lb*76^=l3PX|lu<^rO+Uv7hRzrEZ;7k=76$F?n@4JKyL4Lf6KhRk2| zE3F>%iuoTj-0m0J%=bGQ7g39rORPe7KKg*ZTwIKn|CW!w(fJHLG5rLM-oKANEPEU6 zt#u3SWOfaWIS`MY_F|)x&qtsYFP%pxW(1=L^Ze1u<;T#LO>SsL|6w$4;UHRw&jwvB zM?oLgBBDo4P0$WZ19Y}K3f&b9N3X@Ipf_(q(L;}9&?QA;=zz}xX#SRc)aAiV)Xc&% zioiREIx91Qx~4INx`ypVoujm)h>k6&x#K@j3Fp6}gyKG-PA8Y4${v@XrV0yCd{xg; zyiHlCvF-<`;>p`6zl~d{ZNclP82L-6f2=18Z4`;}vme9+aESmQI+{icW<0oR0UY2_3`8A)T@KUY*Og+I2)8wCIFA`=L|!=Bv(r#U~xL z`Z674Yl)6rUxCiV_;a17OIbRM-3L0qgfeu`v+2aXXr`~oe?oOO+hueZ17bR{;{rN&=l8WAtZ!;x*~+8UN7sBYxFBZ~aO81glJ&;!vV3;98*l#_PE@)jvzSD)@o6TF7nfz{p$L_c_VibkTZ( ztku4cgrU=sM=(jqSp5X#HN%TYu2C$~%QzefH$8`J#RnmS%>9s)1TUn6g)1_fIH(~kX~(evXgLb>h} zf>Be3aIY*uxO^x;5KEpT#0s+zU-KRyPUhT3EIz!2IC=LP;#+DwLgFSHVRuMsh z5z2@&DiDMwL>f^eDT-hTfe@AZyKvaXI{eteBK+3GG(2x`6rSHX0KeDL1wYr&2FF%6 z!+Sr}!$V%zz!#oZz}+9ehZkhLhELpl375M36s{io2(A=*7tRxu3jgJO1Afir3S9RP z0RKphh8q$tz|#!R!26H^a5)tpI8M$JZYgpEZnSR)msw@PyQi$-NrM(}bh|0Mq|p$L zs6oTyN)hn-d{y{H77Q+TM;5MdLmVy=CkP)7IHXB3 z?A44zv}+c@S~Tm$e`x;T`KnpAQl*(P@j=t6w^)<6C13M??K4fK4^K3&zq+sa_ffhg zJT*zv@p6J@P~=6;)4{Qt?q1=VMh@pRSFM9Ib4>g+i8@}IpA=m+^&}iMukPDweqW?% zZVX#$%C?(nLK=)T1rvp z4X4yO?@p*YXL+kbZ@R13MLMbb_#IN8u(MJ3Bv8~Vw2110GA8PlJNoKA<2vdgt(xj* zs+84TUO?2*>C)=c98vXqfgp9P)1F!>X+up%XG!gD?T2Hi+AYFqHB0zOwH~qKYA06Q)p~lJ)JWeBsU;QKsD00%s4a1bYQiT? z)I{wJ{>_V0`=bI^dn}-$<~$2gTl+1ocBN8OjW-vh7JOq*wK{Y|mEU7Y)rc~qYOgb< z>LxX)YQNT{YSh=J%J;Qdwfa@PYH(_eDqmEE>eXZKRX1p_Rb6yns^-W%Rqa`SsLI=a zM-}`vMHT!iQI$94vTAQQSM{l9l&TvgRCNn^S~XGpq^jVOx9a&0ch&kzCspyBL#m_% z8&$8<6xAR{qN<;%iK?xVfvPGGN_B8VQ#IwgvMQzsqFS0Jt*Rd>s+#TzQXM1jsUQ&> zDo(;nD(7aVRU%tPRnEQ}P;tE1r2=QSsSJ5HtK6d2tDv-NRNjbIs37Owsa*fBNTvJT z3l)WXIV$wnhbrF3?x+M%QdEv25>>2(F005){bR$MB2_rALsXz?r&O}SPN+a!y;Wk& z-Bp^DoKz(C4yq6a87eMctW=KY5>(u-8mm|a>Z{1w>Zr8oYN}k4P*%~Hmscrlky6nv z5m8A_=T{jG+f_!ptScYIFDi3j)5$Qj(RS8rPLYc`qr?46>Cgt0R5|ItLWGsg9r%>t{B-WIUPtPl5f1gzPl{c(3d!W~uy?08KLc$7^Rvn)!1sG&0HHbe@QkY6ta;r~LO2|!6%Ds3| z>CLfNr2=BO(p}g&rSq$SO6IM;N{dBDmG0eeQPK}|P*4%=OjS!c|f${80CT@RQZe|e(j{9P0Mjbn^zu+rk9-+<&W7Zj^LS! zPi3qX4^I;n7rvS(avvKg?nI&#gB{_D4QLfb2ned^)F-WYu~by?aWY7;AaGCNC1pe5 zj^dI+*z&XjrD;@QFLywpfYYVGa%ofO&~H|77OGeHGEl9cURJJfHszf{L12+Wx77=U zO<0bC&|;>7;P(uL)vRQN-%-~Uavd%y`0H>Kz&w!(?>f#a&|e2D)Lr#gz#luNaNopD zVOspKg5Jmhh2s@;g-dB4BS&ESD0|rFJtpjYn>9@Kg$3*x+Z2X!G=x3YLc>5?aG2*$6fMJ*Spa%6DP}R&O=>FLm=zrE@(A$tfC~K+cV*_ zt~MCjmf;We4?G4PC%8d9B@RPt1`a@BC3L9IWis@ki#fDG2L~P7!a&!WkkF0C>d@)) ziqIBoFf)|~2_LE;_pW__WV#naQqcL3$n9K+L(^l3(xZEj&NFF{1k0Ncl+;y7i^n07Upyd`G-t?3UpolLhzYsMXAOyOB|^^Um_Qst4IrAH%dmpUxeG}|^XBm9UZx&o+I1aAf z9R%0?=mvkj`x~6^{}Y^uZ2%wLs{v~^R)D+jz6W3Re+|~cz66);=724KJOqEZa|aCf zO996lB!d5JUji#PaKJ}yM}p&zhk&1APJusc_=7)vJqG@m;s(w;dKi37=OEZ?g$_nm zlfgqb%)x1{IIsy^58OD11iO^0gWIksg6WQ6@GE6WF#m)Q*#0dqIGMXGSIb(Jn*z_v z2@Foif%AvtAQ8QC5|nnib+Hz?-|gS!o@dv}ojP45r-lC@*UDQgccJN(oY37|xfGwr zauS$(a-6kPxxdvn$Q|r;k~4pP zNKWy*joh3$MeYMXQ7)|6SWfG%zTA)FI&%JKO}V9ICAkY#@^VvGrR1C)MC9Ho@XHAd z@5ml1Sd+aLz93s>IVIaGG$Omw(kILNphK45??2fM-A37=m9MfjRi9+jua?Pr+Ly>e zVFj}FgU@77zkDJq5PDxWo$zmS_>*LBHeQuoPmhyzJsKlhfC!UaojD_mdmkWslH((r zME8_^DRD%${EwaN=SNK0k0-2UU+7uL-dHt}^{X1JZlJUDDBpZPHV# zP0|h(bNORcS|Sm~^V3taSYkG3k|C0@6^YeJMlerj%vRk`(R9j1<{#Ov+GuPzpBP zCAC)6CiNq zuSqpLikDLJVN0DxL`c0JKPNT$Do9H4te+GG>m_w;#YO7E2L~xmjI9)xM3ai(v6MPd ziwn@Hx-7L8nQZH#>TqAj6tz0s-?49Jhm?Ftv7B3_R_p&7?sxu|W z<1-}tXvva|g4ZQqH^fUOCbA`u9*mGgN}iV-`xPYlIMq+`kdv3>GT2ozrQJaianDxr zwL4AHNXb&NpcgNx@)#?5#amZ$R9#EbVn|go@hMF5m%pr}I8t2FYFt3_)Qf$ITS1!= zFVM>p<BZsnN~iYUcIg&o-*X5oP7#4!&buUft(zFTrl+$1z!{3Mnwp1kmnlzn|p{QKD;@g6-t z@zI&1;uHBU;={oX;_WC~@h=lp@#lFY@k=N1;%-`4ajg-w_;e0J{FRTYxQ{waTxLK< z{Np1ragU<{;>(KrVpqC0#H8;niKV;Dh)KzhiCtp1bbtH+Z+)faca=a+I zB@rt+@FPsLD&eeX1}#wZB(JY1_LHaRYRnPQw|INeQ!7kSm11krhBFqTXV9jiV&ev) zPoJVhO^(AwYm`+)8C?+3x(sPi@?lZYVo8vwYU8fR<%D&SQR<=ynP*xgy>dk4Z&bes z%A`}|)Z%|4d4-K4y+PkZ#F3vxOoz%u+#i>SM0ym6BtxEyWVJpKDY$iCq{KE|q(m@D zq~Oa{k!)_9NHQTtBx>z~h)2m85&YQz5lOU<$l$1lNPf1nNQjr62v&h9GX0w(l9fUf zu|H@cvLR$3l3A-GVh(7Ev=Wp>{MY0~7K^1sqR)tkZ0qogM2_qT&plZa_V!#5ZiGw; zV_S!X(~|mxXPF(sRM3CI>7RcH_s4t{MwosQ_Fw!U{G^~*_;*0QFbMuk*r5Nh@R9rX zgu|WFgj1w$3P1aCMfm*{K)A*#TDWfeA2(WhTKG%IN#T!}}8K}bkx zg-3|LXiIQBU`4P_V@@!;XIwBUYuh`5!~7|NaaGp^VUd>v3k^Afq^StOA5YHPc0&9G z-CDc^|6F$!w4*u-*6!E}8kf=pbIw@`ilNK|Lx!+|ZJD})*dtnkHzd^r|JK6za9?d%puKZOKr(GifO=q1ARN>!@U*H;pgE#hV8x(b06JMM zfX^uxaPoX7a0*-`5Z9b1kajg&Ad8$S@M`0>KuPf}f%n1J1WMuY0&ja`1qw341#;}p z31kQb30$f66$ptwD&S${B0!$D7tqXQ3GjMR1^VPk0`GsC3M3{N3V2ze1u&a%f%Re) zf$CtWz!kWR0JB$AKqvzwP zZ2Sg_xcnI;L;47Mxmp6UEGhu~_fJeZu9gLw?YIw$Oi2grF_S>?ya^ysc^oJ{GzPSX z4g*CFp8?Hf27r8=eL$_^o*>FMXHWsh4kT~N1hMBRpn>N^kd?Oy=n2#SwEas51j4gQax6!}Xc!2B=uCHbF>3Gt^t=HPY6xtYxrx) zckR9zpN*ptA4mkl_qke&FD6Qj4`-;rH$5)Pm;FSX&(&3sPfUu3?^E3-?>X)=ue#|h z@2}Z0Ue2>YUbI&?Z#(!mZ(LI|FZyylZ!58eH)gqFBf-XO&nyyC6dyhYbD zc^xPjybBw*c$42;@ao@(@_urV;XNcQ#@q85#2Xa3$Frut z!E zRjV@(Cee=PHHFE8-K6lmeM96i2{hp;RWsl*>(Jr(cuSLq$WZ2~+?D4cy_e$obXtUm zjNs?l-`@v#{*7z9`+z|I*uKWvJ|I@vyx%yv56C`vw|}*BA5e+P+;{x44`5v4_c3|< z0NFTbUm;;1aFcb|hxqOTQ46N~2(x`4>!->-Rb(G%DFE$<{@DXWZ%pr%Jlq59gIf3a zz4w4Dn~!@Zl=pyLt*pI{-@8BnC}Gdz+Ac6SbY^ePbQcJ!ao$TG+yVHqhK*&F-34G=6Ac7Gn(22_)0SoNc&an=@@G}s&@iV`fj*QnHUGYEjXm%RxRzSKc1z+V5E56k_Rcg9_;4;`ZO-Ev;O@;{vxs^6Z#}=Y$G5YA zGP3QO{HrHGq#<@KtNamgM+3HIRhJ3CKm_++@J>YvAhNq$D7>%zjln^akKkXu2BjcpbQqqq4fJn*eOz z1+7N&UIFHlrdPnN@qpvy)|GFM;sA}a?JKD@PM+o{Cn~g5NXl5>~lE?XvBYB z7ElZT?%|#qXYC!6{LIhe5J$SQAO5aqcXPWA#awXK&ED?NZVE!6S{V>ciX zA-%kncLb<`uP+^eI04b{{-t`r0VsigTXGyZ1e`?_EG%9h@}pCML=1DuKh+BOYhbX%?j!-#ILK0=A`w8D?JlmlngPnBkww=O6X1b$$)ewq0YI|9zbL7!2l%?gEw);r0qC)S#n;ERfukqw7N5l;0Hbpzi|E#9wtk0RzySSTc{d0Arf4Eqwy19^xtz0>s!Z|$b7dMM?drt9H zBe%;lc1{uB!2KNIJ7@a&E7vKFHFw^+hI^;TaIUVpihHdQI%iHO=ju-G&HgAV<;Dq( z%|@xd(=-vp9zr+>V6!S+{~*?%S6^vzh$aTt<__?9P!# z+|+seEc@ww?j1R`S;d(Qu8W!AY`Z}kx5aCArsV7`uF&P*GX*aax!bQQX6pK`atm8? zX7(j6aaFgk&$yZcTzf>w%unxFF2&Am=H$gl?phRiM&*T>GTnAuKo2_)8ZqZ+|wUZr}O$ZDz|QGXKLS-%#BeWnYv_1`&KH1LEM5axI|M-t{C?tB~BC46=Q+0ge-K7SOmnd^WqN|oe zb2FGoLVe~y@*oq&;pLp)YrEromG3!#&FJ{X?i&vDe$%)-v4Hbr`t7*;g**;~oH<_i zJcq+gk01B=^N7G zo*UCih~w<+{2A*`kL5_XSB<^TjNm{@bH~abhj0|ZH^(L)p5`cAxG-jYCx9d0<}p^6 z=*y8XwjK+M@#28)pvDfJaN}%lNRK%jaN^7#-53QhcAU|gfzd8u7N<|Ue)QNNmD72v zXjJO0C8uL8V{|6YoYU>i8C_)=bB4eBkLpSqaF&e^j^1oWaYVCmqe|Bh9JHj;Xgf)b z&R;NIZeHi~^kaBR?|AI@HV);##OLWO;g@qRGi zHk2JQ@o>;7P=*cMxI7q%7h``lI6c_PE5N4waT+{PzZbg}OB^)3wh=oDhYuRlmSQEF zMF-DsPsd(}TpAcF9E}CTy9aK24#Y11su^H|x?-icF9#mKXpKFkmpZUz(-bSzA2pCN z^euKI`S`%`sL!!{ROY}bk&m(d>jndFGD>1a3!wv8m4et6zy1EXC;v`-JO>T`Vp3_`%2hrm;6-i$$*XtBqZbJP$z zn2V9_z4gZ@Vw#;Py+!VSW1?}W-p)haG1uf|dg-LLn2nW-os445pzshxTnbOatw=iq1#h{6O*&t(QW@BJSKSjb9bWu*_iC!ylx4JfEZR= za(Cw&?-;+v$nI%-x0v~_-rY7+4l#3|ZMvrcR*X-jL3gLLb&PE}v|H*CA?D@B{jL-Q zE(Rzc@AAmgjcKm@)pbq_5p%oxL)Xv8$}zvcJ?V;)laEPhO6WRsNg}5H_qndZIf0m% ze%CJZBYV;LljJU$4{On$Yua6=;Q8o8kaSnx>G5cD@J6S9^+0s6)?nv3sm^E>vxd$F z_m=3x2j6s_ebNvu?t8D(cd$D8Ky+MZuJXrdskFdO6X)V+j{=8I`Gl9zdJSfs^!M4( z*GJVmzxLmcJ_{1*Oyf_B?n5kg6vGpvI~iRa>g4!n@8Ft_!6Pxz7m{CgECqx{LrPOS zoWp~oZTh1-gt@-a!ot2ClJOqVo;cf%fQyHt$;XX4WZAaS?{6t~NQYWSSAXK`@bM!= zdoN723pyA@r^DOY_weZGV{R4g2b46Ut8YDRpV?H1F0Z@MKGY@?ZO0SVuJ=+TI+l2} zy*ZjUnifTCucdEBy(q=BOZ^WsK+L}l@p!5B6xOoO=y*st{ne|D;CO|5<<V z&DEp(&v@Vlw$-Am$9Vrvp4ItQzj(lyhSjM3ws<7uZq=}#u6QjmSJe?crg++aKh?|C zop>(LC)M9+m3Sy35Ye0T{W$<(upb9ktFvDAzRYk2b1 znbg04VtDB=g49p+S$K_(YScSpQF!0&Qq+UZNO<5*JJcyNKzNa{Bh)LDH+b_E4AhJ8 zE_eof^wUX5CV0)`+|y;79e77g#na#E6nJ*Ht<$(O40u{4mecWg1930(9H`9?{;CGK-Ak(Ui*LTO(2-79E&Ud;`@zMd@#dm7T+0sA! zym#0}!qVRtw08u>s?y>vt9S53lhQ~*qIaCed(sh4nRg0GWYRuZkas!HOw!I=hj%Mh zHPXXees|*D9nu|Gb$4B92GZM3Y)&?zR-8->vlq2r_f8B;&z4vkkE-q*>;|-c+fKP z&vuJgVbDjG#&%8xO3=qOy>{obGSIZpvvyfz8_*4Bs&=Cm1klp>pmxW~?9T;;mv+X0 z)z795j&`3ozR$FhgmzW(rq3}Fdv@uqkIx*9aduj3c+YkNXm+Y9Vb4HyUUu5+NzZxW zRCepGGS4GROLpFK8_zwjL3Xn`1kcD0ICg6T?ast$E_Mjc)y^@%BzB6LzRnR68+P(& zr_N(v5q3g3kj^Nm2X=W2dCp+${dJk&Va^LI^mU@OO3o^0>UEcmGtRx8;B|Lr9L~kh z)^$Te1PWeaz@gBXxTOX3XFy8FhRG zPs~&R4|RJ8ILt-U1a)~0A0Sy>yyrfXjr)vUIS0Y0KzxsC3ShQp?R4o^lXM}; zB+DFEiF8=z4avMXOx5=Z!;B&>%pvhqr)^jHkipi*8%X6eubIEw9 zz;im8T*=YvwR7y>Mai@(t8=<2FUcZhpmU{j7|9!(m2&UM8e{&sS z)W}I9b#sNZy~uG!YI6<>r^qH|Uvs))kjQ9(RC9^DdB`}JNppJ_W5|}OK68_GOvr<{ zGjq_@HOT+LD04J8AIJ*F9do~&2*{<#K+mL@p6eo zuE)2X=5pt=m&YiG+j4RxfyXOu&~hr7YRAD(#c~l3RLANpx^gFnJ;$d7uX1exC&%~M zqjKbZ5XarAm~xH$`NmgujdE#y*w2 z5pwRB?8O$R1#)jR*2PIV`f)DOzr_~E?r|(~sl|X$<8f*flf{MA*Kz5%e8nbK%yFq- zX2oUFz;UYxP{lz?wQ=#YImNoYsd0K?BgN7zo^eSL4aJFlnO2652N>%;tX`f$FU)x(aW?r{BZzr)7M z;&6~fsl%l3)^K(llfx(x%W$yue8W>Mzi>d&X2T^#vv4M_P{W^Cr*LAAI>W$cn{fAW zB*Tkxk8tEx4#WR=gK#Q7_`)1}cW}!m;=<#2YjDRC%)(W2UvM7+w!(2|Q*hMspTap< zM{wumiNdW!J8)RrbHdFmFK{W-UBa3WBXC;HN5T~F7I5szF~U5{3UJ}b8^RKz{%<(S z1;Uqf@^ACa@4?DK=5G?z*}<+1+HaTK!@)t)&2NF{t-*zp!Ee;`m%(~awQr3Cg25pP zsc*0rY{7ZGoNqlVR>6dAkZ&_WK*2&8gm0BwD#5eBcW-2O6v5bIYj2;G{=l*VUvEgZ z=)gdoQg2|{(!hf=MsMf-yuf|MId9)4r@$;zEpJFsk-(DNAa5gnd%&<^6mM{?Wx$2v z2X8XpPrwpi`)+6xI>1=h?rs!HB*0fo;%+vB4!{t*)o#wd_`icD$!_2L;=izsyl!bd z&A*xOuWoFBx4%74qi*WOp}(D}mTuz>jK8`6iEda}cE6KReQrvnV81G#aBjNvO22>T zV{WKMHNTTBS8f)YAHQa9N^S-63BUNNJ#KVM^u9{tFm7e1-o9KHByQOS$-Xd07jDsJ zv%bZ03T{ryoxU8J{cTS$h`u$w@NL(aa=sDV<89^xUB0pQ)@^)oN4^vd%59tBF}^$> zy=_EP9KI}-45#Jn%g-fYBpue^Me(QKs|n!K1+#B3kE zguH?jw`?J?gn!8{rBy6xUg}WiO7HmBD zZ@acU32be^TDu{@`)fmsMZ01@?rXqUFuQxY;A`Y48@p;T(`&H%1-mh%#cL(e@Ve0w zxNAeH+qy}8s%s2{#=4v1oNIt#vAV}ak87YooVv}Ufop9fhq|u)b8F`ba=L3%W@`}g zT)G3LSZnCqN4k0PN^5b-GP=tK7_-aCww7K}4>T0r-pSfho+-lgDin+4!&T6)ub-Cgd!D>vVV7c@)vuc~M zOS$P$rD~+VHo3uRmuhFwA-R2hiE8HK47nbSduk#2_qe2(ZE6`49^ClwrN#T)VCRosA>3-zqd?U znrUU!s<&(;jA@%0mbZKAeQBIwfwy?9Z)s_)Y`0}PL$?sxL}{Cy zF1OB$Hff&o8Ml5pC~0p@1-BsM8EF!z@V2#x3u%Q0+_pU`{b zBDN$VduX3h4z^31Y-mH!`L%2iUTDEk<+X-^PiPv{(6yWHKxj}}ytS)WGH7Dsr?t1d zBWP1^leNAb6=)*1WNmLAAqq+GieCEw#YL%V$yZ z7`43*y=Q2X1hu+Uu4iL5@U*v;pJzhc+qAaQkY@*l$F#Q#f@iZZv$VQEb7w{0p0vPm zWM{yTinPj}Rc9kbcC^^XMrUyRVYKS(H)p7}O|$|IDQC)aIkX@v8fVxuCA36D3un{z z5VUVu{ARnn{Ij8I?PijN=(F5+-ey-()UzOg&t?oDz_V?Jz-F@XtFyz0v1Uoem$M{= zqGr>bgR_x-lV(qNZ?gz=gl4~0TeFO1b!HM2W8j2XR(<5_hc36Q?VwA=ww?LK(Wyf*<`CoEU}oB$z%n67_og6x@2m! z1hIdRs$|;k@UWl=n`Blj-LT+%i)7$z$*@1|dt`U8wXnZgY-Anxp|D`WTx8Nfj<6yp zO=OpidawqFJ!Ea&X0Q$AEo40S$**lfuw!R7wy(#0pkoiEqOVG`kYmvnkFWOS zfMcwSd#}tCabuzbXs^vbVPms?RImAFQDfo!K(A1WL1Qa^Ew9w6F=LYg8n1=LA!8bf z2Crn@5o5p<^R9960b_-t->$3y@?vZ=%&r#>;$n2ixURDn(qf)orLKM(!eZQ(y{*D50b)BUs;xf&@nMqfmaX;A z;9(ZDgRSM8&|%1ZaIFwzz+tLNU9EN~uwl9yO05{_pJDv%Hm&!ik6~`aBdro&e_;}y z5Up$!Z(-a5yxPGK-U*R1dzK4GII#H>feEn!Ozv8>)^9bqZ^ovgP7 z4Pid(imcM0{9udTcdRft>|hYpWUSH4+hEVmQLMLH%V5XLKCI#Ax?uXtE38m(s$gl) z7_0^LnP3yv1*`#fiD3KR@~cGicwisx->c7TXkdf=%&Vf}S70R(x~sobM_>mir>iBy zHee}2l&jV)CSZ+UfveG!6<{)eZmSvi1YjDZTdS>C^j}8HNUM#r<6pJ)HLJV}(_d;M zBda)I!e3-m5UT{Sv0tQ!{i+}SpkFM&>Z*!IkYD@y*Q!R1e_s+g#i~=!ZeMeHvZ}KU zUSA%+pQ>d@O0N^B2C1jE*j<-=^r(ED$6W>y;;6KMwq4Sw&!|se zrCs_%y{Jw+lwE-0s;IFPgI!~Un5cQ_ab2Y;hN!2yU|mMibErFrPhCiUVW>A!K3%FU zPpFz0EnRNlJg8;c8(ou@DyW*83SAsf7^pZ_`CJGM2B<*}=v-ON^QX1K)?5#f;ir^y z#at>_&!^xZv|Owry{DPVqFj{ls;9qjkzD1$n5R?|fLxxIhNoDvZd|}_bf?TsU0h8{ zVyCd>OI$-KP^SfYI$Wg-KBvqIDO_~%E2jpS7hJB|8K<%#23%Li2dC1f^jmGW^`>Vk z<6H8oKU_MO%#3L8i`uGh2)6FQ$;)AzJ|j9;VMV5L@mc45o{U z{#sH(`lZF&>{>5o=%sxr+ggQ<)}^&`$y!yo#HDPyw_2d)vZbZ{rCMefp`~6ulv=1w zkENPeQKYqFKv@vmKcpF6 zE?JLOE~E}s99fyw9Hf&-3Rx~#3#6$y_*hQf`J+-L=2-e?=%b7d)L1n2)}veW!C3o+ z#iPB}uUJqTw4<}Nome!oqN6~Oi&&^lk)vX1d04FMf1?{dXIMdxZli1uRaj>=U87Xp zLRcW*OQY7OFj#DiI-~J!9#~5~DWj({3|PPM7o+&{`B%uP2BYM!=T~NB^`dQQ)mNJ& z#?pu%fyxj8|DjpQ2mVc~^%Pj-s7=XID?_e4>CI zRadgZYoZ3cLRYb$TB0sjFjq`}Nuv7h9an^6IHGBT3s+f5C!&57`Bu#{7NR+#=2qY# z1)`ZO)K-!c^r4}%!B*r5|^;LF* zD52&9<5hm77on za#fqRvY_HXU{y`>p`eY0O;xQhk)ZCzI#s%IfS?5hC{=d2Z=lpa6;1w^UQ83!vs(q*Uhz`=8E#kyI~h>YsC< zepD*b*`L?FYgF4j$)EYxSX4o)xS!kZMO0oLsGofTGgL8?m!IJhAXK~zho1!?4OIV$ zcAxDj`cwM~W}lZZ=ToqcRi6el)KecAMV~n|!Ba`3G@mgsu2U~GB%kmqn^Vxo6Q6Y< zh*K_K1E0babyG?D@}AcOVpAfS;-0nfPE)x%(w<%0J5vzi!Jg2;C{rekv7Qd46;u5= zp`I9p0#lUhke=>g?^5odfS!^&+)@czaGnGb$x`SRV4g3F{+;lZLQ;aN?w#&ZFH(+$-krh>98zOs z&Yfz*2vPw@zMblJ^-*XouAM+9;!&Cxo}F&g&QX^Ij-7RWyHQ{FeVtV$s8RInZJiLw zlu=gZU7e+Afl-CyO`R17Zc&2dJ)L5qT2W2uEuD-wM^WkV9i5cSGf`Cj4V`;kAW@GF z{+vMT3{jjS?wsaz`A~a0-kfdyEQ`%iGq5S)X==T8V50i2{D)K7YB@td)Ez)#4*;hU?^tWWbA(wmba znNRw6!kcMwg-_ntvYRfyaZjK9NOgqt9fHcudfbepQvB2QrV zWSb@t4^M$_RhyPe`%Z)FMVtGA=T2yAHk(zq(@rn%CYz<`zfRhA7n|!AtWIbG2%9NF zm`>Y~_?lp9gibRh>6(v^a87Z&*_yerTuzl&%9`EKNKT>lx|;m#G)|M5tC|-EAx>^U zoSHBk4NfuZjG9I-`Ay!LeVST72~FPn#+mLG^-P)Fx0y5m;Y>xtsF{T3%uM5~nVH?mxJ-1KikU&Gq)hmWdzrC^ zkW6oZY?&=$d`#SWU75EzXiPnLPMJ;)R7{h3KbiF3KTP0$Fqx^YD@-JaA(?J^7ffH3 z5}8Fq15A;o1DP!e?@PS9^q45j+DqWn<(M{%#!LS3)|gmHvP%{d$e54=o=Ye=xtQI$ ziAy$Ns+d4;bxS~wo0z*GVM|88jF?T&OiM}heVF-rI7><`ZvsC73frzDhgS7MP;jsY*L62$(Q%l}bH@`Ip`S zfl5N+>X)sMY)VN(+?SplSV~o>&6lvHLrP^4znA7KFG_lTu$Mot8cLM!p_jcc21>PL zlb2zw@k!j>gqJEP-AM{tc9$EV$VoxmXO}Y-v`K$qS(kK&pGn5*N|)dEib)rEJePB0 zc1dvwE|)XSVM*7XAD139O-V;M5tlZYI7!3R0+)OFBS}kl^p@^d4@ux0=9ZDO`bdJt z*Op=o=14Mh$(Che(Ma$myOx=?yhy&=td{=;s7RZYo|czWlSqhDkd|bgen^ECf|h0G zX-JgYbC#PcRYOw0!Z@qESBb5?MHOg z9+qv8*hdPu5SA~(!$-EB0+uZCu19x?^p$5FnnzH0=9S(?g-1VY*p-uQa7RaC%9V(b zTSsPHyp_DNMn|7qu9Y#-F-P!Upq1zB97kMdl9k^D2uI>_gq0c`^G1V$c9oeg-bO!` zXq8+*$wn8hT9su^v_=fdOqH}*pGF?)K9x#hibhTjF_kE2bw->vBb82TU`7aI6_vhg zOGcEF2bFkfHby_l`ILQRAw~-U?3B)23`Y1p-jr)n_eBMN(3Dn1;zc#Y!jz9S%|(X| zwUihmxJCV1r61{+dPJbs+mktvWkic+&XaynP(-8pz>^^kJ4EJ^vy&sq zB}7**rjvw$5JdIQn3F~~`$NHWi<4;TUO>aJ zT#=N2NI+)~P?49yGC)vrLy;i^9YB5AHjy$x2SD&dDv`>3@jt1w9g*y{+drr%5s{ee z#Xs(#1d+}lus?ep_>hoNnmyX`nggtl(vTt9SU-b0#*i5SLqC1Y zxsaeHEkD3wt&q4$7e7w@ppao|0Y505l#rZ=>po3Ch>&Zf)jq!Fdyvh&zdn4DZ;->( zsXm87V~|kklRn?}R*-Z1eLjY-N{}oIXg+&vK9GMHQa-;eGLUH_JU&wMC6MkbCO$U3 z8ITP!5I$*(4Uot+`aSMl0gxXz5rx|xIJd?+>h5RqCGRy(2uAj zj6GAk#E%&oc0I?ZxQ{FiU_FnRtdHUSNjzC62R#9Y ze2*Nd@jP{naE}R&+dM#+WRIS3#XMoBSdZFJuRPnjOpm}WnLMr1K#x!ggFM*oG>?ko zY&={KDUWcvRy;a19ghQ#Ks<6?5syM)Dm(;>1&=T>6g=|0`Hs#0{X0AJ?T#AC=R4pn z;*J=T(L3R6){e(nyE{Oz%8n@>r91ogzK%ZNjyn}ZvyKO#csq=gr;dhQVmo8$n~u5| zOgorDkdCF%H9IY!gpNpvA3Gufd5)tz2|IUaZH~9@@;WZlVUC8L+&V@=R*nx$#yY>X zN{&_cuR5D8KaN+RnL663GmaNWgF1UED2|rvY&w9i9FEkDRyyi95suO=KsvX^1&)!+ zDLU#{`i&B26FP$L?u}Le{W*Y&Gr2T#b|d*f?4GP>tDm!Z;SwMUC(9t2jTfI*rz5l{nRrFO81cemK~7 zB#jwNXgEn?8I57JG4LDmk?TkTV_c!)9;*8A4 z;5Pw2*NiYK$~S#S%#3Y{vo~s0!Hk9IoHxj4wv2Z~hBuggtBgjTZ#UYRpp5eMST~Qk zm5h5!LN~YFij3o)D>qUGfQ%~e6gOfsb&OI!{x;=gYK&Wq=QiG&UyMfA&^AofRE!iL zx;8HqN{q&4qc(_FKa5qBpbvB>tDU3TVUp8GlAB=`Wij?)-|wx--~Xxzcsw>)QctNs5L`l%8SVp zk~Ku!zl&Wzdo{sXwTt3tWHq|ms*6{UO*JoKpo_k>HZ>vbm5UhJA2pABi;HIZ2sL{U zfs3da@-*bAc8lLO+ceBYY>N$2#56PKVT&?rtuz>oSBp@BmNa}fO^arie>7p{LW_2) zXf(!|IE#V1Q8cSjE{liCIy4auB#VmIBQ*HV8H;nKKx(+=__$f-{tp(u$AwYcrI1$cmftR5KZ3zKW~s zJu@Uww2H&xCNs1`s*2&)4>QX-po#~}_%dfTmWnpK;WCRgjEZlo$}%=Of{L@4vodHy zc!~mqoH8R(Zi-%Qg)(JhWQxaBZZa`?T8ck9S2Bf_P>RMKKr&>tMv7ejC^F31Jcu`Y}5&DT;}h<1s^GABt&m%rVxO6^dR;wK4V63yNnTo-v>k0*Z(9hB4Sz z_=Z!w*q?uibUSTXPIGkK`>hJafv#ADlq$bXo)#B6EH3ZUx{7m`!DmDRf(sYZ;1A_n=S9KW{6}tge|zfU5F67Y%LzqREYdK zRV^XtONc1BJuSflLx`3&CN2LXI*3NF4lUbAF^D-S_bgU&D2Q>O-z;ySABgT1$Sfz* z7KpKluq=NH4v4z@m@Icj1&9o6fh-S){D-F6X)H+0^M{H@QY;}B>xa3rIxL%H;)gRF zBP_SK*@yar3oLaH(T5G{^DEVB$cJxE+$-12zlR{P#4CL=w}&ATtt-Wxu7`7Rl`F9e zriT~LeJeqKorex9W-D~}l!sV_PAg4xjEDE#HY>{YgNN%hA1my8dxtiP2P?D&bBEa7 z?nZW_4u@Dt(0KH?V+&iU?wtQ>SS5Cwk%g8RKqawAiiKVbC?%!(f`zyK4<%BudxfI!_awM%bcG<_ z-z3*8ZG|(<$0V@vWrfmn4yiSB313e^C8)tm4qGi+99{~ zj)a`H!Xa2vh=k8~sv*0xfrPa;k|E(4dxTH+c_GS#bcCR@VIg<)ZG@+9Ng?NGXM|-c zF(De_V1(S`7$Fj1T7(Ro03pxfQ-t)reMuh&nw;-U0K!hA{pCE7@ zI)wQlhad*HGlZ4WZXjY;ErjubRv?7?CWH+zJ|JwQAcXAPB_JA78ib9A4Iq#N6om3J z^&iZ;4TKxq+#k?)2ZRcQ#2=eD0ffIQtRF7^`hz^slOKu5^n-zPdmpWr?t_mPV;`Ao z=!0mvN*_%`;)4rXG9Sw!+=F}h86Oe^)`Pg00Usjk&x6A>=^p&n$%CEH&>o=2!-Ga^ zxE>C@y@SC7pdLoIw}TCxhaO3`v4bo$Zyp!AtAifORvxgzrGw>OJ{}a%pM!$(B_2fL znS=F&4IV)GlY>7N^&JNlj)P*R+#Q=Wh=X1=#2x!uf`c@}s~sqXe1qjrlN}EQ5@T zJRDL!CxeCuBphh9A%kjy3mi@{9D_Ri@*4%R7K8S5+8d2G5rdxW!5ikm3xhRdsT&Yc z27|lUkQ)o-0D~}1cpKP#`+}FiUmJHD_JZ#+M;qw9@Pay|E*mRl>w# ze}Wud5gB2MdV)N-_!z*Tb%JLR;28J2aDtm@#~1|MYl7Rrt{CY6XM!jfmKdfgVuFHf zeHc1fU4rVsWEiK6Sb|{`Oc?9LQ-bMcGZ+X0PlAEC8W{dVN`fp20vODSMS|*B=@)a> zK!Uud&=>P2Jc6V3w--!&H-eu+pBI1DGJ>;?h8K%9E`r|KZ5MHwDS{#-RTnY>C4zu$ zJQvJwAcFa|BNss88-k7f3Kx)B7lJ-S@)o((5`qkh*%rQ54ubj4z!sj|34#R^s1{gf z1%fhGj~4It0D^y*b{1fZ{DJV^MN~BEEe2l?|~SZ6BfP=>wz2B z`W1Y-=7B{N;uRKb;(?b?$rX(v-hmQ~uodCm*@3slmlYG9)q#cpe-$BP(Sd?FW)%!A z&4H?MO%>Mr$bkW=G!=c%#DRw28x;Ylz=1jy0~KV2yn!D|>J+7CxPdl)(G)Vuz~#JpA?=etbwi-hZI>MsDYG5ZWQzzq=B(^RTOO-pn(OZJQT$roPmMS*xU=n*g&k>NlK7p-mwh_ueJApxooe}29 zH-RUlgc0UdG=X5gYZ1xkFoEsYQW1}SErHMQIT1PT7J-|LixAZ05`jpdauA@W4}ns%SrAfh z41v4FKoICV34w&yClF%|27#^U4iLoS0)aUB^$!Za|9~b5-48XN{D5{C#1BS<`G6}Y zs}DSG_JBq;k`EbO^MJ=fc@NuA@PMyRU=M^z?STJVM-LK5>VUXsE)R!E=YZUD6%XQ2 z)w1AS^Qw^^hvVcz9It@91uYiZ# zAq}hPtbjk<2n_~Us(^Oe?+i)Hr+_Wm)(mz-rGRDFy$p-MqJSXQqzs8dpnzV}iwtqe zoq!gMgonUkh}bfq>tHMhiP) ze}J!hEeq@|eSi^i6bpy`dVmFJ`w9)zcz}&v;tGDQc7Uo<$qLzxbbwq(unHe?a)6~f zmkLl@aDas`ehO?!Zh-zGWeRjWY=96JObTW+YJj~6GYUg7Xn+L!843(DW`OAI01Ci4 zWPobk=Luj%Vt|Ry&I#*PV1P)#wFzQtUVx{toC(B*T!5#bg9#F)T7XHAY6(oqSb&dz zQ3-PLR)BbJI0=LxRe%Ov9|?g|Q-C^41_^76QGgaX?Fd20Pk@;w)CdF$PJqP|y9lyS zOn{mIq6kf#N`M>fhzQl}NPtJ#ZwN?2M}Q#3RtTw_MS!QUJqY&uLxA0zBnU8ILV&`C z3kX)pK!8_q@&{@+KY*TF*#~N>J%E@+zz0_%Jb*Y+LI>T$G=NUKDF<0uGk`^-5C_8ZF@W}p_XZe~Fo0rm-UeMaFMx_! z#RiVxEr4%8tOl))EPxXylLop$D}Z(ldIq%lDS(*sU%H;{_D4B7k92$_0;$A%NdEu?6^QAb=(um<3NyAAmIg ze+88|9)JzxWd+D49e}aNOaVBm;il34o*u3j+{C34m2!N!izXD#42Y?rerUI-62Y_&BjRNR{27s_fbOICx27uQlTLLeQ z1%T)ULIOD%1%Tq@C;~F71c1iF4+0uM1b~;K_5tzQ1AtV4-2u0H1AzWt!~ty|1Av!4 zs{s&6akJZ z0e~=5`vAT60DxdI;sD&o0Dy=O$pGq|0D!3NuK?$G0D!^EmH^aP0D#n~eE_dL0D$9% zWB__60D$ggO8_+%0D$#FG63HR0D$`;831?!0Dxlu|9^A(|9_P5|9{5e|9=V2|9@Py z|9`=k|9>`h|9`tp|9?>-|9|-J{(rE!{(pIX{(n+F{(n6A{eL&F{eMDW{eNE!{eO(J z{C~<-{C^qq`+s^M3^?^M7@6@_+WW@qdW+@P8~Z@PFZE?|-M4?tgy6?SE(L z?0;em?0;=3>wk+u>VLXa>3{lS=zmOX=YOzp=6@w{<$tVd;eUD~ z;D1^L-+xWw-G5QK+<#|{+kcN++JDL<*?$-5*MD`W)_><>)qiRj)PDfU(toIQ(SKtb z(0?(#&VLbF&3^;(%YO)k%6}je$$v|n$A5_+#(&zM#D6^+!+*4o!GAsgz<=9ozJH6- zynjwKyMHB-xqlDow|@;hwtpUqw0}d>vVVIQv46)_uYV_zt$&-wtA8W+seivBsDExr zrhhVPq<;&DqJQ_Fpnv$Xo_`I&oPRgUntyiAn19L5mVYtGlz*+gl7Bz0kbmZxj(?$m zjDK=siho!?h<{TThJR%0gMW&+fq%wQGcm2 zPk+9YOn>X~Nq;a(M}Lf+M1KM7L4S=kKYuZLJb&)FIe)|SHh-}yG=H~SF@M&FE`JTL zD}PwYpe=zhcOV30f=6#jd;eDM)-F?ck z*nJ%t)P0tE&wV!6%6?0oQ!=6pX5;e5S@+k9&K)qF^6 z(0o?b%6ybO#e4&vzkH(lxqNa`w0v}>u6(ESsC*1PqkN-*oqTJ-mwaaYk$jXgjC}NC zhJ1*SfP7B4dVEORbbNOCZhY4gX?$%bV|+I^U3@k|SA1zmQGC)#OMGueMSMa&KYU9u zIedyAGkpIDEqtr(CVY*}Abh5%8hrMC6nuVA4tzZw2z)f<0eoYq`+Lh~^?Pd|?|Vem z=zCU$;(MVm+MSEST zK6{egH+u&SF?+l>DtoeBBYWt69D84z6?+)74to;D2YXG_0DH^b`Fe}u@_LQp>w41N zfpqvlt$D+qrFojloq56Wm3cT6j(PtvhItlCetCaic6m8(Zh1s{W_h82 zUU^W0R(Vo?PI;zxMtM$aK6y!6HhGssE_pgCCV4Rn9(jD{6?q-M4S5oh1$kXy{doQ< z^?3H~?07`4S$1F-PpJ->vRkf;dHXl)^ym4%yfM~!gQhW zw{%9Ht#oTfqjVAKm~=Raj&$H7gmeqKd33l-Z*=I`WOSQhT6EIoPjroCMRd&II&_d% zFm&3#CIdUNcwZ*$t#WOG*ZS#w_vPjmJmL~|Q5IdjiFE^`t^BXi|P z7;{KQ4Rbs|0&~DM_j1-I>~eh*;c~b8)pCR1%5vkrzjD@@v~pZ2Z&f-Em?T(s9z1#&O>cyK#zyuW{1#qj9-nm~lVLjB#ZzfpIC1b#agCX>pW6 zUU55=QgMXhMsaQ|J8}DQFL5igBXR!k7jbnc3~`WL0C7-^^l-Je=y1T^+;DLL(QwEg z#c;VNnm2gmYiEx;DeQ=6;ad0MfWpHh6S#V%rO>q5AL2ySoHE=#3 zDRAKc9dI(<5O6WK1aRJq_-{L0>~BUW;BNu&({F9F$8U;qyKh%5uW#4mqHhS6mT&Dt zif@GNeQ(c_ac|BuWp9GeSa0iSOm7MOKX2ZQGjC`ZCvU2s8gHW_4sTVV0dKw=^={#j z=x)3N+-_2F&u*gH!fvfUwr+Evsc!ZBoNhE#kZv!jgKp>ec5YonYHpE>U2cTVP;NI3 zL~f}^H*VW~DsIlN9d3f%5N`Me1a2@a_iZap>TT(1-EC@u&~31m!)>~zwrz^Cscj#+ zoNao&k8Pd2f^CMkb!|7UXl<~dTW#`=PHp{oL2c1qG;MG|CvDmt8f_2v3~dk0|7_fx z@@#c!%huxy1Xqipuvm25VQh-^qVdu%J-ZEWCxU~Fd}Q*6Px zMQra+IBf9YDs0AY9c*#=4{Y&%0&GVB^=ou}=WBQN*=tj4%xebRzH5?5v1|9RqiZ%5 zmTOOSh-*U8dTS9WZEL)IUu#0lQER3bL~G|>Hfsi=C~E`Z8f)Jh4QrZG|7tdc@oKWO z<7yAy)oM-z$ZBpTx@vMntZGkZRF|f@)=xbZXt4W@lI9B9GJ4QRwC z|7XR1@Mpx);b*}h(`UYG#Amy*wP(2Xrf0S^m}jh_dS$L^Yh`^CTxDapOl4wOJ!N_JEoG{Y9%c0;4`o}n|76@l z@ML(+;AAmV(PRhJ!DRYUvSbX+qGUWnlVpswgJk<7bYzT)74hT}QgRyBo}RJ-F97e$Vf{uJ@mJE^pSXnKeCo_Fm6;f1b2) z4`MVTFQES}e=tTnWm8P?cVWzX6WoX4z*U87oe;J4l zm1~SHQ!9+#qxC6TFzQkCcI`{iIl~V}d#h}T{=p@pD>~w$`%8kOo!+@bzrSP?y=JRX z^r|IV(TC>9M-L1ih}v6UAGPRSepK@64^dB?A4JWTzYxXwa3JdY+Ko}uYz0v_S{6ku zJ~lrp%*8osZ^zUqh5hsiu`hS zccj+THIb`ttc)}@jEpom>J=HMG%K=OXcGCUVsvD)vvOqcg>Mn+GR+a%kwp*<3LrHvaSUYQ6Y2I3b*ti2o%5nk;Wu|vx;Ld|VlM3Yc0V&rLV#EFmX z;be1J_;tm!@aYE6!pF?I8XoRIBHV_E3$I~=!duqN4fk7Z6|PC@hub6$ z3x6Cd8GbyVGpu4xMc8`d^ssG1o`?0cUk!VedNi!-!q%`&ED`pHZ(LZlUQpPT7U!^{ zyHmpwiSc2H)78U@`?+D)Z?%WEEGY{;pq(0e<p9i79W)T>RQ^I`;{>o|)- z%?|sAdYCzc7QHeLE%MO~^(;{dwT%6~U`IpKg0Q893r^L2SP&L!y5x5Hz>QD3_Sx;Km$=qhL}I2I|p;Nb0^5LL5^;>X%b7QcPTtRTv znD@a3mUn}D9Zv^)`|b|53T1;YMz09I6uThUI@TpPAZl8$M2LRyOfU6dr8(T-Wu|RG zVIxa|D!6|K4b(gcI{WTiP~GW$LC@&5L6iJf2ALUz2c`771xdWN3Ch@N5M<+{5oD(> z8C00j9;mUsG_cw6b717a!@#6V=L7YF{tVy4;?%{!^EpCC*TWkW^aR!0M z9u5nPaF+;tU(_}~dvVG9P3@oNSMwgsuj@NIe;{2IFYeGSrTe5ahx^i`yu``+=m;yZcNAzwk= zdfz?Q6Ma`FNBGXRa`(;dw)UNIL*JKNqUO7E^iLlmt;xrZ$@j@Kdh6qwdDG{B;JD9o zt*t(<9teC+`Y-eeZSnT$UOU5QnTD~?%QM4$`phJKlpnQuOV2L$E`9aE`>_38Z=2_T zc|Wz@;jMq2@J<@L*!#jBKkqj`XL)~!o8)~beT4TGOKESnKRdj7J4?K_dwlX5diI{z znt@YZ<*qxuCLbcbmR2wJIylMS>)xu_Uhi*D^7`00!s~^JwAZD@9iE$ym3W4yfAlos z-1BUjbjtJW{2iV_G~p@z*CNl$FMT~d%4T{t4j6l`Q`Pj;o*?OYV_KVsqjQl*zR!D) z`&G$WZp8jsQ&qGtIyiIJ@7JdQ|Qxj6C9Ct)eR z)p_V0SEq9)Tw`pux}N&TcjX2~yRNP9a7Bs3Tw7blyA~!4b!}|@>Y}%-&V{MYbdgx_ z%;kFOMVEE6{&ZP)b+ya25zAd9*95w(tF?Era4~Tia#71=q>QwSe`Nc-XZMTd1uMOu zryqW6p8nNi^8yDp&3k5_JTG{2#605^*LhP^tmdt9*PBTl+J1E-}_;uBW}-+?WUhWI$G%>%aTEv-!DtXWs`|&JW%{ zb6%Kz(RqI9KIdIEtg~9@64|nd$<2q0K-0bx6X`a)iE3cdi z4_3E|(#PQ5^C&%7pW{wy1wH+T8OFK^7-R|(izR1C{^R2_@<2M{W z&O72@+`itSW8X@LG1C?}+|G4!xRGS$prNAeP;*w=L1%iq{p*xM`|Pl{_I^#*?Pu{1 z+aLO|&OT;cg8gyX5PO$Rj`oXXOzr#DXxV@LB59wzs&!6OP5zv>^Iy+7`S$9ZF7tzP zo*h{`M?!MNoR^CO=Y0J*XUFf-~o}P1EdEJ9B2AsC+)#)8f)>cFn%o zQ&O1Oal_+gj}P;k9sAde*%PY_W(&uv&Gv}+HtW)%+F83Z(q~D?KA!d6=IpHXOLxvX zbWk*F`kR$9kLX2$;VnQ=Ei&HVG@otc4U$7f#a+%)r; zWD-i)6*hB@&fJ*;2IezeO|@rEvy`6s!m4dXtyRH{imd_H5#N#0?5LQ81-{YjLqcDS4Ez&A_V zLx*&1zgfuH>V598QH(CKdDQd9#&qK~o2A1K+N?Oe#>U!YnN7+)f161&X4(Y2G_Y}V zP_}u<8k5jCTr{1?Vx^mLGUw4c3p}k4g%2Hw00g2AmiKV923+HKBPr4yt z{kKN*GzU@6w7rGTraiN{FzxmJ-P2BY5Yr-E7f$U4^qRi(lVD|zP$R$A;3t6}&0r+#UynEHA2 z-&41F-kEAcADfzUal_Q8?1ZVM--4#PkF%e8b?(HeoTbC2&fD_ca{Yx`%lmKAEGtSM zSW5K$WjRWDtEH)4vZb9xn5C10v!#oVsij-k2us(+T+4Y0jTX+lEDJ}`6AMT3tc5eV z!@^A@u<++aT0|$fSnwB5vDh7^ZE@R2%Ayp(#?&lxr+ANjKIM?gg(+?QyQcV5h^D-J zA3bIE6}KsAJ1nQfCybt=<0&(x!nn=+zI49%U!^b1Pu{&~erL-b^YSp#e4Ob*bM}Y3 zdH3H_&Hp%{V{Q^9Yu;_xZkFGgZ&rBgrP-I{OJ=rH_nIB)BF#qMSZMZgsfXF-aaLx$ zLLIXWJ7vwD+P9l(cjud)JpIzt%jc5mgztMyjn0#%^Su_D-so{RopyMtX^WkXX-0{R zX${q8Vl*<}+>Rnk6PH$2Lt`T$D9Q#{0>n zmRDycjkMf8Y1e7qBrnzQNkO#pq^or%lRUgNC)wWrIWc)u{lp(^`oz472NOB=e@!G$ zZk{;r`>Kgcfy=5(ak|KG;-Xxai(X!!?x`4HcC47)n_YhAYCN4PE|lHQaxGieccV zk%rrvBn+(-n+)a~Wf`tdvDIMxo+JbA#RUcfPaOY=2 z_HXoG%($X2W4%v5-;C0?Fi6t(uZ%2JIOyhuEb~U zxJMJ0j+-v!J1)G)X556EdgJ!4mmhaNsAFuDalzO(UtWw&`*>mO`UAVh*2Dl=I>)p%_pZ~HmR+u0Bl6R} z*JP_rhK|*?{4B3sW!o`wMokytn%NNc*N8BR}}_N4h)>8~JX$)5uv{Cyl(< zu0C>7z*ntP4=S}ZwLfX?q;6`-mmJjEV7FRJ_Q+zb9sQnK+5uKt*Kds0a#NJnYG2qq z;^fn;5g{6nN9Zm;HKOa~<`LP$SB-eRG-$-@r?W<64KWze9jP+H=w^@RN=}Jpisu{6 znMW^czN_D(xyX{x9L+{)wtkqWS)gjBSr)9RDe>2j;dAP0hM$;}GF*Gro#FTI92uV6 zw|2N6dfEpNKEsJe*2CWnj2UieEj#>gUaQ8YTR9pDtxq&qqca*0W43CHIhLq#GbdPM zrScq&Fh@fTf*7Ll{(A2)r|Obn-I{NQ<+)xN)=KRiW_yho_M|jwSh9-Cu-F-9!*(pw z9M*C0hx(4UHR_8yKC9EC?x?3bA5o89xmMlcP@KBsOKs3PgbqoH%wLM%GaT{UR4e~p8s)ZP0Nj;8zl}7-7uUT ziZB>MkJxz(z2j*)baJHjP}x-yLmk#M45`?aKBW4@{UPqxjt|j#vVMr?$K^vBbNq(1 zR@e>+Ytb8G)h{=MlxSC(q?D)PrtwTAfAm?E9Q|!7_LGxT^ejVE5^d+GSj{$6NpKpX zGRn1AdA4VXa{5tE4^0y6l$*&tBK)FT2<%je+%73bvC_gD% zP2S?wfL!JEayi>$@8xW_T$8Ke|0!n|L&?qbijixzb(M3UU@jMo(!&k^_Ct1kZH?^N z^v|-wN4I6s?@3v^?Q3LB_)BE-!o6gz=UU17nvRy8peZGL=SQQ=kD3e_>68aDA8((K zaX-94X6Nb^GJ6*J%LKYlmnk(LD`TW7FJt|!Oa#3@VO6i&? zWtgKTwcy@>%__j^h#=1r9d^dBW*ZXqerr`pK9+@8+$NW0H1 zxq6%%zHL1>ed%(prHdbTi-9dSM_P|NtXh`q@~V}?JDI~d#602L4L!~I+ja}5c*H7B zLvJ9bGkYed|CT=I$1bIR`2U#mk9q!>+mHGDn8S~G`zln4^w)>6nX-`RAB(j(O&o zTaNkUm_v?vWz0{;oMg;H#@u7f zH^v-e%qzxRV$2`LoMFrp#@t}c2gV#=%=^V$U(D~toLv zM9e?LoI}hr#N0y6C&U~=%p1g9LCg=toIuP2#N0p3_rn}N%v%)7%}JIt@coI1>-!`wN{m%|)6%!|WZILv>;oHxvK!`wE^XTuye%v-};HOx=L zoHWcs!`w5>H^Uq=%qzoOGRz;toH5K3!`v{;2g4jN%=^MzFU;@4oG#4c!rU#)*TNhv z%*(=DEX=>coGZ+;!rUs%r@|a6%$veoDa?<;oG8qL!rUj!cfuSe%xl72Cd^;LoF&Xt z!rUaxN5UK=%sawdBg`-Qhf^fx5n=8S<_lqt5atD8E)eGbV9pQb`Cx7j=JQ|<59aM) zt`6qsU``I^;b86!=G$P74d&HgE)C|-V9pHY$zW~_=EGnP4CcLHt_$Y3U``9>v0&~B z=Br?i3g)F?E(+$KV9p8VnP6@S=96F!3FeJpt_bFbU``0;fne?j=6hg{2j+EPE(hjs zV9o~SX<%*!=3`(E2IgI0t_9{-U`_?*QDE)_=1X9X1m;CxE(GR3V9o>PIbd!B<}+Xp z1LiGYt^(#KU`_(&Azn_NQYXI`*4mUpe-VW1l$ogJa(}_IG0+H}-2| zUpDq%W1ltlQ)AyW_D5qMH1<1VUo-YEW1lkiBV*q&_7`IxG4=~%UoiInVxKSe^J3pF z_UB?BF814EUoG~}VxKJb!(!hn_P1gmEB32mUn=&WVxKAYlVaZ}_J?90DE50|Unll& zVxK1VV`ASW_E%ybCH6~VUnKTFVxJ@SGh*K&_9tQ=BK8|%Um^AnVxJ)P17hDF_V-~Q zANK2EUmo_~VV@oL(_!Bn_Qzo#9QM0mUmNzXVV@fIqha3}_LpHF8TN}|Ul{g(VV@WF zb79{W_Ge)q7WP|VUlsOGVV@NCLt)<&_BUZ46ZR`%UlR5oVV@E96Jg&F_6K1f5cd0E zUk~>0V4n{5<6z$n_Saw^4fe}mUkvuYV4n;2vtZu}_NQPU3ig{|UkUb)V4n!~gJ9nW z_IF?(2li`VUk3JHV4nr{Q()f&_D5hJ1ok^%U&BBC1+h;7`w_730Q(EDj{y4xurC1e z{XtGY$lC|G`5^xucJadps4)Vo8PB_T>2D#lJ ze;edzgFI}IYYp==>k0BXLCz+~%LKWX zAiomiP=Y*3kP8X&9YIbb$Xf)ti6H+Fi!94?Tj1#+=Kz7@!+0(ny) zHwxrGfgC50#{_bfKt2-4IRbe_Aa@Al2Z0dkc_|?G1mu^191@Tx0&+n>z6Z$Z0C^iAHv{BffE){uM*(srKt2S>c>sA0 zAa?=eCx9FTkY@mL2|&I8$O!=4e_;CqzaJR=z~KkhKJfH`nGaliVBZ7Z9vJq(sRtH4 z@aBOj58QZQ!vp^v81KMw2Ua`q*nznYTy@eTxVc6 z1D_cf%)nU&mNM{?fr$*--q@OFWz z3*1~_;{yK{7`MQ&1y(KaXn{EkTv=ep0v{F_u)ui*mMidDfyoNoRbZSFoAgqTuWeA0-q8X zl)#w;mL%{Zfe8uRM_@YwzY!RXz+nW|BJdP}nFw4&U>^eC5EzEQDFhZF@CJb?2;4wm z0|NgK7=OU=16CjK_<*?wTs>gt0Ur+-c)+;>mL2fwfJq13Ibh2HKMojiz<~qS8}QtK z*#=xTV6OpR4H#;`Ndp!d@Xml~2HY}WlL3DW7-PT@16CODz<~J$TrXgE0iO#PT)^1^ zmKN}`fQbd%D_~mzzX}*tz@Y-x6!4^g83kM@U_Sxh2^dbmX#y4#@Roq71l%NGBLV*i z7)QV{0#*_5h=4f+Tp?fw0Urn$K*0F{mJjfHfXM^g9boGKKL;2&z`+654e)G$Sp!@e zV9x+w1{gBHi2)W2@LquF0^Am0vjBeu7%RY00agm|P=I*?ToYiI0G|XHB)}N~mI&}d zfC&QJ4`6!$zXKQ@z~KPa2Jke1nE_l3U|#^=0vHy+sQ?xQ@FsvM0o({+LjeB)7!Sa4 z09FI=7=XC|T!le)0^%b80|7V(z%l?{0Wb-GI{<6};0FLB05|~P^#?ycc=o}U58iw5 z*Mo;1eDdIh2fsUb+QGLD-gNMvgU1|vX$8a1B$GdP`3&*c;oC?RIaNG&U zmv9^j$BS@W2*-bLoCn8qaNGvRXK)+_$6Ih*1;1aNGmOH*g#S$18AL0>>Y4 zoB_uZaNGdL2XGt!_xEwX9{1mIKOOhSalae)uW>&b_m^?M825j1KNt6BalaM!PjNpK z_cw9B689f*KN0r_ala4u?{Gg3_t$X04EMiqKMVJ#aK8!nk8nQ-_jho=2KQfZKLz(k zaK8ihFK|Bs_ZM)#0N(e(J3V-B2k++K{TsYvgZF6gt_EI?>^xD2E4<7_Z09h0^T>kI|X=e z0PhAM{tq#Jh~q=79^&y3bBDM(#Lgi;4l!_ub3-f};?)q7hPX4tmLYx&F=B`VL#!9# zxe&93xGcn8A-)PRRN%HlEEM9M5YvRXCB!Bn{s=Kfh$BL*5aNLl^Mkk^#O@$I2QfH^ zvq3Bk;$;vMgSZ#Owjh25F)D~dL97YlNf0xFxDdpCAie`J9Ej6EEC%8&5L1D;3B*Pq z{sA!#h+{yk0^$)6bAY%4#10@n05JgQ=R;o}`s>gqhkiHot)c%6ePrkdLthvAv(RUS zekt@lp??W|Na!a*UvQ!{ha&+A;5ky<7%qpyJ&8u;(a3)X39igOG)?lMBwE0DIvSPW z$~{DjN=Qg|qe5~3CRzEzUkTY~XbqA#VXoIAm?9;eh6>4Kz9tVRpbGJm0QN`^vzNtsf#Ji(EDiDpO!bDyCFWGBG*67B*tE+_S4@UIK{ zD?e1SPj)kEuHc3KNDj!tM2T@6g)V6SMb>PvDxu(m)+_l{T$NO~2y?&5D!_h@lTv6# ztt7w84jrt@DSU>xKg6q2QpkWc{}fkMII_{unj<$HO_m=eDUj1d>sBa%Wkhl-#G6M2 zN0Ja%r4**YDoD9sdn2bX2lj>%SLGE#U|Cw+SV^H4<}z}>c5bM`99WhWSBEJKhsLW1 zH!3l11UeaT^s?h&du!zWgnb$z*(rAztwYh1BiSv7Psk@|(Ic)(D2#&D^vc1RgflRB zLi)rTkyEILx&7j*l7bE_J21FXiE%@J?ZOxFE(}AvFdA)5b~xt~p z4qkG!Fy|=zK?CiWFLc8>b7q>GR+xI`_{bX7QNt`Il=CZ5?YE??lrgQc1yT1XmwCe^uqTr+j9k7O6uSDovP3LkX| zn!`1R8}%gG{4ltXAJM8cj-W*(Im2LI3vm4>XZU;AM~_A{MS5@-HKFlfD~=S0GXj?S zDajeW3QgtiQbm(cGjs%+ZMd1iKh1`4RC8f%d$~5h+My%V9F9f@SLgLlyICC7ZnRh2 z{nAmt+M#V|&cyBbXk>6_S&r%sSlwlfO~0C+{kuXgC1 zX>P~u-u=@~mZO@Fw#4-rp8u;II;WaXIO8C9+?cc=`y)5miZ6=$M}XdS~j zk}9@}(-mFR(c?@!T@GzbimRxIrb~0tbQwd`Xp}PC+`n2&LuXEf*cRIa;gwmbF}tgu-rnG!J>u($M3$sGBNsIK#!u zq2rK14Kyd9>F8<>&PJzP>wkCGP6?e{>A@!GG^6u4D0;9&R|S>yP$=P3j>boz;-3L6 zimskF6fm31fiIqa20Jvy<@iA1fF!|59tx!^k`xDhlup3dujPEu*gwNeG{)ulLLpvm z*ze2v{$Hm7i=Piuo z{4?7{Jb{DSMJ$X-wv332k4uhNWnpd-1ACv8yb%2+Fj;~QZm`LUsN^N6CJE<38txd5 zWXlV5jFLljHyKI_O~#EID>-cK_zjW^?IeeqNc!taPS%~Qrze@Ht2ahZGD25!tnLID z3)Gb~)|Dg%r!LTyoS-W)1f8=*i;~@Ad@Rf(tj%qva8~-F z`Gb3rh(^$kCM8G3$Hc_T1m zaRY}L14}1HEsPVw(f+m)zX%6sXaC<8g(bub$1I6TgwytaFC|=p|8wd*qtQVOZXVY0 zpQD*#W@*h?X&;yD8_V~Pie4Ve;h|RMRuRdZg$X>UJJ^Ogc=);a{rVf>7n{smDW2l! z=N;i57ai)Cz)OsY4V~-Yz==Z#OpPlKk&g z_KWa^i;(>5K)jO^f4?<x>3}XICmuaMqL!nB=Aio>Z4&M} z@#o;z2X^o#8r+-z+-_6NrwpD>hlJQgz8(n+;}*rmCUX9}r_k!3J@9i0afcS<}7E+B02pAG)H8wZbhr9(oJ_@==3E{B8eWLsTB zxIg^|AAsn2sf%_<*Gc>k)b&nGh>1-~LXQNa|37ZvIaAQnD+(T)9Ihce&K%I~8!Mdb zVZo76koAz4P?H+Q)!=GMj^Ju>M{;!}#&S9Eg@Num|WQPHSOPW)9a!DDD!$sCh~QOQvpljx)*jtTk@n!rSp|MNgW z^AdhFgfryefR&_4*F>S-R|#S-}p;@5^5)pgolO0BnE$7 zz@>yXAlTkKBv>Eb-*hz2`GNQ9-yaSB;&w0_hIG`%6#W##175-#P56DgXV7*>po53) z$|B+IMxt@N3>rmU2nkN`Zxirn;(yu&q3>!{JoC4C@o4<_?LI+2yUkEL*scN+-tL;; zmO-POI2j3!E{uo=ylNWNe_vno2no(mG!51VpB=oueP|pngGM=<(fXhr9`L+fXu|L7 z`}W)V(C__!)^`q#<7HqShtT?*f17|uPoa6guTM!!V(@yx{=xR~{@p_3u#6cJ3}vzs zoNxGMM0J=4dMYk)yCT#zU4^FM0k?aHCZNSv;_2>65*!O$K_#?nt7;Q?<8N_;QFybG!l9Ms+8Xrb}Z zNU%OwKWy{&^&M1~;QWoI;Q_A?*Kzs#bSX~9Pdpt;$^SWGsQbk$`F;Fi@b#zjoJ$&8bsB#gP;i5D9@Wv_ z4|dwr&_O-?ZT{eT|Ib$z>OPE5=8RwX`>&tDU-AF>aWXjVzrT?F(`N8j({F9yr^enr70=Rk05H7X_0^;{<|H;Kz_;&PX`glh}!4vI^-x)SIV z!t+i7-FWaBgc8m=l<=977|!A7L#g>ITn5w4#q**23w0-P3Efku2a3y3aTzBr;TaC| zNpZPWTy7SZ2gK!Zad}o;UJ;kK#U%vdU_BqiWvaN$7MJjBg8Aj*vQ}I+i_0!?2_J4~ zrwg|`Dow@ZOmXQUEM_d*{iQ3nQ>y6@ikGL+0 z9$(O24ocKcQ(Qvu8|vob`Bvh(1C;1~aub(+;&OqwjDZp@w^Cdeip$mFa+A2+1tr?= zLMT!DTJdx)dL}_#8A`MrLvekoxb7{khl%R~aebY*enMQoBCfv|*R#d-HgWx%xGszK z0k#JN><^keSPp(ZP#vBhFddpe3BReKoFp#I#N{+`IbB>1elAcuPjNj!Tn3BFC~+Ap zE)&FMlDJ$eE;oqF?c#E`xI82-kBLio2Eu+_7MFvc7gT>HuD=zRAH`*sxXcrmgP#}F zzENE76qmi?^1HZ%z!7X`@HwLP@A*Nq2dCrnhnGXQ7Dr;_zvs`?(rTLSZ-cpo)s$&d zEzQiVb#=`Kr~mqEZf0g>Wu>b-ZOW7>XcihG6<8;C=UB4+CPF5(=|jovTKZ!e&o}EQQo(EIPBTgdQs6)y6LI~ zsFpA;9sP|^PyeaU)#dDxb5?a8>C74Tv+u{xCATDQtbDq9Vn>FOhw{9d$di#A{pLDF z4<+$|;YB7H!5h4dKdF4A?Ri%6%Cjw0_+QW#Po zk`IzAk|WYgq-jXzNE4Ctk#vwoAgLiKB1!-J!T$X5gB?KXL~2H=MJhuoK*~Z&L3)Su z0_hRbZKSJ6=aK$GI{f21yANpx(k7%eNF)*uDIRGFQZ!O1QUH<{lFN^8tUZz)k`{# zYh$@cU%s}n-AJuSbzfWA3Zx>W9HdmF4_{l@S4fYM?jl`By7;x3J%w}>X+P3Vq|INO z*gueHBtFv0uZ`?dq=iUfNP$Q`UmI9gBuAu~NY-ELS#zX`Ncu=RU+dTrNNPw*NYY*gHs9k-$5{dVvoJ~Mlf)tGu`lXDWkK~2qg5>a}l(j>$LNfbO!WtuuLmG{w`K6duMN&YL z`clOH7${=2IXB1NrQ8q=!hi2J+Y|Nav7F4&<_jkoF>N zN7^uu!>&dmkdg^!77NYe*0*r`aSNQMLH>{z5xNW%xx z*da*rNRk7o?6>|@wil_rKZR{XszNI1|IFqgrT72MenNVK^sN6Admrg0(&he->{+Da zNC*2ruzQfU_P=M>Be6)L{&#F5(sHCl{cqVwq+le!{x_@#l5_uSb~chNl4buZb~2Jd z|4UX6NgHWc{|iXDk_l#{rsz<8qd&(9g<@P;c(~v$Qz3zL=K1I6M z_lUiLbgAzldm8B&(t*AQ>~5qjefQaQNDPv&?;g7fX<6T0HWn$o?+zP;rUwL!AzyU9*Mnt-I+cY_^?q~3R(RYsESyT)>mzVu#WyL+#)tw?pfSJ(=qqTb7F z4pM6GCH4c-tKN(36QsLH*LyFp7m-f&o@b9D?e9Iu?n2t!dzSqJiS9ka3XoRzo@SRK zEkp|MJ;eqh`Skw9x*<9Co@8etS@)h`ryx!2J|u8z zZSL94u0^7HcCmb|MMph9?x@QCXvwH(O(7m4RL~8C{$JTcL!ImQxbgyNzkW#u4!5-;F_iFYL z(w%OWz1q#N=aK&Err9G%`?@K12hyf)l3j~Lb`vbGTf`@*~^?j+W@JCPlaq|?2M)kIS5UdbvVNp~l(Kf2=Cex%N>6>Kw7P1ka^ ztZNxtfRx#_l>LnKt}Bjx(Y1tqh;+MaF?$v1eAgoOWLGSE7-?VELUsqz#;zE4O;B-uKBDK(vQvnwjZgZ)1PhX^kZv~$~t}7{7xS>6X|oOH~X&Bi+zstu+x*h-RZ$z zMLO5%&YtXaV-F+k>vUzece=0}k=At1W693BY%)@Or!%{x(}|5nTF~jp26Q^GUPvyT z_N;y99M%rWs&h7L);WtcLK@dOlO5eTgVjVD+G)osbWUfbkbZR7vV9#kYzIv$qrNYFw(vb6Lx#YWOgIc znvO{<*)fq#?l5NKk(P8AvC$od>;j~K4g=P!V*=~aq0ibQ*>#L(tvbfBW=KXIW7%;X zdhF;9T~-rmXvY{KM)bXdlh?w~t~w+O^rH_K|E2Qdzqeo8LZy&1~0XKO?w?=22@FbEh?vxz?J&oNrBM{%TEQjv)Qn zn#$~KO<^{*erDFT{>@OWpBR4YMG)B2tXYkkKAw!US&Ti-CQt*;qJq?xU+ zm}#vq8S~Z`%*58`jDG7gW=!i-W<=`~My>TRql6^W`iS}2@{k#5dBAkF+-F)^?lE;O zcbW2*J4_)`cFS!hwdEG`zU3zKvgHQzxaB%?x8)jhz2z!%q2&s5s^v0s6ls6UC1z*K zMP_r$1?G>I^9W)`-bV!~VgVuFx-T23-|?k{Uz+za-OYQL*5=(zee*7+ zqIoA%)VzbqY2MDHHE&}+Hg9EKHE&^_G;e0^HE&{WG;d@sHE&=}H?L=oHLqh1Ank7c zgW1x&mRZ-lhGCjlGs0$;No;1AWz94b+e|SL%_I}tOfY`UBF4R0$T&9(nAy#I#Mcjh4*$MhoU-;}qs_qdBv$ z(Tv&AXv%DAG-1{>PG-o)Ner)XB9qW)%)~VsF)@vXOlYG4Grw^H_n zGaB`nX^py!dE*#nVxtbD-#D7lX&l9jXw+uZ8b>lpjarOM;|S(wgC;Z3Fr4XX7{;_T zs55m9YD`6gDpS}nl*w)w!lX8+FdrI}nO6-;%;N?{=5B)mbG<>1x!54foNka|jy6a$ z`x~T~T@8}VmIeuCT?3b48aRxg;U~SS;XA#o;Ts*>@Rg2e_(BIY4A8y}{j_^SAMM=G zOV4iTp=}$wXp4qUdU8VtZP3t8>ov5|+6}Gru!a^|rJeK1u`ZPMeK9ycvpF&5~f2J4If1(5GKhj?HA842Q z_q2WeJKC=PEp1i*nl`I{MH|<@q{r32phwp~r#0)J(yH}OXvO-+v~>L=`bXVEy1(uL z-C1{!Zmzpa*Vf&k%j<5_1$DRRthyU?O5Jt(ecd(sW!+W!aorXAPTghtTHQtZLfr-W zRNZ;{Xx%w_f8AMnXWeOfbKNQWkGj8Ty6z+`s5?Qgsyjw6tvgCDtUE%7*Bz#V>JHMr zbq8qoy8X0M-JkTVx_z`w-5%PaZZ|!-ZWnD(x0BYb+d+@4+eQzo+e)j{ZK37rHq#Py z8|kmL8|a?e^>kb9I=Z2DEnQW+hAydHP3P9Kbb2jAf2yVEH?<`Ftd^i3)Qad^wF3Hb zEuTJH%cD=!Cew#%6Y0IRtLW{uE9nij3H0jP6*N)1oKCJ?M#tAKrI*w$p`&US(+g@B z(E+uwv{!8m?NS>}JJd$eGioDgtJ-kdtTv1`t_`Kf*M`tKwZZg=+8|oBHV|cU381BG z{pp`Ie)K?%FWpt+O}Er|(X}<6ba{mfubDybsq~H znZ8}EL|?5|q|aB&(|=XV(MPIf>3!AG^p0vNdQ-I|y|$W5Q`H=rU;UF>S^b?_TK$cR zss2iZRS!^s)%}!DbuZ;s-9tH5cT=;fJ1Ohx4r)quJ2k1gm6}l9Lg`jFQzNSzsbSR( zluC6SC0kufajR>nuT@o4PgNz=R#ibYRFzRxRi#vMRWX%YRYav%6;hw7@~JmfdDOG2 z9O^+;Hg&5ii@IEuL7lBir%qI*QHQEhsJ&I6sqIytsEt)0sWnv}D5B~em0b0fim!T2 zEvb4%MOVF~LaUxr^Q)dw-c?U1m#W8L@*GuPd4{T}JWUl<{zc_fo}|($k5eBj zk5R8Hk5W%74^#Im4^cNN4^WpX_fuyo_ff|y_fiKdcT;;RcTw9acTyWFw^OStw^5?X zEmTtFW@<&{Mrv{81}ds@9krnH4=SK?E#+0YnsTXRDf>#Ava6&ht4e}0s}xbjl>%yf zC7;r%Or}OuCQ)jYt0=|Fm6UX4JoU3;1vOByoa(ArO0`tPQFRrIsfvn4R8hr3D!U?v zO09^ZK2$_fuPVZ+Clz7Ty^00YjfxQJQbiDTrXr9!UJ*bYsPLzDSNKv}D}1Q+6U6m#b*y|ib)bA0wYyx6+FGtk ztuG%!vE?e1s9cFkDp#adl*?0#%jKx3av3V5T$=JPm!v$)xzxOJ4rO2dgS0FEPFj_J zCC$pekjCZxlpR>?!F`_Jo{K z_K2KT_K-9yyH6UI-6hAD-63_#ZjmF(Zjfqa*GZ+atE5cX6_QhSiTqM}f$T0lPqvnx zCF@I1la-~X$fDAdWKQV`GOhF&`LXl}`MUHl`Ly&PdB1c&d9(CS@^a~3@@(lI@wKqWHM<{GLf8IVoVy87?OG=6G-h6eNv-j966*!kCZPNLrRwD zkl%|(k$uG@$&O+zvZ+{;tSQzY%Zk;>f?_o?t9U4xQmjJ0FIFO77AumEi{;6?#j@nJ zVj1#6u@rf#Sb{uS%pvy||0H%5eL3BC@!R z2q|tM{EM3i&*Da6UU5BPUtCMr6;~5h#Z`n^aRp&qTt8uh=HOEqN^y4Xemk|>WV%S6-A$jqM{E(PSHCet>`WBvFJ7Ny67eGwCFi; zzvwA(v*-zNx#$sbw&($IqUauRsOT=Sx9B#pz33*fvFJLnrsyg`7F{8DMVE+#q6IzhM<9V48Iju5ko4ih#-2MLR!{lw&=eS|^L9zw5ZH=$j$ zlh7#IP7Ep9O2`*&CM1hC65k6q5PgN~h>pUwL}TGPR zBC#-(SY8-HEGi5lA`9meA%*^gf1xkoS?Ep7EA%4l3q1(CLN~&y(1kE7oJ$xNIuYXw z9SEI5dtyZ4Y(lMYCZSYlN5~Y~5}ZP7;!A-Q(Ooc=Xf3cH>I=+?$^uiOxL`7oTQHGG zFEAoL6&Mh23MLTG3dR!;3dRz*3UrAp1vFfDf|0~wlm%>G!EjGO@Bikyu(FPb@5uCBh4&iJ$^0!nZ(za4+Bx&ILb2vkSh7Yzw}KEDQQY zCI!7B!-8(n*n&>csDgHpWet`R7Fz`DaCw^G}Nm^8XU)<)08~=N}Vk)7bJ4Zn=hJ`=P$C!^A%a-d5b3Jd5R43+(mkMt|INcc_NKGXVH*6 zN0EG{>_D>|O5BRZHnO0*|eOSCOlQ?wyhL$o?qT}0%nig>w0 zL# zz1%LLc5a7IBezvJG`Cr(klQGf%B>gv$f*_f=Tr+jb1H?+IpxCIoKj(VPO-2sr%;%k zlP^ro$rXOc$rirK$rL`xNfX}BNfF-6`CE87=cDj!&U@jBoVUV5Ij@C#b6yI!=R6l~ z%y}wYlk-?e<~$Vga_$Kea_$J@a&8G1=G+j5=Ufv8?Gl>>{Y@m*$KjP*(-!6 zvzG}EXD<=%%U&ehnY~cBIXhbTM|Px;&JGs}vO|TdvV(=ovIB*&*#W|cY(HUewvW&+ z+e_$~?IE0(?JBg-o+q@+b{1M?I||LR?S;nKvxVccX9{()rwd19+X&UNrwNs_rwV1W zEri@`bK%!46Jbx*Bw<^Yv9KY_P*{~UL0FPCUYM7qC(O(mBmA5-TKFzYTlgYNOZX^D zQ+Ow9nDAPbn(#u_P~oX872&ZgCEx>2S>e_!Y2o@TNgz&fi|V3AcVn4DE9Fvuzw=w+1( zw6lr?8d(K`Az66>`K%m)WLB2oM`pU9KQmR(nfY1JocT#moB2Udp7~Z#nE6_eo%vFb zmib)pG4qMwb><_%)655g`a5(d_U|;41!H=!uc z1Zy)-38>7I0)FN(!K%z7f@PV91hJV11QD701i_hm1b&&j1Rj|?1amXD3hXmC3+ysC z3am2M3(PXt3XC&X3&v+M0-a1spp_{SsAmcU%9%WYY-W;xo4Hc(H6vcold)XTma$aO zn6X$;oe?W2&4>}?XG97zGr|R*GeQOLGC~9|GXe#VGXey6GyDYCGkgRWGdu;SGu#Eo zGF$}*Gv*5RWH<@7WjF{nWXut)&X_46GVBD&8McCi3~NDL##BK}hJ_$3!(0%UVIuI! zm?Ut^Fcvsx7zk!(=nHH!#tAGl^aLguIs(ItQG#(9BL$-~GzFR&8Uob}b%A2WP=R!Y zir{CulHg0af}lHHR?wO*EvQeI6jY{j1jXq;_<8By_!;Q~{J+!t_;1sD_|MZj`47|E z`FGM=`Pb5$_!rU}_@~nA_(#*L`TNr=`McB0`CHRV`0LY)_-uLsUzDE9PfE|`$ERoV zm!zlhqtjFPq3M6~=cj+*d#AtSyQRP3JEgzm&q{yJw@H7>w@81)pPc@HZ|l5^Xt-%@+;F0@r%-gu>*78rKvHYWHG=F~@$={VG(@!7Ohd{J5gKPhcFe?{6-{^GPH{OGh;erQ?@e|}md-#aaw@0u3McS;N9&q@pA z+obvPEz*4XlheHUhG`!Bv1xAnQEBt|!_%DkL(?4jifMEB(rL5!KU3}a1F5$Bu2gG& zYwA>feX0e&GS!SwEVJasJpVd@zEoz&6%YpL4&3#lXc zr&5RWkEW{g52UK{cc-fGx27ub*QYA**;H9Rkt)qkPL<%tr*im9Qor+}Q@`@UQU`c} zsl7a()NYc-b*6<8dt9av5%Xy~9MLgBi0-jQ8 zE>9*ko5xAb;C)F+<8`Ne=C!4K;x(jv;8mr(<&~to=H;in;AN&f<9$wf%zKyekoO|x z9`A9=9p2rPo4o5O*LfFHuJBH$T;d&1InO(oa+bFz6e z%$)biXmZ~9(ZsyLQ9xeLXl!2FXjERqXhdH1XlP#9XmDQ9Xh5E6)Gtpn>YXPa^~@8F zy5+G)o%2qP?#??hx+8Dj=(aq@=;l1q=*B$k=(;@k=$gEo(Uo}_qs#M>N0;QqjV{WI z7@eONG&(oWcXU>s`{?w%-J?_UwvJB9+b}vIZ`J5O){@abta+oqSTjd|uqKawW&IoZ z#QHh%f%RqNE$iLLYu1aA7pzAk&scXy9<#2GJY-!OxyKqAxy|YyxykArxyEW9xx#Xc zTw+y@TwvKpMp>4TA(mlefTbGgWl2W5S-g=B*4dFZ*71>M*1?emR^Et%MH{JM5k{(5 zsF8A3?no&sYsAJ%8!2QZj96GPBPLeZh=CO_qGfrFs93He3f9gMDQokHn6++1z*;fF zWi1+Ev*wJPVND-7#hN&Bob_k;2 zIFfZ>IE=*_4q;J-16lZCKNfP>hXon-WPyg=SgFG-Lb=r8lZ&~N6gp&!hvL*JMehCVZghCVQRhTbvThh8%qhh8vihMqCYhaNMFhaNBs zhVC(SL${fVp&Lxm&^0D^XpDJ!=pysz(0S&8p%Er)Xpl)6>SyAHdYH(eP9|iijR_oT zVWti>GUJCF%&4JSX6R5A(|@R(={Z!&bQ!WScMKIWHw{^sYllqCc3?L1`M?b3qk*Z+ zI|GxM*9ImqFAe--j12t8=o|RS=p6XYXdd{&s2ljms2q65un)XpSO#7)3A*t5tP{(i|sAlXQsAOy#C}V6GurpQ-6fu?#SQzsM3K%m742&rQTE@5m z72{XGobk0^%6Q)|V!Z0-GoJKw829?mGH&*tW{mZpV4VN|$-`j(Ax3xqenwmW9!5hy zi&5QAXO#6*7)AX=MnON0q3y>oMav9o_SV{`uw#=8Ek zjQ{f(u3e8$_pIgIChGZ~NirZMjHO=ev0 zo4~l#_m4i>_lMr!_lw@y_nqF-_l550`$(_qdq*$ndri0Yy`&rap3&8PkLj|$2XsN- zU3z}sE&9p6>-58Y{~t*EF4Gx(7wDwEQ98D7hz{@Tr-S=?=$U<;^pw6fI-swG9@*DO z59xEz{rYO?o_&>c=e{!f_C7m(Q(qB%O`nCnysv=1u+KoB)2F3R>r>Gu^vUUedL{Jl zy+Zn@ULO5TFPr|n_YD1E?W!jfd&BAQ z-cWi@ZxB7R*Pou;>q7_hdeS3%-RL2`&UC-tU38D$?R4kfE%fcZ8|j;R*U{JXuBI>V zT|r;iyOchscM*MB?*jV7-nsNYJ+tWFd#2Mr^-Q6^>6u7>-ZPH=u;&l$PR}pewVv;^ zOFds`BRwB!eLe4JojtE<%{?z@j-IEq%AQBGlAilCYtJ2;vF9dD-E)m5>lvd7dM?q} zJ?CjBdq!x7dj@IydirRLo^Besr-O#=X{8~0nrPsjdK$2&mX^{}MT_q#r$zOY&_a8P zY5qM{npaN&&85dc+tH(?ZSGOg*7nG0D|#ffMLj~=+#VindJmg6spkysZ}&;s&+cQi z&)tV<@464rUUcuJJ?>`F?sn5@H@Ydb%iToUxo#Y7pc_r=?ncmByK`v`-C$aEcNVR* zJCjz_oklZtC)2du2{d_k98J_6P2+S&&`x)U(vEfq(GGO`(^%a;G-|ge4d3lXLv=gT zpxwJ@S>4-dY290BiQOA%G2QEE;oYlgf!)h#KHW=bZruxMySwMnwsy~^ZRnmsTh%?4 zwzPW^ZGQK7+N|!s)G6J+spGqUP=9xQrGD%BME%h9p8C4$4fSc)OX`EJXVhC=kEvI? z9#AiI-K7q9-Ji2d&QUA6hN+ka#tZ0+hwLAx{OqCmyQbTQd3j96x8@GDK)A~L=ElY zQ~kR*RIjeHRF|$()SX?&shhhFQ`dDJpswiJOI_T>qR#E2Q)hHhsFS;h)PJ2g>aR{T z^-Cv$`o1%l`m!^J`lJ&?z1NvRz1f*c9qUY@p6`sO4tB;;dpe`2ZJpuN#?IjXHy#F1 z%R7CkwoWgqxznAh?{uLmJ9kqhoja(!&aKq5og1mgJJ(SUb*`rF?OZ{ncP^!pIu}tf zo%5;i&NU>0*+j*Zdqw@}BQs)iIzmBVvpB1j@XQILeHUXv*Y{2+FvQ z5X!IiK+4y4Kg#=dZ_2B756aVa7s~zi-IQDHJ1AG$w^A;&Z=wvhucP#~ucmagub?!w zFQwGAFQQbm&!gDeXH%^0Gbo1ksT6hlB#N|s97WLnhs3Qkh9isH&}3d4f_$b8NF%*S3zlvTZeaN!tqYytXCe znQaTnQ`+W{$F zhSb;kg4Egil+@Dth~#L!N2+SQO)71@K`Ly$LNc{pB57OCljN<#BvI=CiQC#sI^Ehu zI@a1oI@sDw%4=;P(OPRs#MUYjy0x4HYqgVdT8l^-trk*ptC0j~)sZ4w)ufPCImy3O zLh@`Cl3ZH3q@At#q|L3TN$XmVlUBAKAuVn_NSfEWmo&4LMVj17Cyi?*lYX}lNMBp9 zqz^4f((4u&>1hju^q?h+bh{;!bhRaobg?CgG}01J>T8K5b+$y3T3W(Lj+S6jRf|8V zw8e*1)Z#%hwYZYBElwmw%MOyLWh;r>vWax2WgY2Q%WBfWmKCHuElWtWmW3o@%Ulws zWflqEGM$vuGMSXwGJ%xR@{b5;`Av*!`9TbA`AYO}`AGC?c}H|@c}3jS@|?J(2*E~f0-rPt0*xXHg)7(yc-rPcb*xX3G z(_BZq-ds(*++0o^Z7v}WG#3-Qn=QoFW)rcYSx2mCRujvc6~y9Z3DMjvBFL}hb6 zQPO;x$ZtMQ%x^wIJkflBc({2labGi&$ZVz&$<1UUt{G26He-m8W&{z`oJ&k=1``vT zLByEm3}Se53NffTk?7kTM|5wFCOS1o5Vtpn5H~gl64x~Q5|=l75f?SP5$7~J6Q?)t zB2H@FM*P>bnfSA5J@HG^8sht=6~tFfONmdK7836_%_H7wnoYdgG@W>%X$o<;X#%mY z=^vr9={KRd=?B5l^o3B>^pQ~7^o~&2^on3=dQQ+bJtioc9uP!LcL?03n}jn>R|&_P zE)xzmohR&R8X?e|1_`95UIM16ivVwGBY>Nl3Baa$LP}FDA-<`S5ZzQp2y3zt0-6d5 z-c1DrwRYVz{Z(`)W)fV_{K?u=*Dq`u*N_5z{a0=pT=)^x5iKS-Hq?@+Ztcv zH#WY&uW5XOU)J~#zp(Kxeoo^p{Pf0a_(_dp_`eMo@IM<@wXc4@mCva@fRB^@xu*e_`U`kzO$ha-_lTkuW!)fs~a@<(gp>-s6mP^Xb|Fc z4LrQEAs;VpIF08u9LJw+IE+8hZ~%X}VGn*^0~60^pyJ65Bs{JGhetM`@X!W09@GHA zr!{2b6B{z|u?=bXh=wG5a03AE+Yp2IXo$c&H-zGMGz8)|H~8V#HF)7yG`QgxH#p#K3#`f?nwz66(AUxbUVx8S1d zjkvISEiSNLh4ZPG;oR#*IH!6(Zd*MYx3T^VZcY6O-17P(xJC5`adYeU;%3w{ag*z5 zxPJ~3?w13H`|3dBJ~-gG*A6J|nIjwb(2daLmT# zIcDH!jwv{zV*(E2_=kl%eq+Io?^vMY3pUm90UPglgN=5)#D+PZVgnryu|AG_Sa-)Q ztdrv!cDrK?yUB3@yVfy+UG5mfE^_o@=Q=vEGaPN$$&M!MIEMrKyRHWNt*!$5v91LB zrmhJ4yv~AsSZBoEsncSw*Qv0V>txt-bt3Fw9Ut3M$HunToyIoRoxs-B9l=)C9l(~< z?ZH~>m{?;S6|1QuV&!!>tf&r!<<`NlXX+r><8@isLv%&AMqMJ7To;GM)kR?u zb>Ub@T`(3@=Z{UR^TsCDd0=DfT(A*!yRgA^+p&Iio3WmC>#;6%tFb%lR$#Z(Ey1p@ zTYz0vHwU}4ZYFkq-Bj$Xx{27Sb>pxT>i)z0sr`ZZQTqk+x%MOGUF}=U%i5QiC$ z_iG94(j>8c&UwAKz{8ftqn)wP|Nvf5TmacvXk|Lx5f zeQh;HRa=gc)|OxdwM7_qtr>Hw)_^%$tHm6sRbujLr5IYR5JRlxVlcJ&7rvyXYf!(dDp235N>CrGicoK=%%~St2Grv!E$UvC5_Pjmin>xIL|v%jqK2!^ zqWY>%qB^UNqFSmBqUx*mp{oBM`IS}CP{mawl(`CrGE|{Z>M9sYRs}{0t3W7DRXXZ) zRSN1@RRZc@RV->xRV0dD6^bHN1){K3z9>YMCkk5Sipr|mjY_ZDj!LT9f{Lr!fQqbI zg9@oyf%30fg7T_bfO4&xgW6R!1GTkk3Tk831k{?UzsTiPzmSWnz9Z*WeMZixdXJo3 z^%^;@>N)av^E3YG8RE{AZS6)Egs~kbztQ35Oyw!$ z@ycV!LzRb+dn@-L8I^fRa^?S9Kr6{eR3#pnTZu+ySHh7Ql@MfdWfl@pnSqR|OhJZL zCLjYVW05|Ukx2K-P^433AaZ-9FLG0*Cvt72D{^J!Zsd~6?a29+n~}3B*CVG^u0~F% zT#o!xu^9QIVm|Uq#cbsJis{H#6_b%qE5;)qRQy5QuK0<#R`C^ax#APzT*W)YV8ts$ zPsKAtd&MI}Q^h?*UBxX#RmC+#X~ktkQN?*gLB%jaSJ979R&*mI73~N?MKgk3QI9xP zQG+;IQGqy6QG&>;C_>OH%m`A20fDX1AP^M_1f)WO096PO=@lGAQpFiWT*V1QWW^Cg zNW}q!e?=a`yMm5zs~{tGSKtxbD$t0H6>!9w3J79FMHXUlMFwJCMG9hOMFL_~hyO%5BPUTYg_HrS7Q#lvDw)`x7W%)_?lJcYQ`Q-=Uvvr-q&*=D${Y(3mkwi<3ITMpNhEr!d>=EFs0v*FybY4EdU zli(-H#=#Gl{Ri7u_5;Q$`vRkueSi_l-oVghFJSPpCopi?eHgIpHY~O5IxMkl3>I5< z0Txj<0t+r1fccm8z`V*jV6J7&uw7;Kux({Eu#IIEur*~Ru;pb%u*GF&*t{|WY-X7n zHl<7sn@}c({VC$%%X$8tB7p3hxdI-I+rv_E%AX?O1Y z()Qe0rOmlhOC7lrORIDLmXzoIEV1W)Eh)_XP-4n`U82i}kyOMG(olz8OQOPq7bB|CF*C0lcmB^z^dOV;LQ zm#oOmC|Q!5QnDa7zGO~rbjgg|@RG^7K_%mJeM|m8JxhK}V+84ui7oVCX432ztz(4n1g3hVHQgpbUF7lxz=&;_Sgtl-&=S zYxjcY*xjI+_TA7F`*vu8eKR!1z8)HGUj+@eFN6Bo7eT%3^PsNwnb2MKsnBiqiO`Mq ze~>lyUyv2{Z;-|IPmuZccaT~3myoIUr;v&EhmgOvJCI+t8<4NIE07Pii;y?A5y*4f z0OYZ)2XfEW0l8^whFrDPLoV8CAfvW&$biib>9!R@+HD1pCYui8u&E$bHW{SUCWI8* zxDd1LEW}_t2~pdQKxDQ95Rq*UglnTi&f3V36E-~Luni5_Z-YTtHZX){13`$kGziv~ z1VPvU5Qr@bl4T2nq}zfZ$u>U-z~%{wwz)#WY`YX|*#rMIl zi*JLU7heNED!vT9S9~6Pvv>%6rMM4#vA7F7Qrrq2C~gFI7uSK?iz~rR#id|JaWS~6 z*bFW$Hh_zZHDGhG9Be2SgVn`+u)H`QEGj+)<`o|UpDjKJK3TjMe59BO-d{`s=M@vc zv|fSF$fGTP6uZfCxbJJ0pOJ4XmEUSI5?&_2pnGQ2M#Xw0{a!af<23O zgI$ZagLf5g0&go`2i{n`61=u}DR@QkLhzE}IpF!lGr+Tpr+}vwj|WdG{*&{s=x5IF zqAxk$iaz9gDtevsw&;1z%c93QPm1p4JSe)AbGztT&h?^8IhTvh<(w}X%o!@`&FL%Z z%;_v@`F{k{kke39lT%w%kyBArl2cMtm{V9(kW)~k&(RgBa#TgK9BGj-M_9zo;S` z%9&p@FK2eq%$#XOQ*$O2P00CI_&57^;jip(gJX15l$W;Yf#WY-qfW>*$gWS10{WET|{ zW}6EOvh{`fY;~b3TUIE`78MG!xrN;9vxR4}PZXZWK2mrj`#|CT?7YIfY}7>ZvlkUE%${2~Cwpe$jO;0eld~rjj?eyU{V(gM z^+(oM>*uTw*7sR&tgo`3Tc2e;wm!_dZ@rs!%X%~Gn)OQ7CF{kkbJmfpA?rX^ueCd? z)7qZZVr|N5usX78tyNhS*0QV;YjIYg)sj_UHDu|nnkxA`a))DK0to_zKS$S4^7TrqDB3W@+I4dd(Y0b^bwdQ2ySTnOSt*Ke5)`YA?Yiw4m zH6kn08j=-a_0I~hdT04q-Ll-RPFc>@?O8jlo3pl9*JW+6uF6_%U7EGrx-e_8bxzhi z>x`^f*2!5@t>d#MTK@z6v-|-4vU~=8v%Cj=vb+MlwLAm8v^)eowcG_gu-pLMv0MRN zw_E^?Sw=t?Ed8KiOBbl$(gy0bG=kbJb)Y6oCCFhZ1yxy!KxGy)$Y#-lEEYA$Xpw<5 z77<8c;esTVvmn0Z1c+@p3_5Mu4?1RHfeu+{pnVo1h-txss1^i>Xn}$-mMjp$k^zER zl0jJ(04T!}4N9?uf#NMepcsoUD8k|i3bwd_{4Kjc-j=N(H_HZ)lVuHPhh;fvvt==8 zy=5L~wPhA)nPn}V;4`HK z=uBY&ER$1^lX<29n0cZgHS9ewjDM!?jNhiVjBlo5~?-)ZBGD6bZjG*);V|u#7n3P^^j7u*!MyA`1q3Kp* zK)T83ovt&wr>l%k=`!Q?bdhmWI?uQ+J>R%8{iJb8`cdQj^n=FP>3faS(wWAI=~Uz2 zG@|iW8rJwV4PpF{1~tA;%Qikw%QQYpOEun2OElg{i!)wHi!xqF3pEa>1seO(e2rac zp2pTRS7SrkZevZ_c4I}_W}`iAz0sPs%4kemX4IxFGAh#M8O3R{jJ&jI#{9HN#*=B| zj7QS`Gwe_MVaQASY@nsRHxSca8!&0l4T!YI21wd{11RmbAua8?Au(;t5SMnr5Scb& z2ubTV_@{LnywlnZZfVVi-D&lPZD}=zjcFBzwP_`W6=_9=#c5{4yflMhR+`2zHBD}q zkR~?#N#z@Uq_PcPQcoM+rye)FN}PN!}& z98cY3IF!21us3y;fswk*Ku%p`z^BeNpi*ZVa#N=ovQsA-GE)EPQ&NBH<5R!uqf-%Zi#Z=@*oV<}So`4pjkD21!< zOF5(OOgW)%NjajgPdT8kPT8X`OJV43DHQ$x892Qm1*2D|AoQ{ns9u>m>>d&O4 z>W`-+>JO#F>G!5Y=@}_udP+)=9-rc;N2Pe_b5q>(*(px?jFcVv>L$=#(}3 zu#^@0z?3C=pOgi9_mnw$r<9rc9Vt`wn^Pw0*QNZ^txWl?Taxl!H$UaGZdS^B-L#a~ zx``>zb$^o|>wYHR*L_L8t$Uw*UH2+^O!qYTg6?7Ri0)4EfbM#7kM44EhwfZ*i*7Kv zLD!R9tLsRv)HNrU>Kw_%x~gQ0t~A-GD@xYt3X+vNU9wcCOcv^-$y}WvIbX+4KBYUA zd`x#V`H=2F@;+T&GD}BGrs+t@Bpo&xr$Z#8bdY424wMYmr6q%OiOK1@*yLngL~^_? zI5|e=pB$m{N)FMvCI{+vCHv~OCVT2OB)jTXC-2rROWv+qn7mmxH+j8oM)GRi0-U{aZOPm)bbPqJ!BNhU2eNvB05skG1}nKmm)q)kuaX_J!jwQ)(OwUJ53wINA| zwf;%_wO&biTGu4Hc2^QvyEO@~-H?RVu1-Q|mnA{9i;}XnbCWW)Gm=uZlams)RwvHVmL*Qt7AH>DniI!s^@)Eps>GifY2sInAn~Jyo%mLBD)E)(XyP-? zfy76eyu^DNTH-AYG4YxPlQ^boWg6#1n`TF%RkJ0rK(jtkuUVC-)+|kwYZfGmHM0}>nrVp~&BVkrn!gDrG(QuL zXuc#I(7aFBqj{CU)I3d~Y91sIHMbM6nrjJ2&7}mGW;6k;8At$Wx)ahhZ3)Sm#)NoH zZ9=T3A|X;^PYBgm69P5H1YeCN!Am1gaMOqqoHX2o9hx%Lo;->Uu^->Ci& z?@+&vuU0>cFIPW|x2tc*7pkwto7I=%4eHT&jd~znq3({Cs@vj)>c)7kx;Fl-x+4CR z+8%#QZH+&qHpcH$YvS|N@_4#h6i-%jZJGpb!@zkIwIav9USkf_KV-G_Ke@5c8TAj-Wk6^y(NB) zdVTy#^{V)#>ZS1u)eGY1s%OW~QcsJYrk)r-N&OcvPW=<`NA(5pQ}rJ3RrM0^N%aKq zPIVvfN_7kHOm!9TSalI_Uo`@_t?CC{S9Jlds9FIRRSkeqRSjTBRSxJ=*#KQC3!qJ9 z05q#qfO?e_P@@t6DphPisp=GasuE~+W~0RCIDQu764H#2V|=j0Wwu{ z0ja7PfJD_~06;Yk5Uu(h7q0pi7oz$Y7od6*=c9Ta=c#%a=c>9Bw_9~RZinh}+!ocj zxDBeoxV5UDxRt8*xTUJ5xJ9bExOu9IxLGQD+;o*SZnDZ4H(sTQ`>T}4{ZfkJzA3qJ zpOt6g-YbvCy;dHKd!gJD_e4pLd!Qu6-Bn`aZYmLRSCx>s%Suq(d1Y$ch%zB=Kp7L) zqYRJhR0hShDt+S`l^$^prE^@haz|Xba#LK1a&26Zaz&h3xj4?KoEN86&Wuwjr^LyW zNzhm7Lf><>^>o<*`^V<-u4t z<(^n)B|Ubhk`%jDiHY5$gvYK^f@4=Jfw9Y#sj-Wd39$>5F|l)$VX-rnfw5DSKCu&( z?y=*PPO<+fw#WWdY>fS?SQGnEu{`#jVo~fX#oXBEiW#ww6_aD{EB?jYQT&Rzq4*ke zRq-L_lHzsDdBwAsVa0=(e#PyW9>uko4#lOIR>f#cqhcV&q3DXKRHD;i=-6g4qL zit-qX!WLsxm}7JbeT+(>ijgU#F=B-vhOfwv;V4eVoKYN!IjPtmb5y~KIjEq<>{H-l zSPE1OU6C6@R%FKz6d5rXMN$k>5f_uIh>Xcmgv5Xp{xRtaub32tOH6`dXH1-8OH7nv zeN4DwRZOsANlbuZevFS|R*a`&YK*I5Ld-=nuEK1FX-yp3L~coDry@hEzk z;%@X}#f|9sim~W9iu2Jk6ob)I6+O`t746aE6iw0p$?Kwj$}6J3%I(pg zxhDF#To(OUE{uL4=S1I;pN_sMKNfveejxg?JTLmZoEAMICq@s*(b2tfSahd6C%R3Z z8QmmLiLRFeqHE+)(UtPh=u&w=v`y|EZI!!57sz)->*ZUcHS!J73i+yNseEa)P`)6V zC!ZaiFP|2DT0SBAxcpDl5&4g(1M<&Nd*yGVSn?N9H2LEwvix2YUVbAABOi-G$j?XR z%7>zI@Sq{>r?fe#u;;zRPw-eU@#B`XE~$^;Whj>ZNQ+)HB)qs7JC{QTJt2qi)N_N8OP9 z7kNeYJ@S(5Q{;Kso5*3=^T+|&qsSiF-N;Va^~hG)<;W)4xyX9iKxB=qJF-&N7FjB5 zjI_yWBCWFW$O4%y(jc=$YGnFIrA!qml}RH-GJYgqmLJKMos2vqI}&+9wlDIij2U@Q zMv2@f!$;=Hkdbs5G?F6AiX_O=BC)c>NR%u#5+;j?gvf#-vt+)JnKF;aG?`Oml5Bfq zylhisjBIUWq-=R)m~2sGkZf+GzifJ>w`@|RhwNX3tL#_AZrPWJ9kTZkTV<~zHp-qv ztdrf3SS7m^v0Qc~Vu|cR!~)rH#9Ucl#7tR7#57rR#AKNxV!W&};;*zM; zpfn?*PnsOjB?UyZOCuv%q#+RvQvZlLsb@sB)Fq-^x-+6gx;dg)x-P;ZT^V7LE{@Pk z=S8TcGb0qz$q`cNxCo*2cQ{Y_HJmN|5Pn+vI{bw6Y54yc@9=}t+u{Fzcni;yUJR#8 zN5U!6zHp+nGaM^z2}emC;c#hHI7C_+o-Hj52TD!hX;N)?vQ!?PAQgqjO1a@t($nGL z(qrMl(u3gv(!6kADJ|SfN(^_CqQjk~u<%{dobYYZjPT9UMIWcW&HNcb|T zfA}J)XZU=nOZXh=&hVMi&EZp}>%u2VSB8(5E)M@AnHT;`GBf!$ipfn!mv^aC(I@}6;>!Y8fKOp2s21nVOj|_OeGTu_QN4AjuBnO47sfB}rkYB(Y(~B@tmqB*9?^CB9*MB_3fciE|iTvOSC<*%U^Q ztO>(PmWQDvi^AZNIbjgV^ssEn#4w=bZ)m#YXK1qIb7+F(U1*%-WoWeIacH>YUTBEq zMrfd9EYweOKGaJx80s$R33ZXQh3=L#hVGEmhHjCRhi;VELf1*mp{phO(B%?U=n{z} zbfJVFI!}@xI$Lrgbh_kl=oHD`(1{X8=r{>E^gl5+^rsjR`b`WD{VWECeh{aIz7fZV zz7$7?J`;zAJ{AXrJ`j6_-VwWo-W2Z&y(ZogIwoEpdQrSGbX2?~bVxiuv|l_kv`0K8 zv{O7Tv{n2&q)GgLxmf%mq*nYoq)PlWq+I+U#4f%SQY5|_Vi8{qF^Pvm^y0n{wYVch zA#M(liX9;$ab*Z!ToS?&TSLx>jUgw+>X2h%S;%3rFyw%k9kN$^DugLM5<(O243!Y5raaq#c3fxaY9JCI3^@T93GM&4h)GC`-DV`-9jS7yF)_7 zTSJ1x8$$fVt3$lSOG7-w3qoAQvqGH2Q$u!&$A@ea{};ST{4IFB_+#)I@tfe4;%C9j z#1DfPi*E-n5MK+PE4~;!Q#=wpP23keS=<>sLEIAjPvi*xPgE8BQ&bZCRa6-KNn{Lu zFVY0R5y^sIiiE+>MC{SL`Q?~iuMQJ6tRM@i73HiB7E>g5i+M3Bg^WnBX>1cyO~QFt|bF6I>^93$7OJ4z3Vw4K5XJ2)2n<1s95z1{a9t2OC7Q zg0-S4!79=CV7cgbkVNz?NGSRk#1p*^VvC*yoe@0m4= z5L46W8ht3P2eqIdEj+nao`o9 zIq;HD7kFN%3>*=P0|$k?z&_!bz;5C3zz*TTz*ga&z$PIruwFd)f;j=-1=9n*2qp%66#VgjC-~w2M)1l1rQogq zGr@EJ$AU-x4+MAo?+UK_-x6H%zb+W{zar@Oza;4NKQCzU9}zhG2L)CBeS#AIZb6}c zhrsCHCQ$n~3uOKc0)c;>fbCx`IO$&@IO1O_*ynE(F#QV!WPh^&>u(ew{B;7bzghtF zR|-=6WrBEru^`G{APDj23jF=^1)lz=1up(41UvkX3O4&660G$ zoqjQb7QaY=!!KM==@%j>@e34K{rm(*KW~BB&qE;da}@~uoCNuPy96iwwhIpXZ4vDA z+bCf8trL*^RtvCxD+F-Ar2??uVnL?g0ztChTmisumLSq^x*)`FionlrqQJv%yujJ- zFMqq=Z~i8~AN)0bU-`@ZKJgd&z30#Nd&{5Z_liHk?>YaE?-Txa--rBU)uY(f1sG*ms!U>pRHr@a^L_`F8W`d^`9RzO8(lZxi3*+rZcR z*6~%o)qII>1)t|z%0KIC=O6bi;ve$0@b~zd_%vTVpXjUMqkUEUTwggq+gHL*_Z9M! ze0ls>Uk*Rq_bfli_Y~j9_c-6p_XvNt??L`n-~IdzzI*tqe3|?uzBK-PUowBDFOfgR z7snsxi{}6GLGZu&HHf$Df}^?B>p*{c>bVIEWg_)ir?xJ z!Ef*h zV()4m*SnH;#=DGn%-ha8;9bni^S1J+-UU3ow}FT9*72a;Y97d2!AtX&@e;hnyl8I$ zFU*_E3-D(1yu8owT)j{7c6uM@ZT3FGTjza{x59fLZ;|&N-dt}cZ@M>)H_@BI`|CyI z{qVx^K6#;eZ@rMb=Uy=0LoW#Lj#m!vniq(7(JO;D;+4kh^GfD*cqQ#feo@3lP&x_m&&+}ZH=Lpy0Imp#}_H&hfL7qk2G*2rx!LxuH?P=hKdFr?Uo@%a_ zr-JL^DdX<+6mvIw3b|`NdE6DAZ0;h@v)nnJr?}HRPjDxC9_9Y=IK=(#ae({DV=woO zM;`Z?2ZQ^-gUY?_LFQidAaE~u;JCvcXl}0ug4^x^<2HIgxV0WR+;R^Px7Z_tTi}t# z)p;ay6&{IPkq3aw^@!!3_K4yh^$6$g_Xy>(Jc76sj{q*t!Hd>5=Kh^?&ixB#!2Khq+xCACcE8J!x!>jp+;4F5-LG*@xQ}rTyI4x7|3L zYi{|Ri*Bbm!)_-zy>7=i9d1WBO>PG{wQl=4>_+G4+^8Id8;K)wBXGEG zSk7rTH0P)rg0tTZ#$mZZI25-W4$du$gK*2_K-|(fK(`c5idzx~;1r9puD{u5Tz|5UyMALIbp684bN$4oy1r-QUEi`%uCLfo*B5M% z>r-~B>tlAj>qB<5>pga;>m9bg>rJ+&>vguX>s9s+*URipt{2&BT+gwWxsI?GxDK*s zyY{oEy7sciyLPdEyL7O>y0o%CxHPk0xiqq$xH#DNTx!`jT&mb(E*0!^E@kWi7dyMl zrI_8~VrAF6nAue>CU%L7o^5r}vJEaOw%SF(mb%E;d>1kMtc#F++=b6R=)z&|ami=X zTu!qIE+^S2m*Z@x%Mo^#%OQ4}%K>(R%U*W0OCCGag~9fBp|QPOC~OxOB727mp1sKh z%U_C4n~_6_G4 z_Ly@N`oj0=coY%3b&TH5N=T&T!^Kv%Sc_|y@yqKNpynr3=JdYjiJck|XJd^G3 zJe}?7JeBS2Jc+&Cc>;Tr^Embz=Rf(&oPXypaQ>M;%lTXW6z4Db-OcZJx}D$YbThx%=~}+S=}La3)8%}- z(}jGC)46=T(@4J3Y4Crn-Sd}YTmR_$X4$r_=5AYMq*9eiB^BHDS}RLI+qP|Uw{6?K z+qUoA{hVif&%I~daeujakJo>Yk<2wSGe6$(C5OGEN)CG6CHuW-$=_ak$!@Q)WT#hM zvfT@g>U#wxo4l-&4c?}bwO&feYHwx9O7GB;<=*}!OT4{G7J0jtEbx|;%=6}z%=TuK z%=9LeO!vl=O!0=7O!5YnOz^fZ8Rz|7JlgxUc%=7z@o?|UVvqN6G3mWujC*euqu$HK zi1%!+!@$M-$dAAqqy&H?Q-qpow@6uwWcYd+VJF{5gom?#Pjx82=M-+3t zWHH-|6t{S-#SE{$nC?{;H+sdzR4=!f;$;@sdK-(YytTy@-tyuy@8IHL-oC{{yxofj zdOH>O_ZAiR_2v}!_NEp0@Fo;@^F|eS^@bF8_WBif^tLH3_Wmp?^nNbN_r5L4^*%4k z_C6}g@ZKp(^Ij`T@m?rO@}4S6@E$FS_3kf<_Uc-|Kt^SmlN;(1bd$aBANzvpJ*UeD#iJ)X0LyFAAWcX$pKZu9IZ+~V0* zxY4traJ^@B;abnq!quMng)2QX3zvH)7cTXTEnMUoUbw(R6wdR&g>yWX!dV_&;S7(m zaGFP4IN8H3oakW`j`uVaj`h?Oj`oxlj`R#F9Pa5;=<#$bBt0DqaZh0(>d7udJgJ3{ zC%(|`i7d2wf(y+a-$J9Ob)nAly+GsnSfKK}E>L)$7RWpg3nZS~1tQPY0)gjz0nc-? zfbBV4(Bj!!!0_xSpnEnI&^&7j8a&Gi>OBhz>O8XwYCKa5syyQhDm)_#NyZ@n_V5aNdYA>>J&gr_d1?!~c*+Ypd4?2}c={C-d3qEScsdv4 zd5Q{hJUInfp0t7tPeMVOC#oRD6H<`m@heF1v?+-5{K${-e9DjVyvdL7JkJmHJjxID z+{q90T+8?OT*&wJoXT(SIg;PjvoF83XJ`Iz_vZYc?zQ>f-OKa8x)F2y8ZL_yW8gPb^pxU zWnHus~vE$%yco7~s(Hn=b3t#hBsTjM^Gx5~XQZ-skj-ZJ;*ye00n zd5hf3^A@-l=FM}@&YR<&mN&~iA#a9zRNgeVJ8y~`&70)5=S^@M^TxT=d1Kttyism` z-UxR~p4UywbGz&ENOwgZ?jDkdy8GoJ?jCuNyK|o1U6f~a=j55)X?aF>LZ03om8W%w z26}TVe^4xcFIqqw@Ecb<6ru$TGv-?PHlY3uo zqkCsA)x9~F;$E9u>t3E)?OvE$>7Jci?w*=k>K>mv)IBnHh})Gr$nDG>;I`%Va~pE| zxK+8m+>+cLZeDITH#4`ZyD_)3yEeC@yF9nVJvg_>-8Z+u-90zY-6=QMU6`Bg&d$wr zr{<=+<8xEpk-5q4;M_#FZ*IK1b#AQtdrq|bV@{;|bxyeZX-=5?VNQtqc21D{YEFRr ze2$;{WR8#fa85h--kdh>9XYMsn{s}+*5v$fEz9}tT9EVAH7n<{Yf8>X*SMVbt`RwJ zU1ZK{7q|}FWzBi+(&s#LDRZ8<#5w=CxH%79jGX(fhMc>unw;CNvYeZ)K{?l5eR8h3 zy5(GPbqGW_*Q@Nk zt|!@hT=%ngyKZLhbY0Hg?mC;j)pb03v+H2?M%SL~^{#E%>s%YM*SJjO_9EAq?1e6G_IwwfJ=XwsmPU zTf5|$tz5#)UnD#82T9NTM%HJ3B`Y&OlS4B->Xe$Kcy&cpowPb0=8ggL9DzbOR3i7Xv7-9Ojck?PKz>W3k{{A2UQR0~&!&}<$I^z82hxU+yVC}fThj)T>(ly^E7SUsi_`j$bJKd0)6;sA6Vtkr zqtm*Pp0utcmez%|r*$HYX&p#)S_vslDnv^S_~PS7ESu5MUt)4!pZNcVdTfu5b||uF!?k! zki4H7K;BICBQK}=kY`idlgCrrk_S`Ukb6>Fk=sB|;0601_b6H8LR5pz?&5YtmX z6BAQE5~EW;5T4X`1eW@iaHPH_OsTI3P3j9mmimkkq&_8BsgDU->OVwX>O-O;^#L&? z^&ZhL^)AsP^)}Ht^%hZ-dV|PGy-uX1UM1pFuMm-`mx$oh3xsd#d7^ddS>k)j8RBEg zDdKg?N#beBapFPBG2&Lr5#n;nVd8AcLE?DI0peiFK4MSGUSeCy9%4hvZemr+PGU*Q z4q{%)He!0pR$^kxW@2>8Cc=}lfxuGM6ONR%geheWp-EXq$Wm4k{FLQHOUg2Wma>GX zOIb`*q%0(cq%0u%rOYFGq|7Bcr_3gbQf3j^DKm)Fl<7o#%2XmUWeO3TGKug_nMkxw znLvC`9!Gpk9!tDR9!)$+9!12-Nf-^k~o-55POm_Vrw!=tWQRW zmB}!%I2j`5CfkYW$u?qQvV|C(Y$iO(MgmPX5cXspVNBK%>SPTeO;!>7WF^s(EGKBm zGNLY7LX;iIFnRP97`%A4kVQlyOV|zTa$(m>yic$ zE0P8hi<0^ibCUWI(~|lU6Owupqmp_N?xY@sGpRdaOX@}#lDZPAq%MRcsT09V>PRq? zIuMOX#Y9a~5mA;@NDNBKC;BAi5#5ql6wL_ty(k(HD|Bqya4u}P^!cv1=xn3PPk zPf8?yCngYI6XS_@iLu0s#2DhA#307x0Y<=kV1DXYr*8XYlz6r}3EyC-KP%C-5-|$8m4MQ5;V=f!LHSr$2EZ&U|ig)3C;z_()JdSsa$MAx96wi!z z;>qy{9vctg;qeYUFy4;0kGJ8!;w<==I5Yk(&V;{+Gvfcm>G8X9I{aFk7QYau!B54h z@gs3cd|#Xb-x(*zH^s^DHE~jWS)3SO5GTTC#R>5#aRPj791kBJ$Hj>_4i3k$aZ4Nv z*Tpe$c^m^5#x>*YI66*`Yr^Z}8u6;Q27G8774IKckN1qD;9cVC@Zz`{JU6ZyPm8O< z6XGiIsJIF|B(4niiz~(3#0|s0#}36m#ty+>#}3Ay#ty_E#16o3#rDT9$M(a|#`eXJ z$M(h##`ePZ#P-Cu#`eJ1$9Bh8#&*LO$9Bc%#&*G{$9Bdi#CF0*#dgHqu^n(Uwgk7w z7U9O&LR=MFfJ_@kI`{7y_5ek~>xzYr6G zpNa{_561-Jdt(Cd9Wnm+rWikbO^h$TEXD_)AJZP68Pg7*9Mcvb8`Bye9@7fPV}4^$ z%rDFw^App?{J`Wf-!Wm#H;fhY6>Ez5f>B~VVU;l-v7s>^uzoS`u^ut+u+A}Wv7(qa zSWe7qEH&m879aBxi;Q`J1;;$Yd}E$stz({G-=ZI5AEN)kUPV8`odbQ426|)E%phnunD~&BX>q&B6La z&BnS#&B8iH&BO|#W?-37)3M~JX;^I3R4hDd3KkeO8EY3c3Huc}5&IH30ecrY9(x`+ z4to?i7P}KU2D=tH8oLlV3OgA&5<46@0^1uo9NQ7;#WqEHu+@=nY-ywmn;%JHGb0IX zawLw8iNr8(B#PmYP7I1fFmoh~X(Ay^1_&Y@7%S3_(IRbFU8EJOh_qlsBF$L8NE6mQ z(uj46G+>31dMrCqhowepvA9SL77?k&f+AIzPoxt29iha&MkuiN5pwKhgbaHeA;s=S zNU-Y>V(ems2s<4i#EwP?uzeAHY-a=y+Z@5g)<$r!Wx#?6Ha07Qg-wZQ!Nx@}vEdO6 zjEHE);0QWqiD<%f5j0F5(TE8Fc0>b4kDy|dhM0huh4F3y5!n<%Z{B>EXFp zLU;}q1%!lWV}9XTSnKdi?0Z-S_Ax9Sdks7ZOT+GmrD8Y3Qn1Tm$=KPjBY7^8*-Vbx)QSSc_dECA~j=8ts^^TSHQe6d_0JM5c(td5c(3UEvPbhGb#qS!JAM< z@J5shR0nTBOM};=1A$(_>(H*jYta%QFL(`_9=sY&1fqjip`pPmQ9qzf@Cx)t&6$9L$8EA9Rbd(BI2TemufdN5N(OyAQ(5^s9&}1|h zNDrEXCI(GJqkxd038){?CTKkRJ#ZZQ5qKRq7JUlb4;+Ku1TF`TM$ZP0LXQCl0!N~| zfvtff&~<^s(G|d=KrcE6m>TFo#{(k+-KZGLS$;04ESfn*nMdhE@fl z=rCYFpcCx{bO}VzVjwpVM$>?VKnRTrbf6)CZ=fA*4SWxcc#0N52^M7IPO&~?Cy06n@8m>r-)rvl>wwCD(c4A7tmUO zK#9_U`Tzx51q=<4qy2%N0W!1;P!u3VbAYq}2^tSX28hvMz&AjIwgSHS3(*h2D}Mp{ z7`W%pM{fX^{CVhU;HWY=b)Q`wf^AG)xZLO7CH-<0*v!-L5Bl`KNE!ki$4R^ z0&@RmR0y#B>1Y!`@oz#afgwOYe;V2Y=R)CXtUH$uM(XJO!lil#{yozauf$3 z!0cCsY53rO)BgvJ5kK%n11v_0_4 zcL4eYcn7@j?T>9B=|Si~5ZK*59o-772UY-!+NYs&fN8*ZU}XDL)CD*JYx@*b z4=4clAPq0 z1lR}cXd8lV0@eV_fcd~oU~=1FbPV7HZ~y{KZG%t^AOrY73qS+v+6JQKz+j*+&>iRq z6aZOm1JGn376=Cdfp);JHvZ@r;4SbRcm&)5t^()V_@O6(L%`p_c3>m03RnWnYvYSf z2POie0S|xzcEAXz+W4RnfCn&v2A~Eg0|o)T+q6gj0y+SBKn9Qm!~mgyKhPHV(YhV_ z33vlM10DdkfGfaR;5cv)*aK{B-4>&i{K~od0{Do&S5Eod0_to&VDZ=l}HH`9HmL{p_R{&^UO4~LbLW41=KN1jo&V{H^S?cI{-=MO|LKwQKRtB*rw7h| zyZ^ts=loB1o&R>{e|6jWpKdw-?dG3uIRDdi=f7S1(^cnxy5jt|%YVA${I`pLy5Rh` z^M5+${I|1zI^+De(|TI^q1ciKxdOBtv<$QqwB%2Vor|4|Knp<&K=VQKKyyKJK(j%!{xs7$(>Vh) z9W)Iz6*L7j88itr(K!J$9yAU#7BmJl8Z-(t5;Oud9OQL+KyHu=M1lwq?!-VS=-(Ft zf}Icu%oBIoK{k-pX#tr*CXmr-0O>(Grxv6Eshuj25~KjhoidOVByoyCBBu}}0P&qX z5EsO8vOz3o3y29~IGaIqXA_9#Yy>rcsLpy2#aRccb=H8YomHSpX9cL-Sq3U~4g(E! z4gn2zg4x{8fzAP-{?2}&zRo_N-p*d2p3WZ5?x1eYzd&7`T|k|koj@I(9h@bgVrLPk z&{^Qj2jw|)K{?KBXBH^anc++ar8!eUDb8eP5-8D`;EV^wIb)qMplD~5GZGZx40ncs zLY*PbU{H`V&>7(L2l+XDoj#!U&UVhW&NiUd&Q{Lf$ZzBq@)P-id_T=TJCNk5f5E3B}9KjG2ygd;FMj*t2*by6IMJymQVnU3F0nsBmM2lz;HKIb4hysx#GDM0< z5HTV`gops)BRqtQa1b`aLRt_e!a$l4I?{yDkVd2dp(6DN1*t=7ks72LsX{7|3Zxt< zLrRfh$WUZ3G6)%n3_$uL{gA#$AEYg(6--K_#*WqjMRroS|3BCwlfX~C{;Ir^)_!N8+ zJ^>$xkHJUa!|);aAbbGc5ATKlhWEg`;a%`fcssle-U@GlH^Up@4e)w+9lRD^1FwQt z!Yg1fGZauoiGB!Fa+CS8*GIwun9K823QYkVGXQ?Rj>kyubLc7b1bPfTf*wK-pnK3==r(ic*O@bys;y^5@1!6$W5FMgHjSv;8hw7kOs2Zw*Dxh+x z6dDE%fd)eZq5e=ms1MW|>IwCLx85IP(G9k|bCX^1PK`BrY zlnBK`aZn5t4Mjo`P#6>n1w(;Q0OSYxLhYe;P#dT<^xN^%@x$@W@zwF!@yYSQ@!s*) z@!Ijq@xt-k@zn9e@sH!79 z<+8L>@YbD4xK~m zP&)k53&!m_qX@8_qO-6cenp#?`rRC?`SWv7ugH!dG;K8wms9HZcnu* z+Y{~a_E>w2J<1+o53`5ZgX{rzKf8~;oxQESwf(p4r|rA#tL?MxqwT%zt?iBNmF8QUq_3EMH-5!)f#0oy*?-?rVhUA7&z zZMH48O|}iTb+$FORkjtjWws@@MYaXDdA2#WS+*IrX|^f0Nwx{L@wTzH(YBGc;Wm%W zWg~1DSXjX}hs|cQ*i1HqO=r{CR5pc8W|P=NHi3<2rmfl5WNWlhZ4_Irt=d*; zE4P)}hS~<(2HN`D`r3NidfK|%{<3wkb+UD^7267J`L+0&IRZA6q+H8(S;eFY6EMH|rPcC+i36JL?IHR~1YCF=$2IqPZbN$YXzQR`vrLF<0&Uh5v~F6$2KHtS~VM(cX(TI*`-O6zj# zQtM*tLhC&19P2FW4C^%O6ze4G1nW5K80$#uaI44avJzIz>a@aEyVYtnTa8w|RclpS zl~$QmVij2hR-Tn(Wm%b4x|L>au-04atTomuYq_=5I@CJYI?&qR+Q-_<+QZt-+SS_G z+R<8UEwtuabFJCdOlz7o#hPSIu*O+qtdZ7mYp6BY8ff*i`dHgp+gMv!e_6g;zFIz8 zK3d*e-dJ8)URa)4o>(4P9$4;K?pSVFu3N5JE?X{I&Rfn{PFYS^j#&;{4qEnG_FDE> zc3QSuwpun@HdxkK)>u|qR#=u=7F!lt=3C}iW?5!frdcLiCR)Z@##%;MMp(QSw}r4^ zVA%{?>=vuVY%yAN7L7$^QCOrFu|;U%TR0Y$g=uNF&@2s>dP}XP+EQsLw+yoku?({G zxAe92w)C`gvvjp|wsf!*TM8}tmK;l#CBu?xNwy?f;w>?jC`*JT)Dmn7wD?(kEbT0< zEx*k_&EL#l%%993%x}%F%`eT*%ume!m>-z$neUiyny;I$nlG6zn9rF{n@^gLn~#_e znGcxvn)jG@nYWv_nm3s@nAe$Cn^&5bo0pgunHQMnnrEA5nx~nkm?xUYo5z|*nMatt zW|x^TV`jt*nQdl^*<{w6wPuxBVV0T2W}%sH=9pP#hM8`rnW<)qxyD>&t}vIHhnfeO z2blYrdz*WjyP3P1JDWS0i_Hb*Jae`=)0}QjF(;Yh&9UZabA&m}9Bd9W`r?aZys zzfC_(-%OuPA5HH}Z%nUD&rMHF|Ck<{?wRhGZkn!}u9_~HE||`mPMc1cj+qXd4x09v z{x&LEGCmlZ_=7nCWT3A5}O1jo{4R0F*TcLrUnzmRBNg-RhUXmLrsHB15ABQy-ht# z-Ar9folGUBB2&I8*OX<-Fr}K3ObMn~Q?x0<6lMxG1)BU!KBl&&)}~*^@5ZmjPsR_% zx5n4T7shAC$Hs@o`^G!QTgL0gtHw*l^TxBrQ^pg8OEu`$;JuBvBuHH5k{}kWyFoB5jHxER-?&iFlvn|qrxaP zij4vz*T^<9jm<`yk!qwEYmAk~a^o=L5aU2&KVu(bPh&S@S7Rq*2V;>j-kVrSs|?ExOAU(*^9^$ivkcP>Qw);~ z;|*gBqYT3hZUbq+42Z#Duo=t-gF$CdgCQGIgV-Q2a1Cq&(?B;g8mNXkL$#s8P-Ylv z7-Se==xgX@=x+GS(Am(zP-G}D{-*xA{)+yh{+#}d{-pkx{;>XlexH7iey4t$ezSg~ zew}``euaLSezAUmey)C&eujRkev*E?evE#Uez@MPC-kTu(L3~3y-BavYxF9;TrbfJ z^*lXC-=c5U)AUq*oxVn2sV~zH)eqA5*Z0-;(s$Q))pydD=!^9E`W$_xK24vjPt?ch zqxBK`P<@czU+=4Lr*EzQrTeb?qWh?OuY03=se7h-tb3@tr@N!Osk^4Tth=B)t2?DT zt~;tbq}#9iTenNMUAINIQMXRFMz>P8Ot)CKKsQ%6OE+CNMK?(|UN=TJQs>pVbhyr` zgLF2XMQ7CMbZVVKC)J5`d>u#E0xqtk=^AttU5&0%SEd`P8>H*6>!a(b>!$0X>!>T% z73%VI*}4o}sxCcVuvx&WQ8uAQ#6?w9tv_KWtD_PzFv_NDfj_ObS%_MY~( z_J;PV_LBCz_KfzV_L%mt_JDS;cDHticB^)icD;6ucBOWicCmJWcCL1ocDibc)}tl0m=@7Gv{tQ2tJi9@O07&Q)(W&-ElbPLHfbBQ6m5;RQd_1SsvV^5ukEAl zsqLoiqV1?H))r`UwOQJ9ZHhKg8>fxdMrcE|L0W&UkG8G0mG-CRo946Tz2=SPrRJID zvF4%Xp60gZhUTi~lIFbTjOL`~nC7tNfM%~|mu9hPD0%>d-v&Nv&YLpt8MywHNxEhv*p=r`IXegR$O@*dZGek2` z(@)b|(?j!@rjw>bQ>e+)WNR`sshT8Bye3)`p$XLlY5X-lnzou&njh+~>QCzT>No0_ z>SyZ5>Idq(>RamT>MQDt>T~K->f`Do>VxWi>OJZm>aFTc>hXqtc>P71L>N)C} z>S^l9>hbC^>XB-%+NH+Th}xmHs!eLWTBBB|rD~CyujZ(kYPz~nU9YZHSEK)S>DiwV%4Zx{dm`>bvTT>Z9tN>b2^* z>WS)+>b~lZ>W1p7>XPcb>a^;F>Zt0FYM*M4YNu+OYO`v+YK>~8YME-0YQAcYYNl$c zYLaTaYK&@x%A+Dxmt;$fPsuERks%TZXDnu2i@>8`_wO0L7ep7x{eo($qzEnO_K2|U%F9#ZaC{;k}l+@{>D+@M^eT&Y~9T%??@oTHqfoT{9p9H$(u z9HDe82_>q8ls2VVsaI;0N~KgOQu38-B~wXPHYh2|8fAsDR5?UBK-pK>Q`t?~McF}F zq|8@lD>Ia-%0y+HGFlm~3{eIseU$%M^~fXs_3LBRum|56q$-NMUo<3 z5v_<&geU?PzKV8=){39U3|A(zU9a-N(e zXUJ)Cs=QWSB`=c?l@FBnllPK$mv@nOlo!eK<=OHKd5Szy9xIQMhslHG{&F9A8~Jb9 zci9)&2iaTMOW9M|KeGF>JF*+HtFnu-bFx#iOJoaW zb7iw+(`1un<7J~|BV=wF0k$V0nN?0~OITqc$YWE@$Gj4o@CQDoJ!3fVB(U|D}z zZ&?pnS6L@nv8+IrBg>Gb$`WO9vM5=YELi3*^O3cY{gQr{ewKcazLCC=K9xR_-k08% zUYA~xUXY%Zo|GPy9+K{p?vd`0Zjo-3u9dEmE|V^j&X>-XPM1!RPLPh3j+A<&q!g7x zQk&Ey)l1b<84X`s|k+D_U^`cv{%@=@|m@=Eed@>udfaz}Dga#eCsa!ztea!hhqvR|@CvQx5E zvQe^5vP!Z{vRE=-GFvi3GDR{$GDb2|;*k&%R02t?5|czHQAuPHv4k&SOPG=-2~|=j zsgjgQhDZiV`bv6Ax=A`qN+bo6TuG)RRgxr$lSE0vB*7AYNqb3a$uIFY@h9@k+$P*4Tqj&5Tqay3oF|+moGzR!94{O#94>ST zF(E9p3C%*iP%V@T#X`Q2Eo2C3LaMM1YZRo1#bl}1y2Q!1os5D1lI(Y1m^^&1jhu21p5Sg1Um#<1RDfv z1Sa0E<2lYlCy6;ujJ1%n0s z1-%8`1ziLk1cicJL8c&8kSK^1L<&L$fdXGaTfuMscm8Mod;S~#3;q-SL;hX zMgCd-N&Zp(LH=I;F8((DCjL79D*iJ5BK|!7EdDh9B>p)5D883Z@=-p-xAF~q4PU{R z@CAGhpUH3HQ~9<0N`5JSFuy;)H@`c-3%>)uke|!Xq{ zH<~w`=i*^Jm}ldecsibnC*=uwTwV*0&THV+@v3-bydk^+ygt0{ye_;Byh2_sFO!$b zOXS7!B6*>_0G*WaXxY0ab9travpK+ac*(0aV~Mr za!zuNat?C#a&~dHayD|-a#nJdau#ytaAt6(a3*lZa7J)k9E<~VY#b9u%TaQq93h9x zVRD){R8B3Yk~54mh|`bLi_?wMiBrtU=VWuzIZ2#2P827M6U6c5wB`I}e`kMYzhl2* zKV$#HzR$kJzQ(@9KF2=EKFU7G-pk&_-pby{Udvv|Ucz3$p2MEOp3EN49?c%kcCk@5 z#I~}HYz~i){_CR(Yb`N$}c1Lz0JC~iwPGu*sW7rYw5Vk+N zJ-apgC+iFA1M3azIqNa&0qYLyI_om)JnJ;;80!#gA8QwD8*3A59cv|PDQh8X4r>N$ z3TpyuG;27^#X?yS%gQpcG%N*6!s4^oEC#EQMPXI5%2`8L16X}n-C12&9asgd999M^ zg%!_=W`(nYSbnT_tlur)TRykEYkAf3tmRS5y_Q=oS6eQ&oNYPLa-`)z%bu1UEn8aF zx2$ei-m<7=UdybOsVx&*##TDr7!Xen&TX~}3wX^C%%ZV7J*YVm7n+wzs>@-r2mhc|-G>=H<KwnK?PG3ZyOP@)f zLZ3h%O&?At=_uVnx6t);HC;v*(z$ddy@_5=uc4RIhtdbo`_Q}7JJU<(`Sfgh8a;^~ zOOK?7(EaJ{>8)2^niO&gomG%ash z+%&IgR@2m`iA`gghBvvI&?czK(xh)vH_4hrP28rIrlzL)rkbYmrlCy(ntC^NZ|dAs z(v;tn)s)th*c96o(G=X|-_)+@H|;y^6YU-CCG83AA?*(B2JJHK9PJeCDD5EaZ`uyp z7TS8+D%vvILfTx~4BBMcc-knMheps4nvG_nX=zHDgvO__Y0b0-S{<#DHjFli)|b|k z)|J+QR!GaCrPGpWakNNUC@p~2p4OW7qw#a&`^Hy|&l(>!-fg_uc%|`tp(eMU8VCXEaV}9N##q(c4HgB8|32Q=_&~(I{!;H?kU=8ygyH8!H=! zH4bd-+t{PAOJj$|g2wE|w8o^y*v5#)kVgN;c8#qXzc+kpc-Qc<;Yq`ThC2<{8!k1R zYdG0(q+x%nnaDGMp8ql{?vBVR@CqHpX%S%zo>sw|DgVM z{k8f_^=Io()E}dWhg)DNidUEi&~Q+-i=UVUbLN_~8NRDEcDV7*U$>-ry*&y@F+SCpre zhm<>%>y*osbCi>mBb5D=-IVQ=O_a5i6_mx4d6Zd{sgwzn(G)L*pdb`G#YE9k6cjOq zM`2Ou6e^{LQcf8{=}+lR=|<^9DWc?3GAPNEcuEu{loCK`PiaN@UiZ1~UERyNCv^|% zZr5F_yI6O&?nK?;x_x!K>bBNxs9RmPylzq5+`1Wclk3LSjjVIm;dOAGwa!qdu9MXX z>o|3cI$9m2uBxuIZcts{x*m01>PqVJ>$2<8>JsZ>>cZ=S>U`_k)cvgeQv0Fyb?vj- zN40lrZ`59{Jy(0O_DJpi+C8<~Yd6)dtzA*OxOQIc%-Sin<7-FNdTQ}nq}Enztku-Y zYelu(T4pV+mQq_)TUtA)wr_3E+OD-7Y71(!Ytw2IYh!A|YlCWiYunWRtoc&&zUEcU z)0#&$cWZ9cT&_7+bF$`0&HkF*HQQ=7)~u;nUbCoXZq1CE$u;9@M%K7%uo|ewT4ShD z*T`ywHJlnoO=C@6O=Zonnt?TaYP#2St|_j`tI4cMsfn+NstK(LsA*r*s^)w3r|P%W zFRC9`-><$^eYN^R_37$k)d#EpuHI3-xq4mo%IYQ6^Q&i7PpzI%J-XUkO;jV*wrXRw zrdnPts^(TRt7+Ag>ZOs|gt9w*;sV=F`ugj|u>P*$~szX(Kt9DjxsajvPs%mM~f~wh7)2b#`jj8fh5miW)t;$%X zsghTTs<>6mDq0n#s;a8AYEV_*svcEcs!FQztFo$6s}icBszR#*s@hkzs`_5}sq$^* zi^|89_bYEzUah=PdAjmg<-y85mD?*fRj#dEQMtHsUggZnDV5_ZM^$<%@k+STQmL<0 zRZ1%bmF&vq%7)6?%8JUNl>;h!SN>Jmv9ho-r!u`VsWP@QqB6MBud;3B&x$V-wDm{2jg!dpR9AQiR>V}+(d zULmaDR4^(UE9xpLD~44Jtms|Qt)f#!QAKV=Mn!T(Tt!4haD`t*+lpW1U&}v~zb=1T z{;>Q``StQk|7nIK`pISbld~~_DoG3@it>uPtb-Aou zSk5VDlsA;umRFPyEgw+cyS!U@$MVARobvSYr1IGE@baK?-|{x)Kg+(9y(@cJ_N44V z+3m7xWf#g$mmMoRSoU|>jB^L4k}`f- zOIcG{eOYx`S=r#SzGXeix|Efa<(FlarIf{&MU{n?`IogT`(662^keDk(r2ZQO7E85 zD7{pAw)8~l;nIDjJ4?5et}k6xy0mnD>8#SJr4vd=mwHO^Qn=JwYA98eN=pT$>{5Cu zwX~+RymUxuztWziT}wNZ=9gxbrj{m@M*m-I-St~k{TuIXYUu77x@#C+d5?LEd7XKQd5(FCd5n3Od63!8Y+>$V)-ty-H!{~StC*F{ z5@tR#il?vgT9Bpi(X6LM&CqVL$9J&(o5+1^elP`J)Ry#525?hz34PLf$mCo zq}$Rh=*Dz3U6Zatm!nJ4Md^QNKWJZQA82oAFKIKhN!mDVly-x5g?64cNIOA0LhGXK zqwS$J(&}j2Xq#wjX;rjJS}84`mPJdY#nYl_p)`M*7mY?E&|GPbG+UYl&6tL!Y0^|^ zax_Vr2<;E`2lX@c1N9B{1$BlxNxe@UrQV=krk)lOP!Cc&sC%fpsI}B>)Q!|N zR34Q@EurR7GpQ-mIBFy{nCeIMq*ACJR2M3iYC|=n8d7zs>Qp7FELEH;O#MaqMp>dP zQ06JmC{vUP${6Jq7=w#nkWsFYRVSMdWwL;p_Ee!DLIrhN+KnO z5=IH6cvI*U5(Q6jqS#R^DJB#>iWWtMB2ST|h*JKNe~`bBKak&$Uy^6YljQs4QSuG) zW%7CQ0QoriF!><4gWN*iMXn+LN8UhQP3Dm+$i?Jbat1kx97~QM2a$cr3^JMQM#hot z$yQ`jvOZaxtV&iOOOeIM|41vOucVKpx1^V(r=&^JIOz`Q2I&gvJZX@0oOFbAkkmoi zL)t~ECH+U*NLo$ekt#^Vq+C)4DVY>YiXa7%d`S!vndC;okuW4Hk_kzlq)k#KDUhT{ zVx+&s72+4-N8%geOX3W1l6apuN*pF$CY~n_5RVfN6Au#Gi7mvP#2VsO;s)X>B9~ZB zEF$I*(}{`17-ASPkmyaM6NyAT(UE9Jv>+N2(L_z6GEt5wK@=hWCVVF>5#AH#3C{^r zgbBhJ;TGWsaFWnRI7HY_XeI0>)DyN7HWSto_=HMADIuSbMMxpU6Cw#A1V4f& zfkN;gI1{i0Yl0cUfS^NABPbH231WnQ9xEPSJwAH8^?2#=)ML_P++)<^hR0=(^Bw~p z$2|^v9Q0`SX!h9YQSGtSW4*^J4~|E$$LA>{GPec64{{hj-q`>gw8_XqBG+;6&Halha`=zhZei2FhJ4)+%K zUG6pR|G95)U**nqFLy6;&v8$8PjruQ4|5N2_jaeb6Wv|i9o=o+&E1XMb=@`GmE2|B z#odM6f4MEYExNsPd*wFk_So%#+a0%?ZdcsSyA8S>cRS*C(5=I*#ciisjoVhY4Q{L4 zIBw-`g>E@+X>JK_(Qct`0d8JyR5yZ~i<^U+jhmU9p_`7Ix|^b#j2p`BAO0u)EB+(? zE&e6`DSi@vA3us8#$U#t!=J(*!}s71;M?#`_y+tA{1*H=JRi@-m*VsBS@;xuJU$X1 zjQ7Jc@f5r}9*4KbTj5Rc`gkq8DqbEhi5JEHasBT4+4a5aYuD$lQ?3)PW3D5v*IX~U zo^kDW?RD*T-RHW;wb8ZK^*`5*uB%;nt`)9DuDP!1u8FQOu3@eLuHLRRSAwgntAnep ztGTP8tFEiMtD>unE6Vks%TJfDE+1Xqy1aCmahY_v?{eE^*yWPTIhRu|M_qbcI$c^_ znq2B#w!3V0S?f~eQt49SlIN1?lI#-e65$f$;^V?_A-UjPoLuZ&EL@CT&@LJ-$}X}l z;x582znqty7oFcZzjB^+e(XH%e8>5Q^JV9A&I8WJoO_%PIJY@BIX5`(aNg{^&YACA z>0IiZ@0{tJ;vDB3;T+`b>&$Q_IlDPKIoml~IvYEqoi&}6on@WHorRr$;g)fWxOcc$ zxLMp|+&FF&cLR4BcMdmzJBI7Q9l*8WnsD{F9k|W7wKzVm5?6xD!)4-~zWLtkWr{ zqfUpM_B*vY?RKhj+UB&$X^j)lslut)Dc338Dak3uDa$>@s~kCwWsU`o*^a4>@s5#>A&!2IOh>Y#yCcpK<7nw<;;84S>8R`|>nPzU?D)%J z*}Krw)%D#vMi-h8-?DoO3wkaMa;3gQ&wF?04*E?0f7y_8ImG_96Bz z_9pfU_B?hFdmMWhdjQ*xZN@fWcVIVT*J1hCN^A)>51WZi#>Qg9v4L10EFDY4x?&x$ zwpeqlAyx;ghE>E$W5uw4?SI&RvHxKI+Wxuyl>LPLnEiQ;fUuvIkpJ|_LA8Q|BA7t-iPq!!9oZSBqN4efR8)$JASrR~M+ z|6+b%zF-4~C8*Vq7r}7#oZ^#t@@}QNt);q%fkGzjiM}wR>l@( z`_Ja5%~zX`Hg9ZR*i73@*o@iSvbkn+(dM+x37aD}2W{GInr(L4RNHK^S!ctyskAAv z$+O9@Nw$f#3AYKf@wTDa5Nup*ur}5#bA zs?(~~YPVIr)pn~*R%@(yRuxu7RykH_RtZ*7Rv}h?R-RTAD|aiL6~@Za%Ge5RrD3IH zC1ZuM`e(Uf`Ni_1)flz_QJ<$+F&ZyX9ufwU$+u zEX!icT+4LJM9XN)P)mPHPfLoWyCu#NV`*t=Y>Bqiv{bf~wG_7$vixcB)#9VY8;chf z(-spJV-_P8S1m4B3|btwIBapiqRpboqQPQ^#b%4O7F8B3i(-phi*$=bi)f2b3x5kw z3yOui1Kd&5xTO zHa}qAX5M68Z@%4plldBRo_U3Nk$H}Jnt6hGlzE7`pE=Wc>w z)5oUcrlY3Ark705nw~W6Gwn9rXS&C9muZdZR@3#S0#mkWscF7xrfITitZBGupsBYh z&6Hs3Vv04jHZ?WXH`Ov#F_kqHHx)AdY4X+NqsbeS7bept6DDIOBPLf(E|?6O95*>^ za=@g`q{*b-WV^{GlQkwhlM0g}lN^&YlLV6}lMoX>6Q&8-#LdLX#LmRR#K=U~MBPNu zMA}5mrg5@ytZ}$;fU%b`)!4(>+1TFL%GktM&sft~*;v+C+*ru?r_ooVk4A5dUKmXq zO&Eh zk*kq|k&Tg=k%5u6k*blrk))A`(Qm_VhKq*p3||?}7(Oz*XL!r-n&Cym(}pJuj~E^_ zY&UE+Y%ttmxY=;6A8*(9e)*NH%mcbTYIvv@kR@)G<^uR4|k> z6gB)~@ZDg^V8LL{VAkNV!MMR~gX;!E24@WV4SEf_3_1*240ak+8*DLHXTUdL85A4j z8l)Q}8blj}8u%M{8c+<}4R8i_1{MZJ2D%3728ssK24V((^?&Gp)_<=*r$4LzSbto9 zRDW3ilKxr!llp!7-TM3VTl9D8SL<)lU#HL4uhcKm&(qJ)PtuRp57qbA_tdB8yX)ih zG5VJJ#`kGy_0%Q(D)(Oaj-*Q?Yk(aY1z&`Z>d)(h41*Ynh)=(+3R^e}psdPaJ>dg^+LdeVAgdVkSB z(4Wx@=sEN(`Z0POJ&GPiUqYWn_oI8!UFZ&U3wkHI8odR*4qb(2p^MSE=yY@zL~3>uBky=*a4b>j>%m)c&gdQTvVdbL}bZ zhuU|wZ)#uBKCgXB`>6II?fu$&wHvi-w6|)n*A{5AwM(`0wKKGnv}3fxv;(xgw5i(e z+Bj{DwxzbQHdqq z8LJtt8K~){N!9ewbk?-jw9+)zL~CkjDrw4SqBQ?%{LuKU@m^zI> z8rmAF8uA(v8p0aC)R)yislQQwp+2oXp+2TQqJBmFy!wFpG4&qx{px$w8`W#o|5M+9 z{O-e6FICT1&s0xRk5La(4^a0~r>eWFgpy6Wocit5tpV(Nd?zN;;%EvU_@ zJyn}jyRUXz?Yi2K+G({DYDd%#s%snx4(SKFkvMvbdhu2!g)t(K}5rxu|Wq~@bW zS0kvosA1Kt)lAj&)HKzU)nwJg)&8ljsD4rXp!!<%nd%eO2dZ~eZ>U~UJ*#?BwNJHM zwL`TK4_ts#U5i)ne6L)il)v)hN{vRXZod~YNl$Ss;#Q3Dz7S` zDy;fTWm)Bu${UpzD$^fMwJ?stt#u0-<#MfB`SF; z87fICF)E=d{wkg-6cu+BClxyt3l$?39Thbd1r;e3QI+4y-;@`X-zmRRo>6|Jd{6n7 z@>S&v%7eaDwS6Wh9P?}SEsx+x|U+K2eHKmJ6rJQ&>^>tngl8Ug4R-V})^rQH5cJA%!yv{R+Jb zT?*|A%?b?)I}|o4tWn@8R45cGWGkd9#4AK71S$9^&=rUZE(%x$YXwsUJq1k#Wd&IU zl)^vx75Ojn@8##^pUFRwAD17MAC|u)e@4DvzE{3WzFodqzCnJ6{AT$z@;vzp`6Bsj z`BeFM`AGR7c^`SYJW<|79xHDxZz``RuPLuAFDs9d|0lO1_eJi#+`QZ~xhHbta-(v? za+l=J$o0$h%5}-L%Qee2$nB8ZB)3M6Cs!d?D3>jlDi<#oAr~a)BS)7b$hpX2<*emQ z z*U0i@%Vi5?vt?6d<76XbgJgYVX|e=a7g?;Vm8^-Zo~)*Ce&&(sRUP(Qbnv}XHbxZ1+)J3U5spC?Ir4C57O6``aliDV=L28v0N2*jRUn)~7 zSt>>DK9B0DI)nxVp-yo#9N6M64MeB5_ctTN?egRFL6rZsKg`+e z!I!9%D3-{TNS8>Ih>{4A@RMLjkRZ;+MtGik}qk6Ym!95N{FRDPAqUS$wT{m3W1Ck$8@Hns~f;qO~zywWFF* z^{DNrO{g^}E~*?=h{{H#pyE&ws6doAiiRSfoKf~DE0i$`jnY6Vp`=k_sJ~)A#FoSs z#OB1FicN~$7rQNXP3)rBX|dyChs6$vwTbN(s}tKMwoz=A7)Pv3EMF{BELkj8EKDpw z%u9?S<}QX4!-!dk8HwqNsfj6wNr{Py{TBTux+wZi^rh&G=p)fF(Gk(Bq8CI5M30H~ zi0&8NE7~YpE4o#5y{JI6QnW-gPc%a`Q8ZdKRMbzDDM}V~6Ll1|6*U(%6x9}06_pp2 z5ET~vC9*8?QRI!t3y~?2haz`HZi-wMIVW;Tq)((XU`AqycRAzdLgAq62RAyJ`!0wLsH|NAGn zgWO5vT98|dTn=)<$hjb=haBqPU%~soe+A>nok6bs?;pV?$d&&2A&5ba^5?t20y%|0-vrCQzX_&)FAJ{x{wg?xT+Qz< zg38~Y1&PQpe=iAaelH4Cet#1D{Pj`r9Jw36J_!1Ly%+5KwIHba^-hrX>#e}&*Bb%$ z*K2|1uX(}0pL2rwpRWX?KVJ&^f4&ej|9mc3{qvb1>*uT>@aI#3^UoOp`scJj?B^4~ z!pdX8{gp|<>6J%ygUfv}bU2YKcFV_j0mum!TmUjrUm$wOmmbVIAmNyIZmNyDe%j*U2 zzpfFCe_bUw^OY}X|H>0=`pOm*eq{+FzLpCJUrPigUyB4XUke1EzvK!Yf5{dMeaRFY z{E{Zv{v}0F{v}Zm_a$CH`w}Ct`Vu8j`Vubq@i|m5`#DH({je#R@jk!z<6VBk z$6I{f#~b|Ak5~CVA20E-AJ6kOKc3S%a4A~;*;N(^3C5D z^5x&>@|PDf`7;Zt{HqIz{GNqae(gdepS=*uPhJS*doB3#F$D5P`*{ioa`ByJ_%P*hure99-uD%@S^}HPA)xEsI zyuB}W@HV{I%*%hVmKXk_ zis$iy#WQ(P%#(SM$NTa;gE#d&iFf&V4DZnMFka2`03Q3f7cc2KmFM-`gJ=KTnWypG zp7-yWCGYh!W8R%-Xx^!38oWKvlz8i($?)=@p?G1>{&GE@{otBB`^=Sjw!r-|JI9@x zo#kGheat;Hd!Ji7dz;Iiy~a(Ry~y>RJ0qqG?lwN6VIKQiQrzF3FIE0@#5CcP`SJrcW&B@ z6W4FXmg_iU#?_h8=Zel~aTlhQx#QC^+_TeS+>Yr#oGsJeI3?4cI5E?2IMnIq9INRk z9Odb8&dStn&hx2joSReUImf0>aduDjaaK=tak8h{Il)s+9Q;%*$8c&ZM`~&vXX!~5 zXYxroXXr@*r|U^3r}{}Er}9Y@C+SHL$LonV$NmYGqxr;*BlN_P^X9QNXY8>FXYjEu zr|q#CXVYUjPSIl&C+hKEHu>>4w#DO5Y^BGq*(;N??B|n{?3|>KR*t;i(*sCW` zv$H3Uv4bbO+4#wJw&CP%w)A8z`}3nM>?e=burEL2un#>dVb?y&VRIg(uu~t!uzeqe zupJ-yuyr0$*`kl!*b5U5><1H8>~j-F?EMp3?EfZ|*yR&a?Dz>`He+I?(sp90Qf=Z* z<==lMCZ=PMk? zPE_cQ9jZW$wN-q$yQ^a2?)Hj{ch^-MyvwbqzFSD|fo{tQ>u3qFnsW?eb5f zSIQ?xPnQpk_LX;!c9z$UHkWfpYs%9`H)^}^T ztnt?Qvembam*w2*Dhs`}x6I>KU76{v&1Lep_+>vv%F3RPo49cuV)XG#wWXgWu6e^p)`K|Qs&4tpzo6kzyZ%&kMy?Lv&?B-Bu z{LPc4%$q%>_BY!~wQe?)irm~%`u>KX^x=*2(hE0oO1o|(me$+|E9KnqE={{ZEcL(P zSn7PkqSW99x>V|ha_N_0iPGue-zC?EmrDAE=Sv!gr%KigkCo&OUn>b8K2t&*?klkv z-dCbD+*tDS`nHl+*VmNXxn5B+a6PxA{d!W#mh0gqW!Jq+;;$1+Jg+;J*k3m<(Y~%* zB6?k^8!8UIcCy&*T6eL@wY|mi*J_Ku zU)@mr{3^Hj*44t|{;O%ld#^?nZ@TJNTym9C9D5a4%(!Ye4}B~!9ePoqF!Zos<>JkPmlw|!+_~6SFnDoaLC3|N z1=}ueE?`}(DoDOqRN#9twZQpeWP!m&p91NNgo5P@_64&SObSLWXcY8ckS^GJ;ZOeN z3yb-s7hdKkT$srBx-gROaN&GD`ohtCi3|JkKcC;3KYf04{_uHT{;~6g`7P&D@;96h z&o4gjl^=WFEuVSbHsAidLB7s;m3;B@;`xi`R`RCKz0bRL?rGl9bNBL^&t1)1e{LYJ z=v;SR?75aa#6|OeL!HaaTRa<`H+9x8@7h^X-qEwzyymkec^l5E=M|lm z%8NbwE0=lpV=ngWvs~S?D<+Poi&e?kUPEN(?OF7A> zPvrQW?#yvHy(`D)^yVD7)7+dNgZVkH1`~7c4hH9(8KmWO4&rjE2hDT1gIYNmgEBcG zgMYFKgP*c32A^lE432029k`nPZs1h*!-1~sp@F9Co`L_ecMVi!uNf%J&L2q5jv5Hf zMpBz>%z$&Y_JBpU_<&aS(kYqjnNxqVZk+mh^stkzTavbLPMl2vi)WLEO216h8j z8nawaZO$@2#m!PUm6!GNWJ1>b$-u08C&^joPda3Eoixs>KdF`_I4Pc$d-8i`Mq;%+~(2%&q<5nXGP?dj32X(LCuX{V0nrF9&QOWSeOKaG2okd}GW zHZAO^UK;tRe45SCzo}YBKc%9M&ZaK)-A#SkHOtzUvX-7 zUvg@AUvMg=kCJNFhfUS#Gfb7}Q%e2XE1deQ_jAf?LD3%=#a?R>Rpq<=q*lh=uJ-1>kUqk>7}InID$=ib;K~`-Vvpg3rB=gdX6k5?>h1F}8(o5P2av<~l15)@M<5Rkb@j+d-@q{j&cWja<1b_K^HX^QFJHoeJGQzEWIoz`SWw>VhShz&{ z`S5RTJ>m0hjo}a5)`wqhD+xc*mK5I6<{w_$<`%xX%_6+0O)WgBO(Z<9?Nb=BZ92@h zZ6plcHV`J;wmYi`&`YgE|jRz_HNt7BMWt3lYNR=F@%>(9{4*4LpC ztq($(t(QV^t-Yb9t<9mTt(!u{TFXPf>`e)Mxi=tme6M@x<-Hc6$M>p*cI*`it=ao2 zWcA+Zkm9{JLz4HN3<=uX5klU(BgB3$FT`MPc8J2>@Q{Cds3D*BU_xg1=!V?gBN=jW z&vJ0zo)^Kbd+r49*mE|Rzo#p>U{8H;!k*Q^0ecF9iF;y#?e=&E>+Nw2mfvF#{I5ke z_*2VD&}_?G(A}2%K^I#t2KBY{1huy83fj@KE@)LtQBYA!d{9!0cTiA^a}c@3C!eBwLbc-{9=<8j}cjeC91G;a3oX)O0`X-xLr*68QUZ*=u7YBcdp zZdC9MY5e6wYkcj4YrOAc)_B23qp{mZs76PyMbX@AbQ8yji<$cxUbE_m0`s>g~I0i#K6cg*RqbvbVu5e{bbouHK@%jJ=n4 zDtN!%`O|B1=e*a*&U;?xcAoP(va`#pb!VMd%}&18+MU^6Wjn*YGIo-^qIOz)`Rr8p z^4KZjWxMl(r~b}KPox{P&Y;^ zt~*OhtLvmi)>YHI>$o(Jx^x<*E{JAS=T1|tGo?w?Dbjw{{-l1WoufXh9ixudo}pf^ z?W7LY?x6P6a;ST2)2KDIfz)-icq*&bgql+;PmQl#p#;^wq|j>bP@HQADOR-|6m;!2 ziefE`B3he5`Bvjcd0XR5nXWOUjMd0cuGD-ZpQ?FA?yeaj@2NRSuC8e%udUfkX4RCE zb7~UE@ikuL;2H-qy#`HosgWRC*DR6rYNklaHP=X}nxmwZ>L$|r>UE@N)di&S>L}81 zHH~zp+LqK?twCz97A7@RFAz6ZKP2+1FA|HYyNPMlb;QW(Dxz<77LimPLUgS5AevR1 z5w-v4-Ggxtu02@x;Map$4^BPU^x)BhK@aXcSo7e^gDDS=JlOHz#e)$KE<9N9;J<_U z4$eE+?%=tD;SO#)Snc4mgUJpKdkSK&gSQUGI=Jd!se_*mW;!_OV55VF4hA~7=U|5o;4WO z;8ufG4L&uP)ZkEqJq_M87}H$Dl?F>1{Ae(v!HEVN8a!w)puv3x>lu7!FrC412D=%& zW-yw;Wd@5G{ADng!C3}d89Ze$l)+5~D;a!bFp z4lmfd;O&C33$89$y5Q%6nF~%X*tp=~f`JR}Em*hU+k$BejxE@=;MIar3ob2KwBXNz zISbA#*s|csf*}iTELgGN!-5G54lLNO;Jt$J3a%?yuHd(V*$Pf;2x7B>#|j23xT|2T zg0BjuDmbcOr-GLXMk=_dV4;G43g#&|r(m0cX9|WXxTRo~f=>!2DLABHkAgP}#wfU= zV2Oesx)m`)!3hN$6g*HcK*9Y4>l1uWFg?NX1iKTwPB1#bw&2Ujvm-~;N^jl2QD61 zc;MfGc?ZrN*mmIAfnf)39aweX(}76`4jtHY;LU+C2d*4ga^S~-83#@r*l^&%X(9$3 zxNl&+-9>yiFx|j$1G^2pHZa=2Wivr6Ht^TLTmxqfY&G!Isu4pC+%&M#z()fU4IDJE z&%iqa;|yFgu*|?O1G5aAGO)?OBLjmB+%d4mz!w8k3>-1A!@vszBMe+Hu)x6o0`m); zFR;D9^QuA&FL1lS>H?n&OfGP^z}^CH3ydvrwZPH>KMTw(aI%aM8w)%vFtEVA0_zHV zD=@9Vu>!jayecrNR1lX6EGqD)z?=eS3T!Fxq`;5@HwvsM@S(tj0tX80C-9!Ycmmf6 zEGO`rJXH7m&uIdi2|Ok+n7~~EYYBWMFqObj0y_!3BxS@%0v8D^B=C>GJObwkY$NcD zz%T;02&^LTiNGWRhY0K;@P@z`0#_&mv4p@60y7AlAh3bJ0|EmG+#j%h!1n>u2OJ-; zd%)`fqX%3buz0}V0dohO9k6x4(*Z*V+#IlSz{dd-2OJ!*Z@{|&;|5$Cux!Au0ka02 z8n9`=qXB~k+!?TDz?T721{@i%W5A06BL-X;uwcM{0rLf%7qDHxa{lk z0doYL5wJzT69Gd6+z_xrzy|>nq!4jH!2SU5!vrxt!1Vyj1N;s!JHY7xn*%%!FgU>7 z0BZw$4KOvp(EvLGybLfhz{LOy1N;jxFTl9~+X6fbFf72W0INcP_!MALfI|WH1b7o* zOn@r^mIU|_U`Buw0X7795MV%n`vBGh_zqw?fa3sm19%N!G=R$h76bSTU@m~O0JZ{n z3ScOJn*de<_y}MkfP(<`0eA;s99%^XECcWhz$^f#0Bi#A2*4l!cL1yb@CCpW07n4q z0Pq692mluVEP(&l`v3pk@BhCm{jkaZ|8MZa>OSo3!?r#w>LV}s$oKVsOZlIXWqjDf z|AZ{yfB4_x{Q|Ob{}x%ce~oO}&msHuFOk*y=l|QOpAk$Wd-P9`6?)j6hrRjx|67;8 zgKWveg8WTnGyeMjR^nkB{=)xu;7|W=^}YXp8}EI{rhCu-R@@IDtL+`gQu|(HoxKU! zW8aBvu-78X>)VmF^)1N8`UYfEeKoSAUWM$ZS0an)Wynf;A+n90gRG&aBMazB$m)44 zvUDDSteXcTo92GVin%AUTuwpu$~};Ua%W_h9E&WGTO;e^rpV^F0kSi$jckjnB75TU z$cDHivKlTd_={|W|3H?(myj*+1!MvI6|(vL6xsQHgsgjyA&cHOkqz%F$Zq#pWUIR$ zS?E53ta2YfcDP%S?d@I2;&wH%vAqe|)n1LPX|s|2>|$gyI~&=_PDZw|qme!AU}OW^ z8`-_4AZyonWZ&AJZ-eYvn;;9;I>>IdGO|@IjjU4(^M502)L)PV>UYTM^mAlsdJNm2fyo4+%&m-%}Q^;QO7_yOkjdu}Q zMDFMHBKybtczckw;~He+cmr=0kAo~37a;q^smNw=Brllf%VY3JJUp^QY>R9U8}PJw zsyumQUs#y;i@S{M2*2UJKvshva_=G=!I!z`kUii&WCOSZ+5K(cZs%^|u11!9%eeW- zl5Y|>8d>f2<1)BJWStkwwc;9cb-8L>d9DOkh`Yl1%vs>P;>>U+ICnWWIF~qQI46*u z-2I$AoSmE<$PVr*4jb9M&EcdXE4N`Be-48~ZGOezHHa7uYY^ zQ|t%q+w7~z%Irz@5q2kg54(ZAoxOq0XIHQb*ct2ub_6?s&14hV&TKoj8C#F7#+GBF z*ncXQE8kbXs+_KTPLk)Tvf@cEUe6^OsEX6^sl5>x>q_@ zT2&fWYE>#$N>u)1ePexKy<$zV##tk*ORPawAL{^X538QFm9>V&W)-nASqZFgmLH48 za${jx<}5vy8cUWX%37&dtax29Q}LkUR>h@?!HT|$&We_b+KSBx8&FY^SCLu~T@h5l ztnjFCtgx)muTZa$tq`eLDgRVHS3XsKulz>&h4TLLL*;GdJIntoUsGOLUQnJ^9#bAv z&MfyRcPO_g*DF^omn#2Pwp_MQ_PlJO>~`7ZvVpQAW&6q+%eI%TD`S@xmZg=&lm(VC z%G}EA%S_93$`s4Q%YKzEmd=+>m5!BOFFjj&w6wFdxwN`;eJQ83ur#eSx-_tqUWzZZ zD>W|FER`!2Dg9pZzT|ny!;+DbizWRf-6eZV>Pj}2@JfnHGD>1f0!!#6t|hi5MkVSc zG9~|tzZSnOo+-Xxe7*Q=abNMi;>P0tidPqx7iSkI6o(Wui`|Pc#m2=N#j?dh#b1lw z6ipZ1E4o&6y68wzdr?Et=Ax>i;-d7T=pz3jN)fKevIt$ISR_{TqwsyMh;li_p zeT5x`I}5iIRuvW(rWZyP`W2E29ShA1wF~77g$tJp-V{t1+%33VaH^oYprxR?U~NG~ zK~6z@K~Mp`z@@;d09~M1AXe}_|6Tq}{#gE%{8Rbe`7QZ7^4H{-=V#@|<_F|c@}2U{ z^R@G3^Z(_2&YR1d%p1u&pLaBGUtUArraW$5eqK^uXdWZaHP0#!ou`l|lDC}uI`?tz z?c58w$8z`O?#$hk%gN2pP0S6>rRO^5TI6cy%H{scS;~2t^DyT|&Y7IUIeT-ebJpaP z(7R`&VqzU=nwy6pAY71>$YG1#WCFBU$INj%2lFRcEcqD$PpIipcWH!e?1$>1N4g{mWd;e4aU;c{TH7=7G${ z%*~mc%-qcQ%z#W%rhTSirgEle=GTn5jERgJ8K*N2Wi)4O&ERF^XC!0(oc7!>NO*U8#+!n^G%Nvs0r}y;Je2mZ@5)QmHE` z?^2$mjHH}NIh4|rvL%I+lARKr;+=v|u}slQkxE%fev>?zd?R@eK63--d zCpIQ-Ok^cyB!(x_6P*%`6O|K%6BiR^6YeHlNH~(vlCU*_laQSdmEf7+oM4)unjo6+ zIsSS4Sp3EKBk?WqTjM$L+3`{F%y?Y9NxVwDaQtH2Y}}o=b8$U!O>vvzSaBI~VR5uL zY@9)yeB7Vdh1e&tH)023J7eo(*TfdbCdT^5dc<1AYQ;*#F2}rzxgRqW(;KrVW@`*P zCNm}?h92V(V-O=B^E>)o^yBE^=#$a=qH7QUBtJSf+B@1M+B8}vS~&Vs)J)W^sKKZM zQS}JuTNITLVN>@^s|E$cD(ZkwuXSk-m}mNb^Y5NRh}-5i=1Z z5rYw(5p@x(A_^j6BfKM=BTOQcBL0TI4}Tm!9Nr(^9=;=-7oHs+5l#=shUqAOH5<~n#TtiGlltcanF9c5pUkg4Kyf=7jFe^AMI4GD9Y!$2? zEE@bNXgcUd(8-|opzT4Npv<7qAX1P`kY*4nXen?ea3t_lU`ODNKyF}WU|1kI&?Znb z5EZx-FcWYy;8Z|I!1e%6Kt@1F05QNSKqEjj;FJH9|FHiF|5pF4{w)7g|3H6te{+8o z|9^f9eiMF|{d)bH{5JTN_$Byx`{Dcy{p9>sd|&yF`JVIb@~!g~_~!aX_)>lCe6@U0 zzDqvSJ~w>&eOi6C`c(L&`1t$aeN225eSUer_P+0Z!MoeL!F!c=o_C}-)!WWn%Nymr z=r!dv>~-90kJl!zGOt80A1`MwLoZpc@18F_?|7c}-0!)=ljE808SLrdY3`})`G@(2 zInKPm>}J*@a7zv|oJnR{Gu4^G%=e5(jLVE8j7G*0NHPxL4BYxF*P z6Ma3sh#o^{(Cz6ubQFD&HbuKeJ4$P&t)~^yVrdMTJxzy(qAgONP_I$@s7=&$)Iw?u zl}^P_wWy-hkCaKu70MAxBV`RGpAt!-P;4mb6d}q2`62lt`4G9D%qM4)L&*fPIa!(f zn>0@vBb_C6l6H{Tq*RhW$(3Y8k|lj3J|m70`-yvrn~0^vc%ml}OVlBvh@S|L30DY5 z2)hWY3Au!D0+C=rP$vBLnD-d-IODP3W4i~-BiX~(1LvXdA?5MeecJuH`%(AZ?rYui z-6P$}?pE%q?tk50yWMj;>$cx*yIZAOvYW4)lbfEKq}vjH3V#*fi*LlQ#^>V0@I<^h zUJ3ux^_Aws&U>lW8i*LYW^E5=pJRmAnZ%R`q7E?q7)E*zIM7k?LL7Xue5m(R}A z&exoKog1B3JLfouIuo4DoE4mZ;GW}d;relVa2s%ixF{SIXN^EHt?JwCMvahq}+Nat3+dJFq*-O|jVkR+{ zFo!U;7%nCaPj-`bLw4PEHFg}kR6AcgCp%p`l-&p03EK;{2W@xQR@x@n zdfQ@cwQWUg7i`9D&e`m@*=AF2lVHQNv9r;z`Dgvcddzyzy4`xSb+L7fHPzbMTE+U8 z)hnypR{d5jR_m?ut-`H{R%TZ6R^KdVEr%`pEO%M1vdpp!vUIgHu#~b~vUqH9$)ek$ z)`DY^V&P-qV4-axVzFR8ZhqE$pZQkvQuA1Inz^;Piuo_IS7x`(`psI*)|us*g_(Jn znV89%eKnmny=r>cwBD3wnr7-}>SU^GDr&l5GH!C#WS_}alTwpd6Pk&&iHgZj;}^yw z#>b7DjMo_F7>5|+jSY>ZjF*fa8x0wC8C4rq8YLNd8exnyjQ$zEHoRka%5bmY2E%;A za6^KjsiCalSA%JTD+WCVbp{-R6ayav2LmkwVS~5&WBP;ot@<1F3-u%PiTY;xa{9}9 zGkRC`4(rwFarIL4eDoajwDg4a-k`_O1L#)tMsxu>0!=`hqGi!vb*FT%=pNFo)n)4@ z>w4+h>uTu!)0x+~qjOSckIp)sJe^P-HytA#DV-(lN$nx+gWB7*E41Ua8QM15D%!ua zUTBSI9n)&mTBVh#6`p{s41v@ zQ=L)0rg~VlPL-pYtm>_5ud1Q?S7lD+wo1QBv&tHkY?UAt7ZrUKag`6s50uX;cPMXG zE>@0GCMlaK%PD_Vno_!~)U8ybRH>Ax#8k3XQdRn;_(Jif;!(v$1aQhw^jCCJ)KL^s ze5){~FrctkVZB10La2h9f}w(>!lL{m`3v%$^8d+~%E!o40=p~7y$hQboUAB7$Y zofFz8v_+^`C{l4fBJuD{#}s1fBb(vKQ#Q%?L(^%eLgh#(BVUS54}A!_R!Ts zOAq}#H1p8OLmLl0JT&moy+i8`eLFPm(6K|i4!t@w>d>V_iw^xcH0RKnLt73#IW*+Z zjYBIAeK<7X(1Any4ZSxs-q3YJ%MJZDG~3W=Lz@jfHZ<7KT|;XPeKj=I&{0D>4ZSop z($Gai3l04=&6481Wl#?Tc*OAP%mG{evdLmLb| zFf_o>{X**teJ?b<(D6dM3%xEhy3pl9iwpfNG`G;%LR$+xEi|;y%|a^+eJnJw(7{6c z3cV{duF$nY%L@G}G^^05LYoRbDm19jokD90eJM1h(2+tr3cV;aqR@px3kv-wG@sCU zLfZ*FCp4VUZ9=OFeI_)S&|yM*3B4sWme5r~O9}lXG?UOtLK_J^Bs7rFJwodUeIqoD z&@n>02)!aSiqIuOiwON8G>6a`LR$zuAvA>04MHmjeIPV}&;dgG2fZIOe$e$n%Ln}) zG<(qLL7N9X9yEB+-9c*yeH}D)(9uCV2fZ9La?r&=3kUrhG;h$kLE8pB8#HXttwE~> zeHt`r(4j$l2E7?HX3&*EO9uTIG-J?-K^q1=7&KteeL?F5eHS!c&~ZV#1-%wDTF_-d ziv|4^G*{4BL0bhq6*N@PO+hOKeH1iN&_O}_1ice9PS7<$%LM%rG)vGaL7N0U5;REA z9YJdZeGxQ8&=Em91icV6LeK?43k3ZSG(XV!K-&X74>UZ`?LeyoeGW7^(BVLP1HBD2 zHqg~TO9TB3G&9i2KpO)+3^Xv%y+G>%eG4=#(6K=v30KEY;2GA8iO91@}~bR#ID zSg44Bh3=es$_&3SFkWpnn1bEcdp<=iOeLpcY^c~8!Da(I z8P3IU{)KZcoM++O3g=Tehr)Ri&XsU}gmWUC2jScY=Q}vZ!FdhNWpMt2a~7PZ;M@e~ zBRB`ac?ZrlaDIVv3Yd`u_i;`V0SO`lA1iPP%J+qy@$lTKD$P3NO7(9NP#O!Mg+(i}QZbOfCV+K*24^rDkF8`0^S#<~x5 z2Ie(7$#Nf^M!Ag6lPsh&AxF`LzsN+*8%xbTZr`I@@iuYM{!SPFee|yiI4JtyC5( zvy|b=PRe@94~k2QU5a@Mr6N|*P2r^YEWae*E-#gfnyXA zJ(V7oR!UXUXsMgjOnOVQOHv|9m-tJZB(KCr#1&$(xWCw0{6TbFR4I~(f<;Y4uX7LO z&dnW@+bh>T_wLwjV++R)8QXU3mz?7{3v$NfbkDKKxstsqTb3P^T{rtq)`l!iR{yN} zS$8uxW~wv$WjbWu$XJyj&VY>C8E40oj~O|}eaxrP`$kV19WmNz^zHPO>DlQ%>EF{1 zq)kd2m{u?C%BV%7Qbx5M^?c-}k&=;JM}AA)lbW9zm}-`KETuRlG{q+6RPv1Eh-CZZ zzmsMrMI_lLolcyd7?x_(jq4cqc*OD%2_qVfxG=nA z_<-T2!}ktT4C^%PS?u!IxY+u!r-v2|^&9$W$c7=KhBO^=e(;pRy$63Dv|&){poW7^ z$4rRn7V|QCS@e)->*#$^k|@`xYmw6wdUfMmL9UySm1AHSM~_H^TR0m+~&XyFB!n;^XOa zp|h%Uv(5*-)4Z*`H+G8d^vSE-%g^hsXQ5|1&%Zo!JRCf>xesyw>bB4g-0pN7-?4Sa zqaD&aSaw*~KCJ!Ab|vk++MR7HZdC)y>YkBJit#`H>(&}T&vX)(1 zUT~4R)N|R|BD%%f<};gnHb3p0r!{G!w84Zb>`IZs&mSI zjJ>)2GCM!J>$VEpdbXQvLTw&fPq1!o&8&u6y|*l}>}Yw+BGp1*QC{1(_Br!xb4&9- z%zB&MFjbn?Gu>1xq}C&o0+VJYyNw4Kzc!j`{bcSNbAOooz})ZUzApD~xlhae zSnj)Wf0g^F+%M(6DEB|P&&mBv?ptzylKYU{Z{)rr_Yb*G$o)X>`*DAd`*_^1;JyU+AGps@?I)0L!2JR41Mq#H@AZ6t=X*Ne$NApP z_iMgK^L?4`#eDzedoJH+`QFO+Q@)4teUtB%e1GJ7BHsu3-pBVlzQ^%>jqhcA|KfWV z->3NA#P=h<2l0J}?=^gX;d=_-NBG{s_Y1y9@O^>r1wV<=eMPM7Njgcpj82mdr4yB3 z(YeApI$QS(oi3Y1XRPi}$ErWkS(~j@+m*eQM-}}QN92C;tuhzcH0e7@jAXOeQXDVZ zko#q<|JZ_@ec4~LJhGB9r)QAQJ^FjPQ@U4L(5S&9lT$NN#wL$V%1%s6h>H)8>oub7 zaJyk|hn^dWj@M~!!m8gh3E+j8n-~$) z5*kMc-%zrt7d-@~Rg|VP?MP3pX*n&YSUnPs!aD#X-a`v1!Wiy6(YT0wwNBq z$->?Q<|aR?pV9QJZD)MQY!ZoEIMc)Uh#5~bauHa()OBSG`Bd%i)&+uT3IyV@48kOYUE<~s|jsu^L`t-)TJggp^(`( zF4V4eTMAnVpV3n&v#TC*N~gd0@aqz8p^~km1VXtT4|SkaoAcCYp~8+gxj&D`(nF}U zzq}kR&PHp7&Zn9AFz0GL#?FN)#Xa%=233}y<#k=%iDUnCjL|4xQbUB`h=dfs+(A! z3s*}COay`k{H>qH0!J4@VU9f|kr?%${>vJ%Hvfp(3LKa49>4YdCAOEu94S~`TG&5g zAh0jtrF}3;_$5b?`aNspBowG_t4?5FKy?T$EhqjGqn6iCtr1&DfnSXi3hXU-aZN2Z z{E{P;)t^!$cjzBEGlBh0US6W*#b0u_NN#J5-1C3rnhEUdak*5hpTFetNbVX1orKq@ zcgCa4tL;kIkef_HZYK@-y!-b-@7fDn**I7l+cdI?F|`*)3hhkESX&A#EqhTSmEkBb zw&`Zs-7?sLhS892PO3Gb-coukA*GwTl2Bu7vTcKOEiP?tOQrBYZHM1vEv$bPNFu(Z z3`>fd^KyPgt=xoQRb64NHdet7_QEbWPC>M%K9C@``p=}pOXg~DJ5URAy3f?x-COM$@A@E-NUhy?1l zrgR$3>TI%Ur~hnj4=Yk`t!fccGwHGV)>I>n3Zcf1W96@K1A>1pdQ~74gmb8@4)Tfo z&((`ULO}$FK)Q_tVmpo@bejlhCN1KjO1epip8s5a6cP#|IT+rn`}=#5zr7bpGXGq? zDI^p`aj2;y>NnY_e*`JuL${H@V-ZI#EEL4lw1y{BO7+#4o?Ick#Wh!DO~8P^$AK)^ zNbs0)jD%lptOY{4D8gs0o11%dZekXlT$Y;|B*{t^r)Ou01j*fo=j3LO%1z949+{qz zDspy}`}(vUJ}OJ%EY8l(5IHC2W;&;4CZ(pNq^1n_cI)Eo<>Bcy)_ZtTde(3%G9x|7 zoeth|C$WxnS|k0Fgv6wDcan4KAcl9W`zKiR>C1Ods#rzDHLE*;%8Us~?gqQTnK?)D&m#&_u-t1O-J4DCp@EFaAx6XBy;^(-Lz9VM$bb_4_>M zx7vI?yLt&oDfD(u?{slwsx&$=DI--NsVOrhTf*Z3-G&E*Mg>Rxdd5ekiX}OQls-}6 z@geC+!=th#xyh-+`vwFE(y32D8HuAJf7iZ9oS2oI%11zu6D>q z!GH9uZ&-|TfOGYzSKEiDmq!<8*WA>M)I?EgTjyb?1>gXNcrDGCVVse^uZmKk0 zM0V)x+10y~N9Pg0I{hC-i_)@l#m@hc^qWGwJiL7cN!6MNsvar9KZ6k+7!@5KDuDmbifOo)HvzbSNjN^n@vzdEcQ^%^z%SF8C~zxnvnB>CTo z%O~9bOq756?jPAVCNwZC+R&by0B*HeH1QKNsFT&^(#eaA=zj{S)<-~g>d45@>=ZhI zGBsCF-M0Ul3e|S_Pi;}bv4QcS!BI2^0{Z=~z)Xt8vremVylRzTj~={HxN1r8w#5mwGa|pNiG{*v;(VctgPv;nEiWIQqbSVZoJ6^ z<3gipLVp{+UAl=Bnc~DGLUHadOsfe|U1VS>iQ+_oTarj5aHBcv#uMHC*EHO6vwsP4 znUvHd$tW7dk=gWmbvQ98iKg?f5`Lv*WGDX~O{6(LD%DWOFNyz6$w<$lZQ)lgHB#V~ zoSm7O%4Y!$gIl6loSU8`5&vf?BWd?a{Z|M7SEvyQ@J*5YpX$rofHm-IzZD3YQv#Q( z-ed^>TaM@Ps}0@c-2I<&{P)>^*IP+xHCN3J-+>Zp*CZ0A)DsH)2>DQQ8GiHn`q9nH zt7-2!3JZSn$FHlVJnj?Kw3X+aBN?|^zhwBcCNG@Azt_8r>TN)s=k=P=T~luYg=^lS zpunh>P%!kjgqmRPf5{CqC0D*C^S8V#3jbcOzJXBSL2|raav%SxcieC9P*9LzCKNdH zfZ?hsT0`;Q%X{V|6xdN3FOScintsftaLqdu6ilJ=xLnOulQ)ABelPFaZ{?A*|4(@< zC|vUnFQc5w3-~ReCb)$1elO3ep|E;9dHZ<%HSOC>Vg8N>-Tb;~E);yLF-D5>Jbv@< zA-~IAwGz_5Z20%8kvmLD^mceaserFT)mI+Zx2d2#k5E|P_bUz*6zrwj`B!`(1qHY0CM9tBWFCJ-Hz}FN z`Fx{4j9INH9-qMD{JRNtg~z$Q3;5>&>MD=_ei>KK@PAW`|6^o%fB8)O_cE@YNx#SW zO!)UQt{$o1<8`Y0&&TiA#VzFD%lN;vX)K^$jK5vHTc)F({pZ{j&@c;vc8!*OzNd`13ok0TLbdR&E=fQU^u!Pu$KWt4LIC@V+^P? z;A8_XGT?dxG6SA4;8g=YG2mwdn$w))_3|&n9Q_P9(139U%rv0dfW-z}Y{2yf+|99; zK!66^&#|sRaNdAdI8r_L4e=+2_Km}N0X+@*K8APzN3yE{28=S` zFasuYq;hf$ak&BW3|M5q862tIS2&XV14FuymPa19=1BFp8sgrD_&`H^xFIez#0w1Z z3PXI2A%55pKWm7;FvPza;-=IFULU`BdnmaYtLF#B`TD`rxd_MV?=FNL3~>(wb}?Xg z1NJvym;tNj2fa7c5KlBNXJ^k&bX=Dg&q%P)1%?Fu`fSB(<7>Wa z^}7EnMr)uo88!V>@~%#B6*Lso7vyZq-)IsfXvID?5G22~t(EY$SzxOKvxQsU3v{Uo z%@dOno1eD7OtEa2)AWq5d-`W9p|fCyd60cj!ytjn&yPQTrfoLbn8WhgzdmEtj~2%F zc_S+m9wa<{SUc3B-|~c834&JlADV~OHiU0JGz&F1gfBl7d?JNaUxc^l=8j7q-FxX4 z{v0dK@?;dyD{gv>tZSd|-gr}lZyWbPuIX-9iYr<>KH|%~! zc;5Ed?uR_z^Um(ugh!&j?!HQRtD8mDIl`;Q9ji_dUL5XHb&&APbN8w$!V}saRhtM8 z+Xh$tLAbXvrmCE9muFH{3E`&wSydAVS4F9+gG3aZ8s9`81}Y6M|W!HlXf!hOf* zQ~_c4x(lm32)7MiTGfouefg>?8^V>(H&lK9p@Zf=+pC@s&eQ6vE)m)v*#u*mjU z)keafgHKg0Ae2;|uPP*b`siv^4q<}lovK*E^NL4R0ffQ(UsSaxWEStM90)z4zE*wt zPW}2zpua_E@y1wxm@vT6OuvRu)y+abop4K>wO&N{B;QUyn6Skk4*ITyLykM@8xc-_ z>7@VuO$Ub@n&@v3e(mC{M?#O`F8T_>)V$Vu4dMJ{ZS}(lPaf@{?@DO&++FWT*xA05 z{>@h%q;>YupCp_=w5xtK;R#I-{dmG3i$Nbp=zh4j-j^`pNub`IaE48={_z*mzgLKU zAK}YE1NCKuO;nNkEW(gQG5S7)iUULRPJ}BS4%0vXtb?3CH!VC(W?ksc9iS;6Ap+_=^GH{O0@b1AE~`3 z^7LB>Z^q^8^9bL(D$s`zniNdX*C%wWH&K7*gAUsKQKVl>=-YL&UP2gryjb6hFm}XL zy(!`7m(%no-|Ij*Zic>;aFWAJ{V>9L%V+7E6aLYqRR7?e4z?egqhC#UaM)aZ7UAE| z=jlBOZ|WB4-@VnrGy8@5?S!9~R_JAfwR|e|zJ&Hi7wbR0(Lv+brTU$OZJsUD%Lu)+ zEA*WSd)TeizkN-1x@47pBjG^rHTn#~A&1xMT?rG1tk>UtrGxY*8}t=~W7V7VLkQ(I zTlDsXy2`EkKVRyg&}+LspK!{-9r|vBC4+Y9U%$}7oJYI$e-JKE>h&WC7g?dc4&l;@ zJ^I7XX`DRv>6L`5_V3qsBwQ1HP=D*04%R(5q@PK+L4HIZK)BK3nEu^U!ty`$%Q(87 z&_{9H`HP`AOrGfP-=ldo=c&Gk(AV|3zCB@w-7oZi-PM6}$SZvop~H>W zdRs!%oVWT7cXaSc_+B4I_;}U_{qx(jzP0+KFDCqR$7g+8!rj4N^@nd!f3AMhClQuq z{?Pxpse=hWf9mHE?m8-9-h>-UgzV%E9W0MEVxtHbxEM15;f!a-Z0>cE-)6$x36=mWc4*=!wHk@%-EZ&G%qfjv5ADiOUzj#!X9I4vkg~hK6+cQ-h|D+Td?z&sr`p7 z*(kzV)2-O2OFH;4*qTiueCTY$oCq&HwqYwT>fq>RTh@her^=2UxSY};^ z-8xTpbD<8)Ae1a}V4u$EAUUlrD%qbdAizY0FF!yW|cKM_ZhLtyE z!wLJOHe)yb(m_WzXO=)%@1rxjeL@G{_cUiog!hVCusg?TJ&$ldB)hrW zlEo2f*S2EUj_Dvp(wYq=4DQv2ojq~egu^roYnAYWX z?O8X%MQ_`)&4&ag1BfIYA#S#f871!Ou>G@(Hd$5`8q%w&0CoE3y%hqku!3eK@%$CsOYdj^^FN5EemLXJaVauvQ1Rv6vMg`UJ4(? zW-iykVyD6E@iJN$?+j)@=(%PHo4u6QU(rzZcnR%OJz`le!opg^Sjl4ApH2>A_bRDf zWy4t)!i(`E*rY`?KV9S4l?u}1>p0equ*L3prd&w+%THi`mecw_Adxj7Os|{7MlH}m zyX#48>wMaumnSnJ;p(gu7CMjCqb{jz-dr8D6^vx}%E(TRj%03x%S%Qv`5cu5G_7R@)!74y=MQSZl(=HkmA=gx2?qnQYSxTE{B0 z82yho@G32vbtPQsnZwl6bP)F?hv8J3HwVTt0paoDT;@N8_SI++%P*$=zKNLapG@o8 zeK8XfmamsEze%*u$fQhLMC0ivV^tGrzM9L~r$Vy-GjirlSZ}_9_i4)o1**fq(Jdu6RqIR|`Vyy}Po>s)dGiiT#Tg2oUv@Q>x#45+=KwmY9 z9T`paJ5OdW(seL+{A5;_aM`2DtXmq5M@TV?A4T(NQ!y(TN$Xs_DeR9_9h_54VSlF3 zc;A@9o+VR1drxIHgj-ikW$sDjXIV^R;fXrvmpzSTC(!&nJB>|`r}e4JbhbWD2QKB) z*@+RPH^B_{csRY6GJ}~Cemy#awHQY8tYZo56{~~EB_(X=P#v6pU&2H~NZ+wD+0?-f`I>_rs$5d&wlT7=uS%w~-uY2MT?Wu6h#4|ORE z3@5w0Rmx%q>R^ALIV>}b*85d+SY9ZtPu68@RtWWTY#CcVfcD4pWo&zY(oeU!>~Jvo zX%%zXg?_Yt7|ml3`jS14oX6e;QU39H%$Tsh`+Q~>Nbk>@&zkh1-vJ-zv$g?L{_q8? zb8j8=-n)SL`BVKZ%UORv(tlAoiw0`nvvM|~7uj>fLN>Ce4sy0FWLZ6Qu-2)9NxD=2 zG!;zUjrPYo6)e9i?Jq%#Sdp&|N>?vpQ@YUa4x36=;-dp|Q6-z*SqFX>D_NO0`BB{$ zv-zFKk6E;sm3!&nk?|6?(38e3Z3(OJ&_T=zio26v<*}44bR&JtUdqZl>fqz2rEGo& z(&va}tgJoxA^VoG+3l#lR?FFpwmLXAX*rwXO8eOJ97vKWtyYRINy^ z;U7%WlKQXxgJrsq|8eIJmfC{WkG?C}@aE*7u35>VoN0V*SFzw`sg7t4vZ(SXF5CDk6)~38MY)Jxq%I_q4i|@ z2G+-#{GWy!nY$Iu7wtyoWT}HMcQ!I(3(|YvP3)ODwP(#HcHT?}*|wV*Go^ltHnU~5 zXdk+`nH8JR@4fC@*jQs4@5(J~uo11NCRswv=BdO2kY=r3%ch!nB@m8 zEQ;949>3E9ZrjO@yw$>Wr(JB>8!dd*>|%MZwcvDT7aRUc3tfVCvo0^S5WRXgvwxw5 z9Gfck^qCf>6zrQ7H(ANS;!+Td@^Fp<)IepjAHEbeJyl2 z&e*AYS_pJUw(PDJM$AGczoP}oM`R(lwJ>$q9@gxZ7MAVV!`|G`!fuzn?7(#`oSC?n zm0r`rgQt60>Q(CBz|b1VaVfSOtnV~NuhtTo~VV4O@FcUc0m~&Hn`ZzC#OhmY-l%+qF<$`!A;0riG=Me=(n}T3B`FFZO1$7S?w@$<}Yu z!j^d_S^7pT?D&3?wcMbEs>D<5#yTzRIdqDZt<}Q*wx?P68Z8{0dYYN9rhdLY&GxR; z!jYIWO!|iwj_x|cI<6pW@;AG)jBwoFtZXUa{l8hr5|Rr(%LI$HaA@6Gwq+5Gv;8@i zTA_u#l5?#7LM^b%=h(3YTG-X|JX6fq!nVcdS=)J9*jVcVyIiJ)HR%^v(Ht!-|LX$t zDJ8q}yvXj&(!$)*i>zd(7D_%}WIao?Flodk_ISD$#_hYrW>3?Cywzm}Q?-ya=`wp< ztc8^4m)Xq8T8NFf!n#k=!oY1;*xiX*2ynW}iVMk3HCLI}1TD0`eU)7*&_dI|YfPI@ z*0rO@~|TyjTmPXWU|9kroEOyT$6{QvE}2vyC}gaMRyrq1iNVobRwF znOZO&e}_%T(8BYFcUbc=WLE?3vZ{0%mkoDWOqv${aJa`_j?}_***#X2ss-uQd(1gS z3&Y_)+mS?ewDdj;OVmOevj^;cycVp+JYcFgExbDUfZ2_pc6&W!%ZAao&w0pvW3@2< z%R_d2h!)gwk67GbnqT`Lu~#uP|64z1`O#WvHu*8D6QzY8&mXg;5j0ODo-nU)E$FvB zVf(`9eW#}^Je2gVdCG1K&_c}Zr)*4rEqDe#V;}oz!Fts*R?t@qkF1_E+aR)ooaby_ zA1y3A_nf%|Q2Tvfuyy`4F6A$nkDnG?1uq%)(!$T=mn^8K7A_un$^PoDg>~&;v8Zk| zAE&=!mwmM`^zADa*M;;q_%*xRnZ~K=H5=tk`fB=y(LqwMD*p}3^rU`0c*9=0Yay)v zTQ=5>`m_Emd((mRVgHWhw&(Wvj=gD1<8}ER8|zB*zvp}Qvb7dEE`HB4ThY2^@_{{Z zA-hidz(%#8b>PGYcGp=8i5?$WTr*mqW`AUtn`q(V$B!(kG0mG{pV(gwwNSk06AN;p z_0Q!q!}>JuCw^u=jcHA1}y)^Zq(L-P3`Y2+?>|8jPGo}sTO9Q{?0npqI$f4u%*UYs5|!u zb1nlnHS8Ck?b*B|y86 z8W3I;pz6H_ZdwWP{#y;`dkJyi8x73M5#r8Q8jvm#qVr2C@0<{eo@>C()CgZb)qsVs z5e|Byf&1x3sDGq^y$g)6`9lpX_{)g?$g2hS1G)T-U(XPsVuRss^UEGeMs#8b}>(f^#lupyxCbe1Aa$b@!TJ^mz?DeQko9 z&uU=5OD(kfo7xvs3o}k@AbVmhJa&@$wW}7k{7VCkp4LL$aSgm`Y>HQoY2Z+pDRw%l zf%$o+IOVVgvNoII{ev3lea{qo9?*cJqZ!WLr-8?P&G6|S>c7Ga{ZRwc*O=iPy#^Am zQ~GWVbh0%^zg-%r&C#{vf~ zC4C&Vzy*sn5c|afA1u;9n+}%fQK5miBP>x_PIA*N@!)(76z{V{t9cq2^wtui%QVou zl@*qkYT(%*E4(vH1KW$Nu-8^S8x43Js)-Z1J0n>}9zvc9l~9F4&@2OnNZ4!;QHb`c7+yPjWQSE5i<3 zW|JLO*kN2I)pN=Y=Zqme3GMM@x(0$f*`sM1*;}eT_8h5!6LaiQl*096kE@b25cb6$ zZzO2Irb8Wch}Xc$5p^(Vga)QfuY<~A8VKE22iFeOfYsYNcw?{z{%q-hc7rr9X^;c@ zM{A&Okpqs6)PTuu2doU&z`myrcq&W-+9q}JM~DWx53GwF258`8UR@j-tbxs&>*9pI zWJmYv;-)~dYsY$cEkFbJ`qo3U-WsS-)I(1{4GdXR4~O;Afc^D)IKGDlj@vlm+HM*s z@N>j-z8dI}>xf@{H1KYzBR21>fwkuyv2Q00B%9U83{MR->{=g7+%<4!bbZ{`Q3Dgp z>*J;NG%rrp$FFV44u00hCaxO#{n`MbwFX8cH^79JR9|TW%xj^6!-pGSrLzVUpBmtv zrW)wj&IzwK*1)Y{PWZK<24+rmLMJDhH+!70bA9UHD<_PoN9DC>h?x!=7#iIWi|k47 zg$;3utp=)gG(^3%2F5&Yi03V-eT^F7^V+1(kVaU`oa)gw!p5d#ryCn#Cld{vzugFf zji|p4jWJH30gu4ODEgs>8`8!&@tYbZuWXF-zo^0IN@HC2Ney=_o8aCLYM9ou37(+? z@w#R=!8>p0V7$sE`1Td0|J?+QU#h{^q$$>UPV$|bV)LhJC?3@m-5;yLdtOuQ@lXxd z|7?oE_th}rTT_g=tA-A4%`ow{8qUQx!;G71P?a=8>2)gQekM2-I=Uf*&yiE;fm%8A=Eo#U;?}Ga_slm>yC9(}_Sm)akcdb*y zfYB{+>l!sYT+k9XtWv}Hzgps|Kh)s-vn4KBt_HnFD_pQt4TF0YfLI5x#HG1xRl0+wZ;Ln)X?H(YwT5`hTYC> z&~v&PA|l(M%TzTyDrkdsi`Agr)&^@$QbXN`ZSZ}e8df)O#rxyc0R3I@Tt4Yt<%;|B z)R4B$6*p?t@a={xE>x@OfBtWala*?4>D?Bka?*>aEhb7yuglwFh*%9*F0@6TTs4d_ zZ->ot)bPD)J2cNy!_+bD@bwrqG+o#ZFQuzt{mFK?XOtRx3fkj}R5hINY>!it)i5l% zJ&sLO!{gcQaZtP(WQW^hw-IVE`P3ep3{yi%+YTrgO63gefOiH_yQg%(gVAJ<*a4SE zs$t*D4mcrP4I#}tVrrNgE<|?3J|SvI9N!UL`m5o|wvH(5rv}l(j(8)G`qjVD!L zdwQaGbF#Z6Pc&<$hN#(|c)2m@|BxrHZm5RnkDjP(KygawM6*RN$jGpgRFxRg$etM$<``pgR zUa4Tx($1LwLIuL}ow4sT7069}(DI22UUu=plMhvpn(l)$?yKPHd>@RutAg+oK3Mm* z3J!hu!Sgp%(9OLImR?iA`h+eRb43L$W_H24msC)CpbP$eUIpgwyWotoDp0oe#n3Y< zcsAGKRl&w4UGc*q6*v#1Ho3^N6>XmLda+3-^ zTXx5W8&r_evpfE^mg>vuj(Mw9(6zEVdaYE!(lg!h-f|UK8~4D{r7Dnm_rSo#D!7r_ z1K(GuAgHVdE-R=09qoZp^HosqOAi#zRe`#FPh4NBf;+=|;;>mN=r^q=nw6+v-JYJb zzpJ3m>z)`lh01Hu3(Y4}d!u^c=7}okHK7*{o1lWl+k2r&feK6>^}@AzDj4Ym7^PLg zk^X>RR4O1-!%78>&pNwh=8sh)RiN|r$Kfe7e(C=BEl~ws7Wm_Wcoob#;ZO5X1uwq)Fz7&UB+e2xyz7k*!&G3_IsnIos33lD057X#hUxt%BW+`=G{81$JS5ux>B1BV8X{(_IC-HugckuB7ifeei;h3KAUx zakMv$U!Oqy;YsC71Cjp98w~v;5LrtAbe9ewb)Y^JHj0d}^VB*OU99#9Rg4_5JWiEfq|7-VY0n$!?kkqm57n4Z?$Q z&JQIdjtj=d-;}Uwb1*LXtb|v0gVFV)5`63R$935sdgC}Fnc0POKd372{dKz3gVjk5+|&$~*9Uqta+N?3B5;y09VPZ)ywt4e6y zDFnM+R>G*15ZrM=2`fuO(EFSc9vu$BO=pzg`Y8lEo}&D=p}6vd5>~{9Vv9fN{o+t8 zKca*dEEF9NDIwuSC{Ek2gz{!#Xu4Mkm&3zQ%al+rKMddRRzmoeFdVZ}3B~uq@b)$( z9I7`E2W?Tp&!B;Ld?WQwJ`iEO62`6?h@00?|E~Rw%)#XE>TKqkd+E zqhhfV3Kxar;|e9{Plw~sawWVLM&QwTygw1xrA!I2DG|7Awi2e5Mqr(pO4xTe0=3hX z@a|&-KAA#tZ6k5eWF-uVjU>NV36qK=vHb)k?AAwOX}%JkJdea5Iwdr07KI}_IpceEc8)Afo=$1@1%rf8;78`C)w5QAz182 z<6CDa-fpi1<32;tr!9@MWGGH73MMTH~j@kA^hb5KI9AF=3UuY_jq!!XT;#yepcZnsoIM9DBTsZIUZKMW&H zssC?>VTG|0=CvG-PXtQX7&9DwekkB@;cy)HRRPy_49DZ26!7}daIE)10ks;Az__;x zXgFX5u6U(@j_MKk;<*C+){Q`)rwWL=F#^?(6p(5ghx_j&f4#^L!Z3fN&1j}0zSeVyYm_Pheljf}_gzZGz&EFQ0)Qozfj@!0e)1$_G) zk8yu0z`T6|EyC$kx-}`>dCQAJ-@#Jtzr1Rw*D`mV{|56d+!igq2Gb zAitc17b_LS6DFf|g#z-rCu6_@1r%f?qkOIcCM-}?m!A&8?S)EcPVIKTnAl!Bo zeoj(AKfh7fB0&K#b`%a6p#YyHqfiv9fDUIz;rzi0Xkn6u`=S+4zjGQsj8K5($TYMb zsDPhy($FhJ0dJ3_;hA+gi#sTw_npzWr>z3q9me3b)(U9U zXAFLJQGlsr4AyH-cD8&BdNd`wyD$a^G*ZAJvkXjapnwg&8K|qLfU@)qoLff$y7?Kn z(U!_To`FZL6cF|;18>$=fOp4C{9sD<8JCGxCe)v4nb=&YfV+D#$*$#alN_c+X5rZPa>yyj!h$z)h}@cmr7z{s>3$ZjcqWIsj@h{5u^iq7W#f?tayTo? z#tV1luz6)R-oGWM?_b&Y_PQLhEOJnIRSpBX=b+6cIk;xzV8iorFj<&`t^bz8&A)Qc z^OPKR|H#4aC*&~OeJlnZqxTZV;=sdl=vy)tha8YYv;AW+VXquMz8Q8W3Cx=~`gmdIjR6*&py}cKspL=0AQ;iFb^c)D7JXIjW%*;N(pY9@!_R%%?_nCzsd8jGB$+)OoQ zJ5swV)EMI+2j5d_>}Ds2=Reih%vughJTz!xA%{VU8hmI<{h6u3KaHur{Tf^+kVE!c z4Nm_q1Lu}n%=sdNGtpX%_$Y(?30m}gCj+nTTC{sDgWC_Z`0}|7rq|cu$tN=C*-wXS z9?IaUT!%&XWH5J?4pVQ-pwAT@`rnX&yjC7IzAA&in&jcfi!x~8lZR){$v_sChilHr z;Kay0EI3K^>hf^-aT$oq^3eOJ432EbL(4-lXmm6WZ|{>q)~!6;fil?pDG#Ss$-u#W z9479RL2BD^*m;`_w)>C6+M8uy9y<=Nt(U>j+;O;mjSN;#9*21=W$gZ@?H zu*DJ?%s)F0-&Dxp$Ai;I5hG+E=rkU6VKV49U_AN_pm9kakAi+OxS$%3d-}+r z$?Wl{^_M})+VR+<7wO~Rc>LT=1~0FT$L(EY(E0s%%=MOm(s}~AdCFiB061?LgChlc<`JQ_MMoB*=MBi{T`*Cl!EW~ ziManyDdg5G!ZAmru&!efIvkY3!@wfky;lm&DgsE6=E`>z- zRBTa83Pm%f;wqsOHmsbAZa*Y&VeeGj@j}mC{dMfJQN}zA;X$Y?*klB11 z?tdnMnO&!0pT`o|9x)9M-Ivhs-f0+gM*=^_O~b=C=)L(Azbb*i&6Iyp0%?De{5c5} z-=X(UOJLm>D(^1|oT@V&^~WUes@-(-JuCtHfa$npzXZI7O-Hvq5{ME_$5mAl5EW0y z7CWilrPHx|s{}SzO~<;MByi^Jbeyt|-hVnBO;$_5#$*PnR!E>j;~DsRi3Iw4&%lw3 zBrqyu23}ntf$=FbFnq2A7OQ9A!PydEvu9wJ5(!*hI|ElwmB9OhGqCYw3D{kqfl~`5 z(Ej}l{E<)nur9%DodgnEmEaAP1Qb0>FjOvqSurK37fWDmW(l?%D}h53O0X0o#`|aaR}8 zyV)#k;w^#B&1PYq2aQ{oS$MaD1cnZrg@J7)FlN*&T+vDb8r>{3YaxMYWwS7?sRSxE z%)%oLC9vVhENoMs>bp4$Cpbvp$@T|>jTxd@9!fgCvB7xdNW@C&{ z0`+rdiowE_&h+)9#*;xOj7zRI@joDAdkR&L@!wsJc{&dk%}?z^hWUKOlzV=5sJ#Z+7_n6h57Opf zQth#u7Ts#RHin=Q$TmN7H-3b1`_N7#tJlVsVlf>MG{qUvXkO zQFboc3=KH?;>m$xFnv82twY3MRC^u{=qH9B&hxOSj~G7t z&cj1~Vt5xm4~=??;YHd!?A28akMriCqO%z8&Yg!_JjHNr<2-!cQ4Hsg&cinC#BlP~ zJWOaUhQpuc;oKHtK)d;Px~UkpyUs_mMq*g!Hy?Y}7sIk4^HJm=hWR=3ah0tYW)#iG z>y~0DtelT^%*CMEIUfT}#E^4(KFS4RNPRRPSAP@1P{9Jc_DKYx4HlsFdlC41EWlo` zMd00U0cJfHL7RjHSn*f{PVxnK;=TwhXDq<4w?**%j|J#@Lj*7OEWklmL~!%s0?fZ4 zf>SRS;QGHsu*a+%FP{{_hGykxa$E!zUCPnzhzO<*EGPe+zEqDY$8mc^Fj`km>xu}5 zl$GO|9U=(YP>!Frh@jJva%{Fy1kN|hF>tL2tUi|G=#?V)WU~;bFB8Gt)(dfKCDqq! zAzmyO!R|o|@ylEhEX!JmO-e;Dt#Bbii3sEs3o&7;2okq1#Bq~E(EsE@Ts(owf3Ohu zjT1qm9}Dr8Mg+!=75GCTf+rm-u(4DGX96p*Ypw`(j;O#vS=4?>1?G+x!T6~aIBlc| z(wA4@$|MmCWEFTIj>L=ZB25teorLC3X=aCH|E*c@Dh*opLebrGI%7s1K5i|}51 z5v;eY#1Cz#e=e11)=~tS-7B$yvj_%6RibNS5wsmsiM|a)U{+9xed~(g{`^WDWG90C zn=3KJiu&~oo(MP#3aPeY1eJ>YWcP++?w{k&nW-;ElmJ632Eynwoa$%!j z2|hiS3lkeG!B?kqAs-+JEJfksT!;u;ia*P9 z!DZx9{5Cfi-f5QpKZdS4E~}=A(k&(3opvXO?(Xhxu*KKk6^u#6jv_RfyD@gVeFC5My2* zq&JHSA^H6vHP0`^V}(Q1IHwQ?%?{E1nT05rbck+DEd+uO5#<*`A^Q-W&o0EX{~e-Z z>4hlXd5HEU7oza&A=(^Y2)jFnXnAxYWZMqWf8he&??aRyT!_7@hbhUw5E(XyDcD=+ zkKEebIj#@}<%j9p$U?lWKTNNO7UFpO zVY+Wyh$$k)RB2g=@mj@HYFa4l&nc#jhJ~nhE2g=+g;*X}Oc|Pm@SRaifddPny0(}m zDHWojxR}i33$dMwNkO_0(GA7)O{@@xUB%SYUw~H05~})LfP?xaRNPyDv^gLIX=lx2gcDnWglrvH*1pN~z&e0hVtsr8DOW z;9OQpYfcxS|7Iy=94|n5ODQ>*7NGEFDH$9pz#!!#^kZ)U-dY}^`ke*XjU!aLwE!Vu zM`-@W0u0DILSbtQP`%^`4Ov-$qCH1QVrc<}UpPX~78cn4DD6!tK*N-yl$RjzTzQlbQ-FyFkCIYE z0X|h6rRLxQ?0tBYj{6tDzvC#)_AY>^*fDZ*FF=|0F;a6D#%1_1YC!>%J&w`wi3Q;J zV>Eqi0di*^BZrX%&|7zmsMcb8|it zGfq%&Q$C~@oFJ8kd>r3)g6baRBjEH2T5&HQ-*22C*IW76{^|sY*5qT-j}ugRH6O1O zPtx?td@Qs$Ny9GX!_4j^eK?zs+K`j9|5QHGa!yjjv3$rZK1s?Y`6%6Wl4=j+!{gjZ znzJV#?RQSnh#mP@+IEuOZ_bCspOdt6eLiYbPm$khftSrG5?h`R5yw+>Zc#pVN1US6 z`T3YoaEi3%*|K?w_K@%zR=0!zo&lnva+Lr)X4S zK4xf~rq-BzC=WSJYa;S-#N{+i2+4;-%xQY(pO0r#Pt$tud=#uYO%vS(-iJ=pTc>>N zy)4KhAEO_grm++Aai`-ny&98`c(F2CGC~+1?J^oXBp)k=m(gSEd>D9?(QNa4oQW?Z zL*sn7%q*kpdii*|wv5uW@{v_iM)GR;_)BGUQYjy68p_CDK3}+R%cw^xUx;TsLmR~e zUixQfRDT}oN1dU^zw!|8eTJrd&qH_88B+a{hq*;(==8@tC~Q1KzU_I~e)J4=w&lU{ z+8J8*Di7zLoguU5d9eR-hPWXQcV*5}vf4_TAX)3EeBd<;HMl}UNX z$v#i+ae4Ukzw`7cQn=oEo?=6V_A}?HJwTAZeVz(@^3c(Go_@RMA^q2R`k!+i-YH)o zIr}^$SzVwF6Z6o53#2tR57A*4XwQf|Jk7m8W<&B2wB!PnTIZo|_XQeko(GTf7wEK6 z9JW@8?2s$|aJ!lZ*K)F44l;TzuJoiGEk*BC-4u z6a&ljoi#X8=y7*r% zZfjML#jIS699BUar{-d}TLp>c=Rz{Bf^xEQkvqMDo~7oZVRZ$$B<5oB;R-q(lZ!)@ z6{Hi93;D+t!uMJ(3OXyO%TJIKyG)^8xtOGLnaDL4`-Wd83r7LZ<1($DoQsV3%k*_z zF7D2_OcA4UF?6jUH#8R;iZ7F?Z7#lDxlBtfauM?6GIbgYN=ne5SxFm3a}l_%l6v}baH^z|{D0;^fh+0c z*BoRtRFZsm4r)GCQhG-Yj3uv7_1hfG(Yr!MtvP5Md4-Bz(dMgK8O0UrPnjB&NeTCLt&4Fv<6?%U;2fMqj(Bz9b_$o=X@k|ap z^@-X~GiN@~CLC<=k6pgxHyBs&L2MNIqC za*(%y=~H43t{h<+ADaXDDyBsdIS7BsR2Q6s!`)0;{(^m}tCZlC13QDObksEmD@I?X z9)}z}@xDsqCkuGVS84vZ9Ap+IJe;{DGbfQ-y>Hkz((kQ)m7SJo`W?{uTqmy z4jQ_zlD=LJ45X_lUNZ;D232%GH3!E=SJ9gRIr!pTMdq?O7@J&0sS?8Y7gbU5zieFH zP(^QlXG8L66`A#B!@a7ClD=eP)zd24_c0rF-Br~5J{v01*GQ)=8$kxwD6}~nn?_%w z4bQR#zSrp9<7}uWUnA-IY=jhDBZoWL*u3Ey&92SH<0IGTOjR~itFBQ;Wi|qyUK7?+ zvazQ78bzGV#vQ5awDx2+WDKrT&5>+4kG@X74`pM%_jMY&FB_MWu2a&^Z1m2)PFuEQ zWB7*abZdP!GLKxRzE#;cboDw7UY3oQjn^sme*%wg0dH3JT1_J1+34eHvJJ|{u*PZ% z_02|7S2YRe9%74R4IOnBRB~3Wl%P* ztgE5zmf84NQbTN#4PCCGH~QJ|Xs97s?QG2WR6~Q+vT<0Vmi(2n@ldyxrpRUE--ue; zA}Qc{*3w0hY{4&3OV9pfVd2bL`qi6-<7;b4rzcC8=ho8rPgxM5S_*H^g7uSHn%l@GsW}Tp;y38bvn(9Yxj}W0vv7O(4eGd`h0pFcNa{`&G~;iOacveR&$vMotFn-| z<_3jSW?|{!83g={D;=`M? zXhs$yKHQ|ug;|&(a*K*{vam_>7F|fsLfMd8RGXBAdoH)=No*EAMBk#eh%87zEr`r@_m4)Atw<*>%3(AGJDa9ZQ=F4wWj&>F%?7K}<)Ux1r@ixs;%0g1z zZJH;Sh3Ri^(;~?%EbqHb%S5uUYv3JP^(PZ2ZSK(8-b}E=9a{e-6ZPSDXyeCBwC3HR z&F?euWyu}d@;VbDdxY|3CX~(#<pd zE~V|tL`lnCir<=vQ$Oxf_=ZeeP`oG1BQrtf_sDfwCaNdhqe=hE#OeWJM*6K zp320N1@}mIY9^Yt-6N&EOf;XmM`D?ocwKvsz9(nm?aO=gJ}wjO-|h)(3b|?z&Hkof+6ISx;ZzW?++Ez3^S1 zffXa`>GJao%=fIPJq;O{mQYXgA7mhNW<4d|%|PthdUCpvfxzN=GP{-mmn-!oaU}!e z9@o>Giy5%#tf%W|GN32+fcBrrzyR$BG_N!R{X-v6%)tzFxjvxrdos`*^MEwAXW-t{ z2lQoQ1}axRpu1}_aP+_fDp{U^ZRHPW!J-T-u75z0^DJ^n3Mr`l}98#HUmSf9?|3B85oF1ba+q(euO-tsg@ad zp8bfNO)|j$dqk@G891=x5w&UxJj))@N!1Lb-F!qv0|cB`kH}pn1J=EdNKHHgaswXI ztH0^!Fnvr%f2QNsgvT`XYdT5;9+O>Hy5MhlOwu3Hkv#7)-ET{WCCNktd@B~Gpf^(Zuo>IaXK8vJRy;abm;m#q3h?; z@iplQEjg8ryR)B=$I)~gTK|OP4yU82^aZv4d2dd~-;Ym7VO=^N zi8s)l73nC^X`mI01^M9(*?iciOc2Mv@Fl@7V~1~LszM^k?TJ@-$?5%oseFY-NuA7bn zzZ$7jBOO`FPbpF*9iuFtl7d1y`X)c6D^lsG4t`2GqUl(f^_2Ac(h#`tDc$W&gVy$^ zRP-fHxUZj*^~W?EtbIz2?}THsUp}Qpt!Wta?I{g^k%n%$XY{fm4QGs>(Xt0=m^SVi zjl7$Nv3}2}xi$?yQ=ZY%sx*|(c}Bx3(=cn}GkSI*4dahKqXlJY_;vLeSszcs#l~k; zUz~>NUC(Ix{xpn~Y$Cl~Y51bsL{(eTaAHIgrLIpyrbiRWtxAJ=d=s5ql7^P)O%$*o z4Lesi(bu9hgdA$3&C}DMbh(Mf7Np_kgC=^Km4^B4O*At#4debbkyb()KC3^ci&1GP z8T6b&LemiA^qju>rwQZyoYs2@dil?3h-(`DTl$=C+oxgpp68T0F%56eJtxsIY1nq> zIqe#j2Cvu8X^d?e{{DPU_2y|frSyU_jM5Nq@q$Ek)1Wf>1#MSPLsifV8m^p%{LB}0 zLoN-53tmvHWE$$WzM!xFQZeV`3tIL&71lK`NdJ2(8lJzPvhGwY?0G>h9jO>1`;r>p zq~e+3OUiteibZ2yQr|P7-sdH)ew>P@NiWIZekvBsen}^9rNUCc-c`2+nq~b>BOPYQ%71?6VBz`0ns@l!8_FyV54s9mgJ*mR}<7O(}mWqGT z%`|LdDh^C(ri#_6a9Pnz&dXBqeqS@)TbPRF7n>>MKfzvIGrgRVira6RDY-BenSYw8 zGdmS>s;{UZEfq(sUeS+)RJh?4&52IM+mKfz5+?L7`xPw;NQL45UXiqSDlTt-MJrrW z5qA0&DLAB}r}h=CnV5>zFJF<;m{eGPdqwMprJ_o%g_Lbm5oz2)Yt03@u`Q%%l!_I; zEwoxE6(%VyB&VJ#m zH3ehDTPeFM1-G1}%oqKCCoY+H)(d~T(NmnoPR(@MTiQ=mMxm1-WQVE>9%ns_e- z!}hmQ*^Lxjz1T{Y*HYkH*Gju8Q}FUlD=A-05yqpH7L}z4e&E+a{8$PWS-qyrVgU!Q z>BYVj>=?DtsEibR9@9qql2S0ur;X%eQ}8>fO^EXq_|I;m*1!~q zt#2bQpA;-9X`^#)DUhKy(sxY3%ExWAcv1=!I@{>em=vrQeM7;+g>lk)Llw3uSTp1e z8Cj%YfXf?NVw8eaQE#YICk1kaZ^%zQ1##<_C zOvasgZ|UiSWa0V$mPX%AM)~o#w4pW`L$AN3uB*v7^z1EpUQUMg=eKnDd@|NZy`z7p zk|C!5jv|gGW7^1fbmmYp-g~?w`Mt@AjDJT-+XdX|@96TzWK3H9j#Sqq{X0_oFByN{3H39Qk@5E(Q9&{q2finj>|{9Gyr-1ZWR%&zr;G7|Uf6q* zi%Q0_oc9zJl8mqadr!yxk`c4xJ^l4a#*NeO$;UYv!*9H&U3SUX{_;I_j!TB`8*Pe+M1kmV^bV9n`rY3D4$qkj?5O z4BOa2X-ku^^hgICUXX;B+(EC4k}$HNgAAr8VcEwHipWpG3$aexoGHj_chddjBrF=* zNwRTCXmIHyr-&q2MR!tBP!eVrcG5YYB-~lnNgv$=K6^XK)G-O!=Q}BKQW7rT>7;dI zk|6iGlWK+~A^c}2{jo{HVa1O$)I14a%|23+VG=O$BW=-6!peY;LR_q1C+#Ek4M>9V z+>bOwCJ9-aK2n@m63!p}NNf8N(SP-$uzxBMZjB$Q`*R}Je)>oTor!1=|3p4-6QQs3 ziHcq&B5BwsDt(rSBd(w5$)iMcMSmjExjwPb%=O?l{oCqsPi5S$_Mf)-nk@l&Jt|cd8 zzj!yjiA}_F?QW8cNQBz3Zn6kUgtu!qx%nhwQFJ$@x+S8ru$z`RB%)_oHyxUo2&=u_ zbZvAZV$XL|%g{t@ywgp8trKyhwVQOz67lCpH;pz(#1O^L6rh!e1hdbStt!Y(_)JR_ z5>ey-nf6H~qBr$3m5U?_TkAg4!`}%A-T0Y0z9nGsk_(D{kfXPe0 zQ2p5ir0)JgttS$MePmy#rzAnhllFzg4k9!i^;facjfG_^1RBI|o-UUq_z|E`Btq$a@WN{`?l zOF;6Y9@-n3fJGmAs5CeMhyL|YnQsEFseh#k_XM=sex)kM1oS(6rCXB{pcnp?>c=Et zT<%wD7?yzGMPKQ;O#i1gtpymEIZ%IJIBtgH{6Q#aH^Int;Zhuk=|V0iR{Q z3G3qtkT(2A-$W8%IQkoX{~eFfUf-zqTRglHgt99h2{VMUJs#6n3+=DtvEra0{~{iH z$_4#~c$D4$M&0%Cxc>GVeY_oyCx5=thw6B|SNTqFDIPy9zf;Slc*xj&r{`zlg}gc6 z>B;eUSY&>u`^AF2`QPd0zIY+8*>|ei5fA_4->H04Jfg3Cr_*cVk^b~Ml`Mz$7AELUSU2Rk6o_4G$k`0hoXBaH8~!~3wtRtHXdh}^^$jZ zJSz6|l3idtuAb|qVczkmz1>U3uJO3j(o3rL@wngHOJWn^@krqZeHj^#29qDuGB_Sj z$NixDmhouv{Xvz+@pzH^gO2J7cxN0E-G9-N&2b2g{Y7bOC1t zzv+`#95$r4i=AolZ0g)ls^0x z;=Ee^Fde<(&V4#(~P&`22pH}nrli^X9^_8(y%TP&g${-KlK zV}WgdXhC-@Oiuox;198oto}n5ZLxU&><|5T5sO>hf9PgIERIU{(YE?ntkCVF^xLt> z7~V%?t7GBr)<=>Q3(J^3dUR3HpVCMB%VP0*Ss&#div{oLqX~y&vGZIXN$rir^xJ*( za9b<_TKZ`BhFIA4_EFlZSV$=RrQu6r@zVG&{hk+#3uFJ%^;xl4?emvbPKiZI(q9V7 ziN(ZOe@Q1T7AkB1QcHX+-W~c&#gVbNT=AE(gJZF_Ucm8x2esU6zh2F=068#&4cF})Cy)ihW`HzY|$Kb!g|7dJS3|yW5(bu*Z zC`J6EQ!ir#|II(jXpF($MgPd`K@8G%{G*q*V=(yiKiXOygReFJ$d6)h>G?mBz9is$ z`A1w9BfKv}c>1vzEL0TX!G~jztS!QAdt%^XCc@jc#lT{y2>Wb^fz$*M7F`vCcg`Yw zesK(H{X{rpUW~9`NrZK0#b9xY2-g(~`uQR}FFOWKMIt;rH3r5@M7T9B2LINH@cM`t zyxb|m4nZ-fC>G(*-Z9u(Cc=AMV=%Q+guU%!5O70;e~%Y-K)0r!aTQKJ~__$$I8Ix(0gBg+2<#=vi&C?6RRBlwX;IZ!$V;?|=4MMvC&m z-_ba4C(2&mqOrz9lzTo!BQ02zx4n;s;J{(K)@W#Eit?MLXmm{#<>il~Q8Q1J2iHYo z*9uX7a3dO1HjDDqs%UuZ6J^cI(J(wF%H`*xg?Kzsjyf5Q+gC-ouOu3K?}+m5{n41( zAj*?>M#H^TlwWR&7Jg4rp0g$zpL<1FXIV6^i;D531<}}|AjY9Z(a6vgX~93KQS7c{wKyiMnxlOjTo;P5{(ht#n{{`8ls29__A>{>Q9PsfNr$#eh}k#YSGB5 z7US89(HMVUj1^^~A=MQ5B*b_@95qLBStjKjO4Fji8WJKje@Tv?oF zw??5(N1WxKM`63UIPZ8Ih2&x4Y+VLUK)iv zW#W8ceiYVMinHD9D1_Y*=h`U(&O>qb$%#VS3&Bom6iVNVb7XuJa(cwMB_awV{)%%- zP!xKlCAh;o3Kgmnoa-7T|>6FW4C=!9PYs;l^YMo;4^6%iSgTw|SHh zpCrLWhEW(0E5U!Xgnp+B*Q!xiJ4I-hkAnYPL0&QnD$51^{zyF7D8bWyMq>RQ3GVq4 z3I8J!oYxr%rE?P8`6d!|B*AITkyw38f?qdA!t1dFM?Z*!>?;XwxE+bw4-)KO9f?KX zB>2{qNI3kHV26v5_$w>P<)<35|t|?d1zuJ zrf!zxeNmAZv`>;%LL%|zs3b4&jl{0=lKj~%5u%Oo|$r_fCc>P_H7aB!ktB4eLX-C3aUWy|IMnXhGimMeOao$LZhe$;t!&Zv7 z{fmI!7~z=FUlF)(FU6TX5m@LY#Sc3pFgjF!{ijz-AAoqe4-#8KhgDNSuJ{W;} zccggbt_T!0Nb$$b5wK~MVxP4Uc-kq&CzeHENv{+SSQvqkqSBmQ6oD3bX}&Wx0;@Ho z**Z4@6O5&KX<7u{*-G=9_y}wmBhB`a5t!^C&AWmk(C#J8KfNQcF;tp^Tq9tYAk8Ns z)MrVv%y>b5x-=(@h`_`J(p+I1A?*K@W>s?me~UC{8bn~serdj@8G+_w(yXN-@VOw( zd2$gLQYFnb;t_aqN1Ap1hGR~HP~RI4lU8ZI-W`rxozkrFAsl(V0?zAjsENvO<@0cq z%geChlW@dp$Z&jJIK+)*xa>waN^E6VtSTH{V`Mn6A{^cJGQ9t6I5v36@aN;(v45Woht3Fx z!!a4&mmiMS^D^9#5sn2{Wq4##IE?Pd@SNyy@DmxX4iR{@$gqN6IR19XaFBaAc7B)P z?GE7>CnC!&6T;CTC(Gue!ZAf%mNN&3L)l1{Pg#WHxQ#4-H4KOQXjvYk9ga7UC-jOz>C9a^tozjFOdOT9AEk` z3`<7Jarg8v=-A1zMSd7gxXW>LMi?A|Qq$%5PjDE17RvEZ-!QEB zPmUAa!l1iMjyKzf;rIqQzA-)wlXuJUuMuImS0cwYg9LkLwn@KBCBmBX;}g&b?kg~9s0z)w637r)5yw7yWd^vUtT@1b}oCC~S}LJ_AT&wt*B z;-juSTegN`mW4bAHibfRxIF*&C=}}^%5%xxQ0TeJbA3%HO8n*d7ljJ(`0{LWDHN3{ z^6Xg_3fFvjE<75F`q}cl{a`2}7Rxj53dQTS^89vlD6)3Qv)tNHd^;r1LzjhO&MA2g zUJwfL3VEJ6I}|Ic<$33nP^jLQ7aaPb*!E1GTT(({_(q<^;zDt_OP)=`Lt*<%o}B|i zaavq~lRZN*T2X-)IfbG^OMwqg3Wc4i0$&>)ife-vxMhgIYn%f2TZZD6qXO$1hr-)O zfye2D;(nL{2M-KIK%xTYD}>@vwgRt|3`NKc1wPy#f`$bO%s)a9wn~AYeGWn676tD4 z5Q6ai3M|(af~Ut6*yM%KenEjJJQ3QjDsVtu2tw~DaN3O!Jbt3U|6L71V2c88EDu3_ zhXR+L34!l-Ap+xA2=4q-;QB)$aF-jvZM#EIqc(thw}imKaDec<55X1d0j#q;1mi{x z;6V#RaMo@BPc90<5RU=uGc`oWS3iJbazbDlJAkuOL$Eu202jrDKx4`PULGETwf_y^ ztpOpBSvG(Vd4^!Yh5=mW6oOy72Jn?hAt)#rz&A&SpuKDWKOPc-xXJZc<pj9`iUD-p-0V;a)Jz24i@HBHME?4kRhE z)1_dj{C7nj8X61}5hb?q z3&t8bB{p*p#&0zx)^`x>87i^ngkaQLE3wkZU`!mP#4>||aoA3Y|Ct3t$wP^I^@A}h zNQpmb1mks#61OP@!z*2hpUDWk3YEA{G#GmSDe?8+L0Gg@i7$Q)!pHSWeDq@wf_5qK z?zch0JX(p@H3z}COoG7;n!YeK0hi5VMmpD$KW8GKc~#|ErKwRl{v*Q2>G{^*+VM` z_Z}(pV3isS*K>~kkRn9RFMBqqOhCv_>PF7_VO`*STs>1Ke)r zd`>118=_Ttk!T=Zr>b)B?*I%dP-U~P0hm{$%3nJJaBs0HSG@^^0L*!<%AXDf z;KoN)zPKv@DnC?t-sS*Ai4J7DkQ?U(V64$V-ZN9+VKb0Z3Ix4T z1KB1s07}9y{y8xKp&kSId{h8-2My#|!2x&^Gmt0y1i&VJAd9#LAir=RU$+aug*gLx z$=Cq=Su&8_h6TWW{Xmwr4#47_1NpXb0B#)~$SZULFyQn+_8b@h{|cd9Apjez2l7pc z05sGI`hWeQ{cIpR_xdBMZ6J$v`(xLqflTlH(fnf|7q$4qP)v=-KJ!PMf*SWc@W(z4 zH9m3MA1y{|oOWGkw^d`~N`J(TR^z5~{zCk=8gD$|j~5{aX!onSQ<-|LU?ST(NL z>W|IoYFx0+9}f%F*mAi)l>SrWmka#iwN#Ba%=X99^=j-k#UIyqs&QYIKl%@=@u_5g zj6bc$NiqJITA{}3q5e2ot;RQf{n1{h#Y)0*Zt7F zPMy6g1-YH-{Oz0{f)A_n&J%uEa!Q>Yiv_%Lb#C9|hY#1)dG%I5XxFLp$aQ}3e5%fk z%lrgClRD2?;D@6h)!A^iAD;E9^YubM$cSoiN|qnS%4@JpvL8~^HTX!hA2u3luvds5 zs;o7*)5i~8BQdjG}sn?aC6t-J7fKXTT+8FhWTM{w4iV8C*+6L;KRm#=*`z) zCmn%rkp{m~^@G=94W1+KhiPjySW`lf->$)D`+RZppa%PV_r;eJ8r=TL7uuIJc)>eg zI9$_U-B-TIxGTst`eJ>927A~0;!=wSzq#p)<_--ms`3@~X=t!&g)eOXX$bFgU--*v zvfVLXOdqJpj}H1`r@khq@A3s(YI5HuU$hO^LnCjZs<75q?|yj;Tn$?51f6p_;aNXV#2g|+Ib($NYLWnCw#CrON-|g`=E517K`om!PR+M zykx5no-WrC<~Kg*-l)YZm-#?yj}{MD-~;_qEnYLr2P4mDu~MNAJSw$#U8WCWYqeN8 z$p=&FwRmlm50*7)v0|_fcE8c$Ro*@*>(XL57avsr)Z%561$;4WmK@`QP6cgVFvLg5 z>&EGTyJEOHZS6Sc>ZElzGL5PPoCyM$YB}ki}|MJGP7;O&f z@y4PwZNAgtjZFpG?9}FsgGJh0@!T6_i?w;!V{hJ8HtZFX7bjUgS{d|{b4#(mRf zs|DV0?APXPv%KLgqr)#(V&H%eFN z@MhO)9Ubu8dhlhUg!sSXG-txft3k&slz`nd!bfLm!r-JrGhT=aiLyAmrV`}az?tm zXt$teqs#9$3pk^6*=>!0Yp2VlO9VUax-2_Sup6k$=`#c#(Ykyy&kN^Mb=flA3uXDb zyg1$qCuZw%TeugFEYf9%052R`qsx0dys&4RF8_A$!uA8Y96G@Z8;|SqnGs%CeL6QO;&Jmv7UT zPi)+&$7g4I;(v$rSZsK{fGkfWmFw}|Bu@lg*W*u70Gr^oaD8@c_kd=iJ}+zWfJnAJ-+StT z57YEn^??T-%+u$vTOKH1uFpHGJg|SGKEEpWz_Q)?Y;wi}c_sRseAGk8JEPCV2RtzG zvOc%(@PKiRK3i|}fYg0`&Rpq%&Zqi(^nV_>|5~3riac=kqtHIp16zCbIX&A0MIr`V zoa})ZIRkzZ?E!l=12zuvfQf+t$NG3c!peYmxOm{*a070b?138-4OnH22TEKF*n5b; z$IpP5Sa={k!ho+Dc)%^mfPZUvz#_+hM=E(ha)tqCNqeAez5yTn=Z>ls2Hf<+9eXzk zIG^1yXO989x4R>v)PU!F={4k)4Q|*WV#KHG z+=Ms_BYs@#hH+{}!g_)mqzsH$@1h$XTN*J=xncisBTg)FL*7IqUbNQ@6J3nBc&i&^ z{EYaycSvQ#dGvd3VZulT$%x`|V;)JR(_kD3ifu1oB>~O_s z3uCr4$_5Zm-;;=EB7rElvNn;*8 z#TD}}8M8~4E9|Zrb8wO?{@gL<#3)x>dScA^L9Uqk%9!VRxnkG{V_xaxijO_UyltW@ zO8SiX&`4J#N}2F!TUY2QoA6~*S2SvyaILN@)|r}c{XkcE4mRN?c~^*yHQ_dKS6sF? z;g5e@FvZh^zkPKP&S^8@zD^h6yV!)q-?(6VnhDFjaDjh;39CGIfmD$RYu;3rv3rWwHw%iJ9`aXcsI}Fy*nqE*Pm{ z%A>tqgghgrJkr?(8>~%v_#_uNj5OsTqg>EE$y8WpbHQ#`Q?@X3ftSB2o9MaVXM`#1 ztGVECk|}E{xF8_MlvN~L@OQc?%lA2>biOG|d~-(d3RC{u>5Tr3ru@Cl8Ao=T@~7v{ zf}hru-#l_g-)U2Re#aTb6{h^)x-5R?aOnLQ2XH4uj<@qa}(JF1mh5vKLQWY~!E^@{oT{8}y;*1AoX6%;bjA=v6 zcx;k0bjF#nWt20nIGC|!kTc@F%vj3H8R8*k{M}LD5o^Y66P)3mZpIHrIHRM$jLF6s zD~rtdn2CV9*o?R8IOFabGyb2dGjg_>3G3I+P&i=5kz&p`e$0%We>=hRycrMaal!`@ z>~uI`=}j{hdF=%Ahi3fYnUk=dB;Y@ALfl(3F2Ci3zAiJ~SLK9lKh1b)xf4c-nR8B= z6Yk5KbI=hdWU8CP8gYJ&H?dGxRYhhBf_1KIL(|@{hjc0t~q~obHbWs=KK&&Fxz0x zWn-OCzSEr74RwO=VRO#4bVA!nbM`iL!i-DiY^~`8`D^AZrR0P?cg*>7jyP|=ZIN<1ifZQ$VpnTSc4;WDq8UKdycTxvfy(yj<{@W z!K@cEP2xbF&>tDpB>N=Xvy0yIv_FHlH*S~;BAT}Ta`Em_4dn~zrn$TWq$(wT=@V?BFBT^iYa@msgV;u0N+LBv? z9gt9G$%nih(A;Rrsm>0FY8C8Ea=_CLOYRuyfZ%VIe9YDX^?xln+tdMG(pEf3*8#Q4 zR{T-b0rompd`!+kICsU0GsPT)ymeM={o5WV##r(DFZQsox8g$|?6JqgiW6Gxp%G-o z2G8uVCfbUd>g^$!YQ>vx+G9?h75iVcN6$ zkR4&e4NAbhL>rzd4GhV)VcmarSToIrD|_vP{V_Hi+hqrzWj5UZ)(*$l+wk6(c97p` z!+2tcj6*iueAf;)PT25&)pjtyDCk$(Vc}I9Ett!0oo-Tg&ZG^3#Ts7uZ2e%$EPnv_q7Ev|ORakAwhc6O-tw&j}9cF+yA<>i~6)@v2!{>KoJn>E(Hk%1O!1qBt0Oau7SF`7AuI|zSi3EUVprw zeT8A>H}yQ<=f2OmuH)FNb@M*+j?37s-F)Mc<8tIX-Mnn|ae4C9Zr=6T<8u1*-F*2g z$K{=L^Srl@%WY3~^KV;^%dd}h^O;}r@n(1P{XZU;1E+TLXMY}-+2gyp<1Q^zIJ}$h z-K%BR4d~|A4{Dindw26;|7@8}HQij+vSn_$qnlS0wagFKck|9}nY*s&<_k`5ncXhz z<_9lmnXzYd^QTv|WNzQh?QU$DM~b_-cUjA{Y17Rc>RV=ci*DYtZ_6Ctyqhl_+%nG} z(9P4ww9I*X@H!^9%$qxP!{ggBSN+-5^^dj82S0Z8nkV_VUv>44>ssck54-w|7h0xr zQ&*3Cy=8v26TAA+X06g_WLJNE6#qT2t6R6>@9*mBicYQ4udb^Xo!Bbdmv#03oz*IL z-`Ld!-CO04EBX6tTBYYjUA^FzR{7tVUHw&Mt5l!Z)yLl1D&KVK>RbA^%I$5tdgicJ z`RM4b-a5WjN)GGlX46{boddh_Jklx`?%CDjA8(Zxckb#}SGLN@e|6!y-zuwr>f)1M zZk58XyZEj*TjkM@x_J4PR_wRB`2Rj@l}WF6@iE`G${sIv@pZrRx}Wai`x~{+uPeIv z)h4aEUw82?2e!`EIbGcCu-555y^Cv(X`SaMcJbVHt7jN#;ItvDN@xG_DPV>9E z__T9dXH;Dm_qwz-pKlj9=B-nGV;66|t#v-QvWxetX`Kr$>f%#-x6ZmVyST@_ty6F! z?{7rwOzqUg?@nx;#%;T}@r>5#d2| zoxAwwjjc28&(1#b?bg}$V`pEqwRLX$s{ z3)19;&Tg}30sG<3zOrdS-do<;1OHKwlNWXNqGJm(?~%@aw|znOn%3Dnb}LBzgwAex zYC$#)@9gg973BDPJG;+i1)15qvu9mbkX>s#`=#3pQhG;c|4>tqSFZ2ugZdPt?G>Hv zfdv_RL1*7IvLHX5-q}MY737lRJA2`bf;`!=vtOTAkOK=k`{yMEX*jC04_;G{H=A{K zw`U7dw0~z``$|E^?cUk_-Y&@ZJ9hTWtpz#n_fFpMMM36&-^ri+P>|ie=;WRMEXYk; zJNc-c+hpC_oqXz^ZPM)3PQIyWn>0Mv$pik;CjWk_lOH;^O-X`OFcJjcQHu7a2x%s>{`Mhf)-SGe=hc?zqiSA z-xT9BYMTQ-DfXUww9QTL75nf5+h)ld#V$ImZMJ`@*ry-UHs`G`_7&~gX3EN9-_fOQ zK6|{_eNJwh!nwud3frdd^kPrFq-|cDSnLHQyuXpfUUO?(?!(1?sj6)r?NjVccec%s zwZ;Ctf7^5`E%yJ0wavgAirr{J+ibj|*n3ao-(6VDe6ww?KBL&jJl-}lkLPu)Y@07S z7W?@1ZPTWp*k`@eHuXmp)Aw(iRn3ZBvbk-x?N{tuKW&?nb}x3-|FzA1I~M!SU)$z| z-#WVA4(-z9`;H#cxLwZwyrW0&*Dhn;@90U*+U51PI(q6+?Xur19X+d{UAjNp(esMi zW&E0scvRcvKTA7$>6!ff{El9JQM+99a7VAcsvY;Cj$V6HySy^Gqt}=7{s(vThK6=I zvu{T~*SB5nYv_oVuwB-dck~Nm+U2jCI{L-Q?b7+`j(%xoyVPCG|1M~kg=g{S%i87h z6M4I|%Rf8w@1Ad$tJ?B@UTc?eNArH)ZI_pu^Km|GmqrKjaldMpu6yu0erlJRop@b; zwaeT;I(X?W?X%^F4qmud`|ST^2hTgGea`%#gJ&JyK6k&h9^l-k^PE_2}T^N3_p>Dmu7mV*50@rGt-|-ahTF>ELE_+vnQu9lY1#_8D<@ z2k*G5eO8^+!T(#|KA&~&;Ll#-{kH4icmLBq#~;(dFK%w1(!)A<^{4GK@xTsV@PF;I zZjTOr@YnYFa;FX+wnJg||Fg)w8W%=C7Wwx53UkYsMZTQd3iCswBJ+RY|2KaY{?5Ejcw6&txE>Xn_YvNgd7t5Zn~xDbmid_B zW1H6yUW<86;kB997+$M+&Ed71&mnv+=5q?4oB15W=W0IZ@VT3>LHJs*mn#Zi8}l^^ zUn}!93tv0)H4I-%^EC}$Tk|yzUu*L<4_|xpJqX_m^F0aQ8}mI1-z)Py3*S5QJq+JV z^F0mUTk|~*-)r+d58r$9GZ20j%+Eyl*)TsN;b+DC%!HpE^D`8Fmdwvo_}MZ)W8r7b z{LF=)J@YddeiqHoWcb-MKcnGi)%?tcpIv%^9m3DD`I!zs+vaCH{H&Xw`S7!Eeh0$u zg87{YzZ>RvB>b+J-|ow-JZYn8cXg=?3&hJ|aHxu%6{o4Lk? zYn{2~g=?R=28L^)xh95dqq#F=v!;RxxLmaCR|g zm~fUcXPR)f;d;dD`Ln>BdBWMpoPokw$efA7*~pxc!dc0jnZnu0oT11g6__(sI9r)B zRyb>!Ggml!nKM{8iS~#njGg~;jnKN8C%b7D>INO;sUO4NSGhaCSnKNKG z3z{=wI2)QXVmK?BGh;YAnlofLOPVufI9r-CW;kn_GiNw^nlorPi<&cOIGdU?YB;N! zGix}znlo%T%bGK7INO>tZaC}Wt>*LC*xH*_@ff+1Z?-!&%y# zsl(aYoUxfZv^Hn%aP~H5@NgD4XYz11H)r&4RySw%aCSFm_;8jtXZmoqH)s5C);DMV zaP~LP0O47{JQIXx1M`d!o)ye9LwI&D&k*5R!aP%iXAAR;5uP>7Ge>y#FwY?2S;Rb( zgl7};j1rzz%ri@PcH!L6B|OWRXPWSA1HYzgc-Aq`JmJ~LJOhPiA@fWWo{h{iQg~J} z&rIRj$vi`aXDRbc#ksYWdBzIQTI9RBhG#GH3>Kcn%rjYdHskZ{8lKh6Gh29eGtY40 zS#&z#}e(>#NQXHoM^8lFwfGirENHP5W!+0{J5hG$vxOdFnU%`%FL+3tjf%+!tBb-u)-|M%(TL6 z%gngKtjo;2!tBe;z``ud%*4WM%*@Ebtjx^J!tBh<(84UuEAMcat(h5Hn6<%$b(p=G z8C;mfnVDRe&ADv6!>rEC?85BM%<#f2&&>3~Y|qU2!mN)pmBZ}M%mBkI&?{eYm<_U5 zBP!l-3^{R!*`b*shFPMSDTdjinK6c0qnSB|*`t|3hFPSUNru^^nNfyWB|OjL!|c+` zFvBd<%rwJn)66)-tkcXq!|c<{K*KE5%tXU%)XYf3tkld*!|c?|P{Si#Id*Fq=0s`Y@|EGy5>RH#7V&%QrK9o^xB68Go4d zo0)%@{hJ*?*aeuKK-dkK9YNR?n4Lk`9he^qLf9>s9YfePn4Lq|J(wLt*hQF~ zMA%K39Yxqxn4JaJ{iDndBkVHFP9y9#%#I`MI?T?4eDzUg2NHH6W+xJMBW6bub|r8m zP7J#fvqK5H6thzayA`uz3A+|}@F#}di`l`1U5weugx!qU(S%)%+1Z5MjoIPQ%R0*J zbi!`O?0CYi$LxHnH^Zzg_)gL z*o~PTS=g1ComtqOnH^f#rJ0>t*sYlzTiCUkom<$wnH^l%#hIO4*v)ajJ}K<#%+4%;lbBFzg1+jxg*B&CW3F4$TfR>=MmRG3*x2 zjxp>S&CW6G9?cFi>>|xhGVCVJjxy{j&CW9HF3k=z>@v+xGwe3ajx+2!&CWCIKFtm^ z>_W{>H0(yrj+Fh*5oTu^cBf{C8g{AfJM`qRTQxh@uxm9t*RXpvJJ_&`H9Og`n>9Py zu&XsY+pxPeJKV6#H9Os~+ci7hu~~NJK(SjHap?48#X)Quq!q@ud$Of23H- zgsh0kjD+ln$&iFBiOH0NY>CO3gsh3loP_L&$)K=TJIrKKLN>)@R64GCCovV=_A-yJIpuAeV=_M>`(rXdAq!+O zK_MGtGD5lHo#rMpl)P7P4(7;})`RCi51uZzcm5vT!C77qW3CBNwuACNmeZ zb0$L7qWFGV;8b^CUY0EcP4`uvUnzw7qWRKqZhJzCbJi^dnUsdvV11f7qWdO z;}^1iCi54ve$I z%xTD;nha{lqMA%<$flZ%YRIaZ%xcK4nha~mvYJe5$hMk{Ysk8q%xlQLnhb2n!jexo zD`aC$MmA(+O=dP^XSqI{6|%G@Qya3iCSx12wkC5MvbQFK8?v}2lN++RCZij&x+b$5 zvb!e38?wA6(;KqACgU5jz9#bBZ!-5Gdv7xMA&XDn z{G5=@HyQnq)i;@a=9^7ThCgKaO{PC&`%T6_Wc^L%KV<(+2Ox9-OeY|8158ICbOlUj zAan;zhahwbOs61p3rxo#bPY`BAaoB*2O)G3OeZ096HG@TbQMfzA#@i^haq$sOs64q z8%)O`bRA6RA#@*12O@MKOeZ3ABTPpkbR|q@B6KHAhaz+-Os67rD@?~CbS+HhB6KfI z2P1SbOeZ6BGfYP#bTv$8BXl=Rha+@3Os6AsJ50wTbUjSxBXmDZ2PAYsOeZ9CLrg~` zbVW>OBy>kiha_}KI9KrRwjE$PCZTKMUhB>c-4oM6$@2FPFrAdpO)(vn&{Z*=mC#)= z9hT5#F`bssZ805}&~-7Lm(YEI8-8Bs!kA7BdxHZ^M<#S-OlKx^XH17CbZJbdCUk2| z$0l@bOy?$aZ%hX#ba6~4CvoAqrh0(0pH}mg!`LZkFk2g|3$AY=!QYd!BZF=yI7(SLk+`j#ub< zna)?}ewhwf=z^I}7<;+>Oh+tq#Y|@`bjM7GEOg0Crz~{KOvfyA%}nPkbk9r&Ep*XL zCoOc-Oh+wr)l6qCbk{hCpC7txrqdR>ZKmTEx^AZP7P@by0~fk*rV|&sai${|x^kv7 z7rJw%Ll?Sqrc)QXb*5t%x^|{>7rJ+*gBQAZrjr-Cd8VTmx_YLw7rJ|V>@Q`12WT~t$m3*A)HQ4L*H(^(DORnuV&T~^a+Wj?yM>9~fjtLeOk?yKp* zhAyn>#D;FH>BxqzEZ#g`&-r_s4sGbtnoe!#)|!rO=-QgjZRp;b4sPh;noe%$=9-Rf z=<1rzZs_is4sYo4noe)%_L`0_x!1i+=QnhJO$Ru1f$3FW6dI+bBOJQIrZXJ6!=^(V zy2Pea9JhbeKbz*>svix7kyB zT@<>`rt=)S&!z(%y3nQ*9lFuvPc8~wY15ew-D%UI4qa-~sSe$0)3FX+Yty+7-D}gq z4qa^1$>viuD0oHhwirNaEC589v|Lr%AWKdFA806)A7a)$y6L3TtKO5j{l%fHZaV9s zyKXw{q04SM?V;OlI_{zCZaVLw`))e$p$l(1@u3@UI`W|_Z#wg#J8wGlp-XQ%^`TpD zI`*M!Z#ws(dv7}Up^I-i`JtPS7wO{A)i<5}(A_s3{?O$ok92Y9_M47>==z(^f9U=j z20&l|7$!hq0~kg?UgU=6_i>K@nwhC#qQsfl3{1U7+T z6a-d*VHN~-fngYs-)Ul)27zs07zcrMV3-GieP9>}frVh02!V}Y7zu%uV3-MkonROW zfu&%W3W2R)7z=^5V3-SmyD+0U1Ff0Pg!Z0lY+k!sYC4qHem=}S4VHg;Jg<+T&fsJ7p z8G)5ym>GecVHg^LrD2#FfvsT}8-cZ9m>Yq;VHg~N#bKBnfz4qU9f8$hm>q%LVHh5P z+@tVHhBR1!9;Wfem69A%PWQm?423Vi+QUC1RK&fi1#3;gY}_ zG0c&`9x)7(z#=hBlE5Z0jFP}AG0c*{E-?&~z%nsRlfX7HjFZ4RG0c;|J~0fGz(O%h zl)y$YjFiAiG0c>}PB9FXz)~?xmB3bE&UR^Ftr+G?V6PYkOJK1WCQD$m7)DEAwHRhg zV7C~C3w@)%8Kz5MyBNj`oV33g=1X9|7zRvW!5Ah?V8a+jOkl+rW=vqm7=}z>$rz?g zV9OZBOkm9z=1gGE7zRyX(HJI8VAB{zO<>g+W=&w%uphpZ=I?HXX%pBshH(>EH->o= z*f)lO6IeKgi4)j3?A0y}tQ^D43G5uh&46`S&dkn)TuzU>DC$N1C<0r6w4D%73}Yy;h75Bku!jtTD6oi}0ha|fkzo`CR*_*A1$Gf0gv$cU$S{op z+sH7E0_(^yj{^J1FpvTZ$uN-u8_6(|0xQWdlL9-*Fq8sI$uN}yTgfn%0&B@Im*6q& zVi-(;#blUFfz1Su>9W9TGR&sHZZZs~z;a@KeR*Iz8OBp!JsIXxU_TiKRA50FCRAWU z8AeoKMHyyPU`H8-RA5ONrc_`{8OBs#O&R7?U{4taRbWvWCRJcl8AerLRT*YgU{@K2 zRbW{erd42D8OBv$T^Z(8U|$&qR$yTnCRSi$8AeuMWf^8xU}qVIR$yrvrdD8U8OBy% zZ5ifPU~d@)S731&CRbo{8AexNbs1(?V0RgYS73P=rdMEl8O9f1|D6r z3==G{!3-lTu)+*8EU?22LoBew3{xzy#SCLCu*M8?EU?E6gDkMf43jLd$;h8v5m;sH zeXa=XGMAiiMPQj3rdeQ{8OB*)of+m?V4oQVT413WCR$*l8Ae)Qr5R>gV5b>|8h!Jf z3{x$z)eK`Tu+|K7EwIms7g%wI85h`bh9MVNa)v1v*m8z37g%$KITzS-hCvrtbZ|Vc z2y8m{-08}|sx!>Gz^*e4yTGzDOuN9gbFb!C2G*Tn-UarZVc-Q8o?+qzHlAVR1y-J6 z<^^`1Vdw>xo?+_I|87JN{>s4GGt9lf-ZKooz~VDZzQE=)jK09?Gt9og?lTO(!16Op zzrgl0jK9G8Gt9rh{xb}~zydT(z`zDHjKIJOG|a%j4m1qGz!Ee}!N3+YjKRPf#HVy+ zU=Movb5{lypVPEXqbzEy$E;xs=#72Ovb=wG>pc;YBbEo zz-}}Q$G~zlOvk`>G>pfpi=iZsl~z>YKw$-t5{Ov%8O zG>pl>nl#MGz@9V=%D|#DOv=EfG>po?sx-{Xz^*h5%fPZUOv}KwG>pr@x-`toz`isL z%)r7lOw7Q>G>pu^$~4T(z|J%b&A`$$OwGX7G>px_+BD3~z}_?r&cNa{OwPdOG>p!` z>NL#G!0t2*&%p9DOwYjfgiCUDV0{|qXJCIC254Y`8YXC9gBnI?V1*iHXkdpLhG<}k z8m1`c=9e-wd&L5 zn!v6V4BNo66-?W}wiS%qz`7O8+rYjR4BWuN6-?Z~#ubd*z{(ZO+`!Hi3|(@Ce+s5< zVCxFTZeZ;S<}Tc?KLvv~uy_TNH?VmHqc^a61+zD>dj-QcuzUs6H?VyL<2SH=1@kws ze+2_Luz&>qye1#>vChXsQ;u!sedIIxMe z>Gx{_t5`6L1G`x5cP$AlV_m&RNnjgm(0(P^vfuAod~gXI&)>A^u#&(+R-+arfsL$| ztx5tbSr@l2VNd&;dUYxZEM-09lJx2In_w&l*0R1nt0b_Owaz0uv zffcQR<4XcNTC*mX1eUbc&nO9OX}$kQNnlOu&jlrcJ*|V5mIM~HidL2cHnlETTM}5+ zf>|Bd)f)IxNnlxP+P_P(rt}vrf4d~GuJzjHlEA(e4D7(d*7jeP1U9ysepeD$*=qfB zNnmH|%UdwL z1KV3Lz60x9Fuw!)TQI-_3tTY40~=g0!UHQ@Fv9~oTrk7~OI$F;16y1$#sh0yFvkOX zTrkK3i(D|t1Djkh%IVquB$(xaT`m~rfn_e3=7DXlbq`z{Sm%Oy9@yuCfgV`sf{C63 zFaAj|(gQ19Fw+A&T`<%GOIFPQOx9WNO2fh8}P@_{Wc z81sQOFPQTwF8@I==mU#hFzExEUNGtdt6nhc1G`=@>;ubQFzo}|UNG(h>s~PL1N&Yu z@B<59F!2K$Uoi3mD_=14$-{rIEAP54u=E8}Kd|)$V?VI=1#>^J_XUGLu=oX&Kd|`) zqd&0v1+zb}`vt>4u>1wnKd}7;<3F(e1@k|!|Ahk}xB!F`Ah-d9BOtf}gfk$x1B62$ zxCDe#Ah-pDV<5N&gmWOc2ZVzlxCn%kAh-#Hqae5ngtH*H3xvZUxD15TAh->L;~=;W zg!3S{4}=3DxDbRBA-EBQBO$mFgfk(y6NEz{xDV1I30r9K{y_Q>p?glg8M-@Ac6}*I3a=?LO3FVD?&IU zf;&PuB!WvqI3q0m$g8M=^FoFw1I5C17LpU;mD?>Olf;&SvG=fV*I5l|PU#Vn=8-i;?I5&cO zLpV5si$gd$f}2A)I)bZ1I6IiMJ)93R2;A)Fss_2QShqU#O81tOdv z!3`oDA;A?QoFTy-A{-*YB_f<6!7U;jBf&KyoFlaMIxLe!A&9@CBao9oF&0s zA{-{cWg?s=!EGWOC&6_hoF~D3A{;2eg(93N!HpsuDZ!N@oGHPbA{;8gr6Qav!L1@3 zE5WrQoGZb-A{;Ei#Uh+6!ObEZEy2|yoGroKA{;Kkof&CrxnE2uBS$ zi_e6!Cb(;a!zQ?FgwrOtZG__{xNd~=Cb(~e11Gp}gcB#YafBl$xN?LuC%AKjLnpX& zgi|NDb%bLlxORkdC%AWngD1Fn2($9Bk( z#uARK;K~xttl-WP4z1wQ5>72R5?h61E4a3Vb1S&Fgo7)%xP+4{|2k-^aC8M%mvD9k zcb9N@1(%m_dIh(aaC`;VmvDXs_m^;h1s9lbf(192aD)X{m~e&#cbIU9<%)m2FPvh* zEhZdeY4PJ0;T+5G_qGTJS-yXEi*Su~|6Mf-6lp(}FuqIMjkmO*qwpTTM9D=ml=p%HcN$ z_nL69W!qJog_A8;p1N5$+JdW1INO4|O*q_w%S|}lg4<0v-h%5*INyT%O*r6!3r^jh z;p2^dPdMU&D^7>La&vIU35Q&8$qA=iaLWnDTyV_^=Ui~l2?t$p(FrGAaMP*TPd5iw zop9C#cb#z91(%(0+6A|raNGsgop9a-_nmOy1s9%h;srOJaO4G7o^a;n&tEnPhhA{$ z38!9g>j}qRaP0}_UU2UT2VeT!w@Enpf}2k``hu%ZIQw$-Nt=YjFSz`K(=WLFgyS!` z{)F={xc`I$Ft`AP6EL^|g(EPy0);a$xC4blFt`MTQ!uy%g<~+d28DAlxCe!UFt`YX zlQ6gmg`+UI3Wc*UxC@2DFt`kb(=fOVh2t=|4u$hDxDSN`F}M(g6EV0Eg(ESz5`{A{ zxD$m#F}M_kQ!%&|g<~W^AA|c*I3R-yQaB-l8&WtTc}{psI3vkdz9k%z!6hl2lEE!09FxH{sTEyr zGe?23MtURt9&aa99SHrEppXx214g2G^x!igH(sKSvNT&cpD8r-SEp~`CIb>UPEZdKt}4X#z;Tn+A3;b09eR^en#?+^bi z9Ie6CDx9ss-6|Ze!R4yGFS#waU4`Q{xL$?xHMn1e12(u|wet4cf*V#iVuLGIIAeo5 zRybsXOIBCh&Fg&iHQ|`eq!q6T=WKA#3I}ag4}DEIX@i?qIBJ8dRyb?9KEEa$w!vj9 zoVLMjD;&4Mbt{~=!F?+nxWR=hoVdY_D;&AOl`EXN!JR7{y1}I@oVvlStEq3^7F@f+ zxf|TO!oeF{yu!&F+`Pik8(h7@*&E!w!r>cSzQXAn+`hu`8(hD_`5WB7!T}syz`_X} z+`z&S99+S|864cf!XX@7!on#W+`_^!99+Y~IUL->!a*Ed#KK7&+{D6BOh0C$a25x5 zv2Yj%m$7gf2e+|s90%92a2^Nuv2Y*<7qW072RE{CBnMZra3=G6{jzW<<3V^?IF*B2 zSvZ!1Ygss#gL_#xn1hR1IGKZ+SvZ=5t64akgS%NcoP*0*w@kS`xSfULIk=vM^EtSm zg#$XcpoJ4UxS@q3I=G^RGdj4Vg+n^Hq=i#DxTS?-I=H5Vb2_-Eg@ZbWzVxDSQU^D+ za8w6ZwQyDkceQX>2bZ_y?Y4z6qAybkVb;lK_qY~jQXZfxPm4z6tB%nt5s z;m{5)ZQ;~T=jks9$98aS3+HzBs(wK@xPyyZIJtwHTR6Idt6Mm`gS%TeyxCX%OE|rQ z+gmukgX>#3zk~Z*IKYDoT-(mOBe=nZBRsgmg)=<3!-YdUxWt81Jh;V$V?4OVg>yW( z$AyDDxX6W*Jh;h)qdd6Eg|j@k%Z0-{n}%p}yoa@28E*$K^#V(xe!Obol?ZMS9 zobAEgE*$Q`c!#B_9l5!Is4^089*HS2ZxlG2R$ z_GulyyfhcQ{j|PVU7CH?J*~y-O7q6tr*-GEr5QiwX`S$5X}b4%TD!c;>$vf0z5GUL z{&V)z8uLzR#uYuSOE#D0qC=n7!5@}p?_HkO=1)tr@!NHp{#9v)y}eF1d{>&&*R9hL z|0~T-^VaF(-%7J~%sS29R+`?u*6HR(W$Ae1Ivu%NS-v}aojz((mPd=$>7jkfa^s=v zbnSs%C2}hRUQ(CJFjxEcdbJuG3g0d_fvsTZxFU#${ z)~auDSq{5#tvYop?|dP?j^BJ*BaW%kslc{P~k*dGMPx`g9ea|66M` zYHeA*$r^RqP?iaE)@bX$__(9jXwb&8eAIJ|3SKYE(CgReKW~+#?OAKo>%V1rtNj`s zwzVw14_TvUJ}%2Yc3PubzbMOwuUD(_w`IBQ&DDDBhq7SW(D}cVW#J>M_5B}Zxp35K zjorRHKlWIy!kx=A{<_tA<8S5ZaOP^&>{*_-+O5_;`<17GvgV?u<#5AS>)dALS@zW` zeff`a`u?kQ-%<_ihgJIKyz*3ixl#izE>Gh(R_fr(%QJKJN-es&Jl$rk z)G62VcEeZdotw*3UcXXhckup7R%-jo@;rFjN{y{8Py042xlfhng{CX@WS{bsY`;>c z_bbm&pRdr{1Ishy-z#+M(DEF*YK49oS)RoYuh778ZilygaYJx?ELj%5(jS z<@#-1dA^&mT>YLcPv0TS^|u$xvq#Nxjeey(Q?6XDrf-zz*pruQ>f3xBTQ1i>-{bx4 zzg%;+mgki}pH$0F%5&u>PioN@<@sdelWPBMc`BcLQpEoEK{o^E3)yyWtwwLMJ^h+Oh>e?V1KhrQ`=SKs!NxtX~&AZ?`0a(r6M;R zy-a^Qz9OIOwM_j_uE?#wKB3=EugDi$pHS5~74Tc1&}SD^&=~SO3G_1^2^Oj)M7(L%FkP(5&x>lhaH#b$CoQ|**T$o=yc>)g*OvisP@TJ%*#?&`Hz`+QfCZ*N$v znx86i?b(a<#;+B5wQ#Wt|EkCd%@%9y4wYH7(_-f1m1+LX<2t`_Wk$UDxE|ZHGJihx zxEk+QnL8eNT(>l>%-bU$*ZM;$b4riL)%+ioS$yr|y7S1&9D2s%dgGYN3~BqgTD7js zPX|4&f$b`D?GBG?ONUDM?Tgg0OJ#~)U!)PP%(PXD^zliR*>&b3bveBL^L-v08+?A3aawq9MCh65I<@cPQU_t!!Vyty(beY#L@-CmhF zuPoHj6_shSe4%>QRHl0RLOtJ5nKuV5RMXy->0Gr?H}|c~gO@MV(gBs(?!<-KVQ^)x zKXxJK$jWTkXQ3vKuFO%tKc-K|SLVJCA5*&rD)ZTkkE!?6%AB$EF+KYbA7{#A+UpTs z_q~tl@<%IkOW9+Zv9L1Fc7Kd{LuHQ8V`{U!GX0KvO!ccPvt^IRw0do2y8gUC+i$4M z{aY63)PM2yd2WG*yj)3Ndx18-R+;&e7HID`E3?Zz3v}_jysq08X#D2NtiE7@-uj?2 z`*&WT13#@y#o-Hd*_V}h?r#e;@!QHA_QQO=`9o!TY?`nAeyPkW>*wpjKPuB={(Ozx zt}1=T&DTqfs`5tf`Py~2svLXMe4X5+DtDhVUw7}#pBK&7iv6qDBhS|l2l4hh&sWPs ztMb}6kLt$5t8&C!k7~+MRcXkhdgIutyzt1QYFtp2Lq5u3 zsmfkwJgWCymFwC*s{Kx`%Hsz;s?$!d%Jw@vsyolF%K2Z+)BN+RGVR~ z_Po3*T^^n%UtN{KL+7dDx~jZcGf&fQs>(mFnx~g$CvdjMS zbV+?xF8p(@`rTQD$7ik{yQ?anzC4%T+p4r(Hdl@At4gn_bJcoiRh}6*SC@{gN|TDY z>N~b7-7lT1ITQJJo~u_USLNdtbM^DIsVRra}kj{d%`DwkY1N8L75<^IldRPwJXc%E}~ z_sdmj-gu6ty~fw&hewqEROR7Kk7)BdRrzTBBl_dLsvJ505gq(NRc;>lh&p~!mD#-? z(Zyd><&zs9QRO%M{W*_l*!NYrvFH)a{vZFo*&|x_TUEC1^oZX5i}(M{Z2h=Hb*_4I zwszm8I`=;{TSqjm=A1iQUH7ccJ|k!A!hNfAZo_Qdc3^b|m(12(f3MCnr_I*b=GEC& zFk5r}S)EQzXKQtf>eOsETdy2fo%x^5(gy|A`S{gY`mud=4qY)zI~7;wk{PpfK-cPw z7(7cYj<3#!s#)rIa&`W=e3ni8@Grutk~ zo!vg1sliuOM=#D~KUSUUB{Mbs#_G(TJX4R}TAg?L&(ss8)!Dstrk<*-jxV06=W44{ z)pe#`=~11BkC>^qdh`BvpQ+7#tLbSxtd9m%r^9;>>x)6vaB?2jx5KJ4VZp=taTKp_ z{KNWXTy=iz^RWJyRGoj`{IIr7sm=xGKCJC$ROjvv4{OI+)md=p!)i3QI`8iMuy$Hd zot?jZNIN~w=kwM>YV<^PuE|5%aYc28Jo1pXUsIhYMn0r%Ype5q!$bPxndMYvsA$|OIb>9ALhBp7VI@`TAgXj9{9KB+O zUj3*#=gpX*=Rd1vpEN`Hsyb7uW@y>}Rp;r;XK4P9)%om%8Jh7+b($PILlgd}PP=_( zXy|q|x%9W`x~ox5dVMfmRlC+?>I>6#Tfs2TUx zYl+hxo+8mx^{RCbG--U(R_XbA5^pPHJMrdpnjWFla-e|sJEun=0uQ~BxxI;Bx#+NE*6Fp`VYmC$n7>EOKY>& z+)3Kw%G&HRdXiqgrZ)TaoTQ=G*XDrhCh3fuYjfZkleF{gwQ1URlGc~i=AeTn>Fz52 zcl$}|T*v=@K2bmQ;D2A6sD-_GyA>04TVMX&jEOpYKyCIPJW=o7SDSsSCTh&k+U$M# zM4d6RHhY{fQQM8JP2*!GYT1O^?7H_v-SI$e8vQy!hfS@`c3UUtKQn6c$MX|3XjUzJ ziwWv7w>IBTnxJpy*XFCf6EuBMZ9chmf-YEEoA=M3pdFUi=AGgRTD+<@|2}Mju1{@V z+;xKXUSFH_|2G~;PHk4bJzixm)Mm-r@j7^8ZRX7xujgK?&5TjwRr8-{#;fAX+FbhCI34(HZO(dioSyo= zHd;PTH~p_RZKsb@BBwivhnA!x_95YWXo8!IIu1YpBt;^4zA18g=2N=p>-KCajbSZye@t29;?|$ z*5!^{#_E(~>T>ycWA$Onx}4T=topX8OHuQ&YF1d6!*?006&>rc=eJ{YaTh-Bn`88? z>hkGRV>I~0y1YJnjQ)8lA8*7Mtv;hJ^XkW_`#E(Pcg+}meSTf;K6MPwYjwG;^%(vA zvbtP&z!*J#WnH@dHCm^Y)aA%eM(e-V*QLqE(W<<;jy&FIHM*V8=fTmMSXP$}_m0-F zRdtzPHd?D|>oT_cXr0reEs<^u@r!*O@zxvhXxSvL8_`tgC_1-8Q zGKBZ{%qYzpUYB>~k5b3cb@1Rv>6vkLaMecX{7H2gaN{U#np~G#&K{+kr`6@m!cqF} zp}Mp@WR!Z%uFD>cMyb)fy8PdlBQAr1pEf4sYH_O<7u(F%OSqo>G^Zp(DAj z)a9a@k!qbf^7tdQL$MK4~)>Wo9pt|J^c3vb=h+qfGb6t<& znzCzsI$b+l`|Vzzy-y#mVSCo+^Mc`Ov~PXZ9ynZg9#Ef&+lJ}8gX&ZE=`h{gtUf2d zGK^eUeGYzdn9e_)#ret zhUu^3`h3x3n994>XU$JTwb}I<_1;jOb5eb7*f3P9POVSTf}uL*%=+vyeyAp%Q=hkc z57mwr)Mws}LsfBceeOJas5V_%pR)>w>eMUi^Y=rBYSA_I`EtjhI{5nftom|@`rlNa zA+Hb7SGU&Z@>N50acO;8JUm3JD(dsokRdv}rXH`_5DluY&*&?L=$oGPx#q+nx~NZm zjyraUp6pxC9(aiUKA=9&{5n{7-N)G9<2Tk)#teKX}_o?w$^?CPi_vy-S>oev1ftvq) zeXf3Ypnm_UKFyyVs55`9&z89Zb^jmrnLc`;KG{~EYkLk<;f@Vye%(Oz-MJxKP9Lb3 zc5BGgHUrhPNkgt~I#4(4)sVk$H&6@qZOA*H-mCu|(2$9*+$$g4knT_3t3k~gvd^@8 z_3B{_**NfC9e6}ThL+!}Yg#nqv`g;Q%wrp}qwdw`ts0Ue?^Wxz4Y{+)y{ay3NYPIN zw5(%8zWwh2{o1)9^PU-?u4>4Q^9Sgz6B^QN+yLd|hP>HpfVMlmAtP@XpySVK$mwSd z(B0=YWV`kQ^wb3nS$^;U{dsXiDt8#5&X+ah=r8)K$CZ3Oul3i`YZ@|sMSuO@bqzUt zMt>c5Q$uzb++R1}%D=1ZujzL*r0lZ(dbhkGhacZx`&KvPtrq=tR$W7e?b%=bdo<+u zpZjTLuZH}%xu3qft08lq?WY#~8gk`h{dCp64cTKtKaC#LkhOjKX~WQl)ZElhzm90& zd7__Mj^X_k_R}@v8{p9Q)2K-e>C~v7)=h567hm3^@2588f!FWR;SV+B%vJa3f>{mu z?V)?rcMe~VA@}I9M;mf^^*#FUV-4B$ihH!%;)X0c;T{z|(U6;txkuM6Z^*uT-=pEH z`1rr{)ss&(r2PH9+PaSK+w*Y3|(`^ie~;>~Xgq z{j?$7PQP0lzu^0F;NAN6>xOLoQt?9{E!eI{RzKZGFYMSOyN&6iPj~LYUZ4*-iXM5WO&>LH(j#AQ>#fdv^+@q6 zz14l+9_cr=w<-?kkr&H)YtTVGvR}8}nsG>vT(x^|t!UmOGdK0pYlrv9m-Bk*vm<+? z?VY{!*U>%Fa7Hif*OHIdw3m)4=#lL|yHnlT^~fnt-l+?UdSuYRJ9Ser@3;G%YUt7< zO^&=%L)0VZ{n%5JPw0_R>w9Yc$vyJwn4VgFT952?eNVk~CV$_yr#79_BO|u!sV~m& zk(XZSpu-mE{J;(~W%bveuAza($dB z8x4=A21jS|jSb>yqGqOy8XHdsqGrnO6XNM>iJ7whadOGRcuE)=CzmgYCu>-o zT)CXvWr>rkSH)AGr_<%ywe0tf>2lqMc)C21xjCNxs`&V}cq)-^x?Ho9?f*DUuHF+* z(~nG(EBD9KZuK;|>`**CX+KRaIvP*z;?v~36FlypsdCoocS6isv~8-Ici#99U(u> zQ`5rRBjnMAYFe~rgj6q4)8e5cWV_|euo1H8Dn1?ZCRK%@a{V)#P;zmgOF+$#j3P{QOi+$r}gDZ7cL$6)#TgPIP#93)qNR@0_EgJkD#>|g94ndb+`ulXQ(>zA5F z791pXf7R6E%Rt#URZY#050vRfHPz7#lm{}nK06MSgDh&wS!$pRv2&gM9Uvb$x$Z6w zkh48J-+}>L*J?V|Yk*A2qM^-I2FM-RH8k7OUv|%>p>enR%N+k{sN3rP@H67Al zjwzs_^7Z=5lEE6v>5t*>#cC)eDMqS`Y3S+J7+IsFhR%(Pk#9 z32imBvU(p`D2n~C_m<~6YN++y-m*`$hRUt$EnQtT^EFPpMrWx$4CvGe&18B8>68GhkDAe z@fwPm*;6J>)KJ~FJ>}>r8p;~dQ)Zi{p;te8$Zc^NI&h|kY!t7d_}M+=6OD$Vy7rKx z^cpHvzK8TH97kh!xqgm@u3YObYtPs4`?B3-!a}wqrn~IDL_^hTc9$v3G-P#jlZKTV zN=WP`3$M}8iuK*(zI8nRh;FjUMsC-jo4mhSLz!8-$$r~3bnRJJ`ELi?xwETO@77S4 zNnK^0eHtn$y2_0QH1s`hS6THi`~RVfJabe-v4^`zoZx)Ncae`yX(-UPi|ll%9BHCpDnsiAGW)<^iI`Ls{U$dUEYrJN(%e= zp@VE<)KJjj4)UCd>uP2P8E)2)p=}3w+{*ribdWV18p`+)CHJ`4|1(jtj8{WLXGh5m zehroA8YK&4)zZ^)QF1|cEzLK!m;RhuioDid#^upc=92a@HAqVb`n8us^J^)lMtk|D zpq2_a+R2WEwRG!lJ9(q1mg3g6ll6;h`FjKH$s-@16ZDso!TJrwaR$i#3rK9iK$SQTT)bC&$xu%|$a?fZZ z{oz_V*Sd`y*HBACi?oq%8fz(ka%x_06?(rA%x2 zyQP*!q_&dLZP?x`t>pQ3TDrKXl`P#sON0BglCwMU_|;m;Khat`X>BPxcGFVt+b!j( z9$NCPZYhiO*3#Y~E%|%CT8gUIlD}u9rF35l*=(Se)+V)(TL){Y$<`LqJ5 zBebM6Z6U9Y((?NeEo7;&TDtSPxr`sLrBVBu%Qq9XlxJFVS$~R_4!3A7S5D<|3pJN1 z)3ucH1+vXdEiFC{xl663nmS0gR!jFfK=v?j|B{f$W@#zMUnz6U)za<@Qud$EANtRi z^2|bxcMmD^EYZ@8N>UD5rlrD}LY`frrQ;-I?$uhp-@B0g*J>$wfRHEFYe`pI$gG>R z6yjFN9$U0@;=W4m+oq+q8&%S_LrY&qs$`qpJYGYUT)&s&on0k=?&o+skCgQfX(?h? zq?~nx>t<4#UXOa9Xla!i7jR?do$CvR)1LYD|>zpJHFWg}$deJwRlYbs|y zC`QKA5rS)klJ3rTwrdm_E>Lth5)qc@;I_GC^BY8bTOTkkcNvBy$o0>P0;WjOmFW5+qbMQL(+)(ayX({wr zL;gQDEuGOcl!g6VCs7S$R2CgwE8b8l*>u$WcLRAYhmP)?YasvS(oy@l4P?3hbo8iO z1KBOFjyhLpAm`=R(bM$$@?t?9b-P|){tedA%cb>YsiHdS8B*z@!Os=S^qfSr4gq`336sOZbaeSmJ-M{LjvDT-C(kz2(TQpG6vMf|4 z_tsIl{-H8UKOL>E87j;6*HI2F+LA`I{ZDGicVl^+?X_g)cpWVtUrXkhq$6KMEm?kwj>hMyB^yuG(T6uRWvA(! zm;E*6&>1?qFs-JX5wD}lEo;gp8Xc`FR8wx(v0qgY;^>Qb)OQ6*C~ z*>SComRzqU`>fZId1*B{Y@?3)#Z;3MH|ywTjcPJ}tB$HUs><2hb+qhmRk>s*w_96P zuHCJpKEtZYt$Vr7!m7$W`*la-sH1t0tH_gwb@XRz6?yKcjyjI3A}=4;(eb8L zAh_EwgO=XKO*YGrx zFFoS8cC9GSJ=W3wauwx?r#i}NtRN3P*U^Bh73A)hI=ZyDg52_2M@9NpkZa!RXkxVr za`Af|-M5yPvp(wh_sPr48J~5eU0q&I_{wn~TwV_SuA|VpR6(|Nj)X&s$a=cXB;`C?mJHIX{QW$c0`VeVI{4PV=*$ZOX_&S@blwNEsQGO;4}C zmzE83=&Aat(y~l0J*f?)WzIZ$df2J7H2$ZjQl(4F*Ln3c{$DA1Ex(?wUMwZ|6x37D zf>Lr(u%7z$EF~uv(bJ(yrDV4dJvlN;%0|WY)P_pRk|p)DW_d~JDW#`x{Y%QvW%N|1 zR!K?acphg7xvPSn5)(_vS(Wq@yuO4SQbkV#hnJA3#^Z&TkY#J=$r30oJvH?to)nkw zYU^p?w&L=99X&lCS6r^H$M!`OmlMMEG(2~4*{*?}j=e4>D>l-Tb#F20X{;yJ)MD~g zQ}(xcF?p<+o*oq_Cg-VmzRw}DztmITqaiZ9xt?~YLuBrjdivQeM1E?er<%n=>gi&hLUQ_aJ(=GWlo2!ZRCj+t>7A*k zvC|6j_aybSuSG#QN2{kV1q;endOel+Qb6WV^wj-W0eN?po|b9~$oX@4p7sS~>v?+q z9mfJP`vN^R`jwxb7wc)_+5FP5SWo+B=a-R7_4KJre(7AMry}L@^YvX%9n$j2NvrfU z>q-l$1{*$36+0SPG$xo;B)IQIDa>*Gz#lOiTBhKmR;J!Ta z_jx_NnVLtgy{M<0E%M0bm-T%A^*l25ik^mk&Mh}w)AR39=awyQ=;@j|w@f8H{cD$7 zu1nBUv0}NUxUHv_KXb`nceswuC~LE z%41$PmvhPoPxLf-VNN;WnVvTH$|(!I(9^BTIpvv`dP>dAA$z{oQ_-6_r0or_ixoNe z``CIKIUt8@{DI?9D~EjZQBUWb*=5{kJ$+2fE{lBCQ?~Wl<>_x+*Tb{R=wv;=KbBpl z{LoWeAe&t9OHW%LXOk8G=;`LxZ1UP)J^dP+P4-UVdTW|Zno_x5a%Gc?j9d?|vdRi3 zJkbxqKdBo;m z15G>Q7FCKE=vcH{94~61UnwrpxR`;;E_8_-#d)5}F44B6ftHd}JT7IRTm7A)M;QY- z91iimtbsz;ImDpy1{xaX5I-syXnm4hjILy$`(x}PrLuwVXJi)>s~V`zZksSwGtgjR z6R|Z6{Qj3!m}?s7W}H<_t!i#Uk;Nn$H#bn1ZRz583j@t)nl380GSK!{MzOgy$7zaD6l`mtzxj+}ZaV|z zKb$5U?F|&(CQXd*V4z;#Q^l8#28!3Gimsgvw54RKNQgGjweu;Wepds1>6Rk)cH=l3 z|B1pq*q%)T>pw}>8Upq6`oiHpMwGyuOug%NE3$Dd-+NCT~$`BRui z8R%e5Y1&~KvA49?g6uVVd71ML~{RaoN=@(HzZ=j#AK8x`N1OI=`XK_#AJmvo^D$h3X=l7q4VUB^ywfQ98%{5T% z?;l0|`37pD|0tF&;Q32_6h9VnUe13Ik&6u!)9r&;v&29njPJ$2r3RX`_`Se#jyvCk zX59({%}#hH{;f37;(_mkSZ$!yuD4?K8Ut-w|5p55YoMLsZ$;zv2HOAljaan7Ku5>E z5$`t|`1_1+M9s|xI=}n1P;W8NW${`(*lM8b?_Y`H+y7sWuf)h5TnE9g#Mzw&x_kVk z$gnj&OXI zKNDS#^17+{Ol&;HdAa*kd^v8Qt3#iPDknMbz9(YrDURpnC*s6u1D$B}M3~QTy+3~} z8lN-J-ieQe`n-X*{r6a0yO3x@w@fkVnFQ z%|H`QKNRAIfrfQ{D70jtzW*MGOE(SFdHw@oOW-=H_&|i;Hc;d1_r=6J2CCKXzBqK3 z*S+nY_>su@T76HHxzG8lb5HboU?A)LM6u!_?++sqMdBl_t1OAam&AT)T@TYXf!qc1!Ge!~2l# zmU#8nKvhfJ5;@=Vyyp@`qYno1c1aK;KN{$F>P@l!6Yp;eZ;IQW4Se5~o5K9XK>LV9 z`ELeV&Oc$)={x)FxFO<`d3~+DA@=<+P@8%;#M7U=KRvoGT)zxdc=UBq`Hz8|*{+LD ze|eqmxF+KMah{u96Wdb^bm+}haVOP4%cfoxsc8n9QsAlxPUrpa$Q9AV#C6*CiWrc= z>n8cKn3c)Srm#Mb55wT zDpV`SIngJZLOFMx6|vbB`WAUsEX|?N)wgHFzMKlJpLRxE&!zDHS)UQFb1T&T=xLFb zN1=-CPK)e83b~U{iIRC0dSN&v>g7}DaH&(Gb$*3rT{tQF7Eq{9_mg5mL51q1pAbqR zg|aU>Ayx+~^uFo|vA3{7ClZc}b43)IJMg%;Ta??oj)~VH3e{eJO#CdSkU#90uoPG5 zdD2mlwWLD(#vBy|ODQxX$5BzHG~2W5h^SFUp^~a2qG4HuQr;dGD5ubsX@^Brd4-k~ zJS=)tP$=f;Au*t$LN(hR5+f@qFQ-7nVFQfO$xKC!X3LZJiqi7lZDIh=dNwmJ&kTDMnh zudC3qFlIf4dL``e?0dwv`U;)exm#>$piq3|Zn3eULe1aq66+c% z{65ewvAVHBPYdi4%bM_fM|O%uO%?wCKL{Sjin?l1iZ| z=eLVdLZL?8wu^yMAy?Wq(Gv{I8Zx9osIUcPyh?p)s|F`v`O;?3fy7eNw8{1cW zy(ryXq4Q_giJUzYitVyaq%%WP*NV42*}nyA1@%&BPo=fuKyQTx-dH1+_fe>L%o;JR zuR_mkt3|(loZr=}g^W?CRh`wMQh$X!_g9Hr0~9(pVwL#EoRDReNE)b6>97o zq&|y9`~-!+KfOqFoyhBD#UfE{64!mLMZ(8yn7B~9n5@vxp$o;qDGJ}WdV$c!D%5)O z0?}ovLe_>0M5Sp8?R_?1*qGfX%oq2jE0i_Qe6cA`p_6;(iLo;{PM9YmX7c z3SF8pSG;A8EIe22S1S~JVvd-mQRqh09MN3Me*T&*^63;RHhZ>s$4n?QTkO?y+%C-$ z6Ac{ip0h*~h3)*Rh%B=ddRt5p516&14Py0dg$(ocqTd`|pVxGv{9J`9S+(Lfb9!y9 zI66XNcyD720+pPGnu8 z(7#{P#Vux|veU(!rM#c?oF-Z<<9b{=Rb*Mt;l zjoEb9ByoBb*WKHRV!~>L5(`We)z&DKuk8f!joD2TcwEygy3(WY)|wN^IW5aceSCbl$Ackx3&&)-Am6>>n=9 zF>8GuCPr^n`2K&xM2T$*9qc$%JY@cwGel^%b9}B07PWRLG&pmR_`uv+V~|+9ljAyg zplGs7p~4#nh@Z?(Px_11yA@iHv%ipg6uPO35&xL3Y5l~yy$XdN?JKa4=Sl7({xNr# z>?79fSLj{W-XijVLIoD}5#9LMF(^<$7w-MdUxG(D(Rgagtg1RAyoLl*vj-)Ybl9+{`)ezn8D^xdk4e^>8C98{m4|troYT^^qaIC5r z^iZMAKdOjt%rm8`h@p>ooph@#l9@jjRT9IJ_&P=v#dl_iqkf6J`E!Ln|1K#mGc(JU z6!l;5e&4HvILs`uthlK7lK1i3#l%J?+##aCD_(EmA!06b_?V)?$&A}sL`- z_{Q9rzp&`>hSzcHU~!juNn1!XdCT*iDJTvx-~B5fO1|UxRwy7AGwpry3nw$@%6ww< zdxeT5<`u7*6@5XX$7rpF`BtQCYyM|Jh?inX!up3%lEU0&CL0MfXdI@ zIMJ^f_KlzaeDtaknOCAbs+!;V`gqZ$TFU%T)u}Qv|E;yFqLcagM^>BaBs13(i>lxc zw*O0}Y7(H99+nGbZ{Z=`d zreocFI)^=B?FvPQL@shPb>^@KUjv_h53&d*N= zE>}rr)T5=UIA+s`C8}f0>IWC8l9|Oq7OILn6v{DozN!<`oH185i}`iX9MxH7QqnBd zZ|2lEgQ|p+pQm-xsyZ;M)QMMVnch5cs$c#RRptl{20|} zX6>FMRqL36dc#x+%$IowtBlM8fBLIRy7@YCyRWJ>v(wIAs!7bU+U}~2OjGYJss!fE z`khq&n5zmzse(NU4M}OEYRasa*ito!>E8|2JZ6$!r8>gg(l0{wggK^BW0jfND7b;D zm{*}}#(Js<=9BxOs{YI^`)aE6%#pLIsdg~K22@tvV0xNVP<>(EEmBtHW3DunRF(E| zz8@7+MKCKJETZbeOqo+iHH~?8P=3`)rnXs->L{~SvD~UeW{^3%>KpU<<18vSGpvUv zvWTDeA=1Y@WIP#JAi#0ie>k!{^ZbClkzvfpqT3_EOn9^*GMd?T z?yAUv%ty_ZM2=^6HP4NVXCCgMjhxRseQQ$WYUbteVUgRIH+S`lJjhHe7!`S%nPgB! zUS&Qv){DHud^@0WWD@h^qhgV-nBSTOMSf)7>)~nko%u98x!E7)>w*uOr7=GlPd3YB zCO_KH%=Z8DJ+#f7%=ZPOnt7N%9u;fmV}2<3AR@s0STHIgOO{!bB}2%X-GT&mz_Z)-l!|)&|y6mVp(^8o}z#YR78As?I9T%E_|&1NhE* z!n(pbz*^1HvPQC^Sxs2wS-Dt7UjQ#zmss0bvsoiq?OC;1`B+9TkHcFbb z%E9{X3E&!QBP*8GkyVA|a|iI6b&NHa)sIz|m7Vq06~IxJfz_2&iDhvHaEG;)HJlaB z3OE9I%-X^l#R_M6?E&0ltzz|KRbr*s0yxczXGvCe)_rRL%UE4mMOd#bY$K~Ls|4$v znIE%yvx>5wX9lo>)q$0Zm5{-4V>M!>n>d!NL97r~QhES$SWQ@I#sGG)da`n{E~f=B zj#ZkKlp27JRh#u8C4hyjMy%w2JQpj1_46%5-vKDBs;q~<0+`Gy z!n*jA{bqT8aL!ng^);E>vdXcpeGedp<@^@FI#w7f>1zO^Sy@?Iz68*KmGqfwiRJmk zHNvXSy8bbMZmeG)0#LK^v39%|i=PEhfVK81*DY(ylK{%Hc0LZEB5O|)=ajYQ5kF?_e8}fn zTOV+H*4q046l5*F$Mwh3Ck9}@%kg3Tz7xPe)~nl`M;6@*pdsr}0_TIZ;${F@SW}5} za3g>otXtRFcGj+IY!^#=HGscYIG-%K96&ABx=ZZuMUEls=>^U^YsYz>pEd3rA3MwQ zur{6Hc%J4uVck5%ez4}A4B*F!09vv39OwC2gN_Ao^(faNYx)uHf0*ZC%{#>V!NC9; zvsNBpfA$9;SnKw2jqeQrtaW?XzTE*tvR3R0;M-2F7uK8|0le7GbFyN$@%&o@$j|D( zC4hsQd3|l-{;b6tIX@dXrmRuxd0nsL_^su6Saa6|@L)B^fz@LbuaA{nw=1|UYw+>_ zb}!@nFXcH{Lzi&O7IW<_;`6MSg}hfSU>oLhe^&c>Jldd`K8>qi^FdkxncORBlP;(6?uye4OGyjb<(IA+ti-lp;Tn#y$*8$d8iOyQhN z4q(kBj^{*POA~kuR>Se^_c-3q#$8ZSm zHG_Hmu*4wtWgzb*131?G12`4K{rhn)`m!yoQhj*+^yYo87w=O&1JLx~y{J3;(2Z^A z%KLa1wj-MN`py9avC4E}-#fBj9eDqZVn5mkFtHu4hqj!HHXP&D0qkuRz{!@pXSWF8 zZgZ{&a6BZ}sNlS-0x(Ag;A+M;M({q*3Tn!0pb75>jRPpwh}U34uI~msSAEV!IQtRC ztjCY*^6@%+K9t+l4xn%?&P`43UxRD6I*(VC_lYVTo5}(FtHimj$oozO-tWuvUR;i2 zU6$*k4A*Vx0M?fZU{Oi-w*+4Uit{=v7C`3^j#tqDLW^)*3Uf|_IoAc*?gBhUe(s+y zfPHznPJ=j}|8dRa2_Pyr*K01W{hYj}vU9Amam{7rd9rXG1AfH${pjoSqnX!_G9EvC zEs0SeDve-2S2vI_hZ64KO*1q7;pS| z^U9CCFa4POg8M)BBj+Lx&iS$KtRG#^_>u3lANNlB zG5ZADaoi8FdYA-hM>%^5bC-&Q*6mQoC{ubm81Y`?0YT&)LzB(@`9Y_FM;T{pi_-ZExkrn3jHI zHs`irTcsb1ReltT^kYK=*Hu$Lb~pB;Y9l`mH{kr&_v1tu+fa|ks^drfP(RMp;<(lH z<5YD&>Q>|USMj4}Wk26DkYihcYq6Xk#mf4zsx;eDitR1o=lj+AF*U@GzePCDh1thK zenb`InC0iO@^QR^{3!k(+mf5x=JaEH4nIC-^P@vnuAhJpHT*uT_xg~{s7dviLAJ(}y&Z4?WX;xR&NaBYkZ{$9kSl!rk`LD}_)zG)55vy-aQ3thIZm-1Cw$m<%m>R6 zA6gvtVdX&|KJE9R<~|?d_V8G{e8{`ghhE!#*tyk*zngss+vG$11|RrMU*uZrL&w!V ztX}EE>*YR_T;{{TB|hw0#6B(Xp~`$8M$TowX8Z6<;l~D^U&rS)K75Jyq4Z22`o#IL zW||L=V|~ayh3%N+gJyycXU6%EGRB8WqkZT*(uWnpeYi8!2j^fP>I`DP2l%iy#)rFo zeQ@;VeDw06Uk{FPH;!!=AO3V^-#huxvIFO*J;$!C5BFO8U~b8AZ^5|&9~VBpKR5ds z!R?#)P@u674IBCpQ{M+A%!j>oxlbtDQOk#XHGQaC-G?q!eV9_&hgB7QI9c9@CuKR$ zrF{r04IU=5{$bpV@urk=2JW0Wb7E zFIIcJ*yr-%qQi>^HZML{yhzRT@_mQB$eZp($uuu&qDI z*e_maKY20#gBL5_d9mS*7du{gvHyh^N1u6d`iU18lDxS3&OICjX30|&g=xzCG@d%Re=%Zmj& z*oSRiOxxncm`z>`+~7sGbzZbt<3*EIUesFQMVVz@&2tlUR+kZ zIH>nxoz{z4YA?pm^rCm17cHiFQ9IU)qLaDL1TTJ#^CD@C7iUL#v3Z0ShGAX|AL2#( zL0*Io@S_x+lUKEbZJt^$u$*30)c z_F_#*FNPKOqJD@MS&Mk_tdJMm3$P#g*!LhWvghIcIlb7D-HQ=fy{H@Tz~S|P+#W1+ zdJt{*AjImyhfEK4nLHS2^q^*{2WfvjIQiRysXskvknDl=s|V*ldl2{0gNE-tu)Oi$ z^eYcPXZN7?GY|ee_F(TL4+cH(pyWLdUfl6u*)0!R-}JzH-Gg&iJs5x4gNheDcyrE! zrDr^7eu~FA?!m#M9`rlxLEeKNT-)ct#62FA-Q~gK?H=g1dQfY#2k$m`Fn^r~;cGnj zywZck%h|4_{P!aEV}S=@^SI4y4`wMIRM&G~jR(`>Jt#55gX_~ge4X(i$7G&sf(KFK zJV+hQ_Kox)bhrmeL)f-K9{e|e&-e47O&<@w_w>Nfoqg%bws+<@b@bqGdkl?OALvF%McevLRb4LrCX=0X3u9vEwTpw#prxVi_stFY~rJV+?-L6@=~ zd@03qmhiwC!hRL;pir;}+X{G4EuROc{_~(&ZVztd@SsCBj%C1&em*z8y4@J*bn|Oi zHzr%$uw=L~Bi#*GsvFvWZg_vYq5tWI|2y+5KmNqWKk)gt-0n5Ef5H8pasS6W&LbZ0 zK98H|#*5o-bVzXH)(tnBU325qWjCr_bYt5&Hwv9`WBy4uoX6Z4f5gqNIo#;7-;IPl zZiMf0WA}D9g15S%Y;q%gy&L`4x^aJ%8x2>uv1_Rtc^C8C3*7iN*Nv#zZk#c=QA+2= z9JL$&X7E_k-8di1$0oaBnBYe8SU1{?cH__pH-d(_F=4P9j|aF>C&rECecVXv$+mXq z^IhD?+1ZU@9o)Flj{CQ9Bd(>JpAWlHL%1=!nHwLPxKY268;k4n{Po;uT*r;2wfOJq zY+qG37FBZNV|gCCEZbkojc3K(s2Ji#Y+*NU7IdRvem4dNxp6c%`=7&&*4f-x6>#CB z*M(|s7p6E|xNLPHo7sg9CKuMEx$yp<3+4Z~F!HAhN4~pY`r<-^PcF=O&u!nh;CbnS zcL#x!}Lgj}u+c-sbZ+U2t6I_E&lAOD-He@51jhE>t+>Ld7WZa z_PY?d$AzgoT{yJOg)f_3D7?{ycI#ZwtajnV3KzaD2qD!H_L@rdKa>5 zT?mhNVQ`!a%ci<;X|ju73%O8moD0oHyD(ye3oC}YaB+|eU;Dd|yPpend%MuH2any= zg`J&UxYNOfzwKPe*T#iy^e-m{COa|Vs}q_}PAq)y#JV?5?0V_sYmXBb9y^in(20ll zoOpT1iBAbm{Jh~r>QyJqmz;2(cfxnZiEO8w$aUO_pd(J?Kj=iEeNGhK?L?6sP88kB z+Qfga=VNP}2wv$#fn`pvZ71?9a3aTCCjtuFr*p!pcEUKriQm(l_&UXjHxr$BGR}!R zqn)@i!ikeZo!B?XiB0{TSk~7GrI!=2-JKZT#fhGsoM;{8M8mdDRB6R?HFqMba3Vdz ziI0t)xYxjmvtdr`sN=-qT24%>?!%9LWy6{OZ8TPYx`3 z@4$#R4#<}d6o2MGMv?>fA2_fx(SaGa9q4q^flAl8&t(T5UEt$q9hi2?fi}mv{SgQL z9dO{vULI$c12NkjsJVsPZgAl4S_jsw;(3=lP?7*}7JV!kT+J!ohwILe*Aq7UzHGzb3pTtvV?)=IHrzjI0}k16VV@15yKQ_evZ2@( z8m(~S+_&QI9V;RdtXOj0iVv5q zsCB^#^%*PfovbX9|z0wIF}I1+}MJ(0+;qBPLidYm5b3M_6!S2)7x)WAwEk zTQ3Vrb>lfYTlik(77S@)L0k(9mI@1YMObjIkp=g{E%;E!0%J`J{8cR|RLO!0davRSaoZ^kya83*lVoHm>p*u)?sF>9Aw7a z7&B(}He+meGX_MP(Yb>evaOk)6PQt6no*z`&(X+?)NnK2)iL94O*76^HDgCbGZvRM zV_Hcw28Ec>F4&B){AQH+kL}9IHe@mL=SZ12=gh=rYbFdCnHZLqiMD?;QS)ae@_x&N z@na^QzRkqRmzh}kG!v5_Wg_}sCPHs#B8W2a=Sn8-T*$<(Gnvqx$V8tbnFv3?efMPI z=k`oo+nkAY>oYN7btYOZ&qT?^nJ~@cKC?2hNyo?IGlA)uC_IJRkI%$~(V18{oW~iQ ziR%3`Veg%ZyWKOfHaZhSJ7l76+f2AyWFk>yVs%6&1~ke#EEQ~i1lZnfja{>TLvy>W?-f<15N*B!0|JK--FCR z+@}oGf0u!bml-(rGy`KEWuVHv41B$nfz3BE(Bn!5@?FTl-P0M+AJ0I;!x>23mw`RI zGSFumpWBpygta`*$_&(4nt_iCGO&D31~|aTP-kFwTn4(uW+2PN44fR3fq^435HutM zm-=U5M4t>4>XCt~(HR)kf&Xrs!S6w5V7SOY-iQpGZJ2?Wunc4k&A`Fx8R%3w1DWMA z_`To^L=?-wr{D}I`7==QzYN^Y!Tqvi@MnT1zK)vE%3{LzbQ6>m6UzQJ;qrGAdVe+{ z^PLIHUYSt+nF$GxOo+K>g5{P8OK+G^`HBfw&YRHnvsl;^%B8?AvKV)2${v z+F-)KH71yrn=pH^3BmJC*geaHaGeP^XPOW_&4f>rOc*=P1p7!6<_tBVz(5l=_vNvB znsB^}35`3NaHFjW?OK}fM3~Sk!i0|vO&A)+bJjLte03hbk_l7GnP4kv!psm8T!l=~ zp;yzf=R!J4oJq&>>8P+c9joT0 zBg-rvUz?84Gt$vvYC0}XOh=Wm=~y`;9iGAI7}-A^PkW~$qC1b>IUPY!>6qF&9q*Bj z=8@?*&^R6W>Zc>NPC8!K;C5Bgv8{YM0;SS1v{*WB1*fBO{&dXCla3$R)6ptm#BR3{ z0hXEQ6%1oq0@{wG06ze zSR>kvC}osGyDWkhsqBi6%+&&`ae+}Mb*;YOScHNslmh^Cc| z(3LZSN*a+h#E4dfjF_L-h{Rk*jGc(6SUzD;QeTbG7m zE7P!UNg5L8r@=8R4b^pN=rfc1PEEu4iD~#TCJlu~q(KbkIbyhfuQVidO+#wOG=#Kc zTUw@Jj7Y<(rfg4xG<>a_hFrDM5Lz`2-72JEM(H$cEtUofPD66OG~~>~b7W6Ldw(j% zx>B*knu^1wR6IyY#h+iP$oV}Ll|QAT`P)@J?kd(Q8!L^ySaO#n_XABnQ@_;|4w&Pa=aTag>D}0 z>t^@PZX~vJ^Hr{!Y}syXWxBb%w42onx*0UPn>xvE{HApCV0<^5Ms+i4Xg4kYbn~Kj zH}`vVv*A}4L%w!V{k{v=S6y7{=wfMe7r$z|NU7*Tx44U4d0mXm6f((OIL38xIcb>(Iq(t1kRaySQx7#cZ7}y4AYyeB8yEdtLl{vx~YbU07Y{V(*zQ z2A=35L!pbO`?`?c*~RHq8G_K!{^KX+2{wiDIvPUg3DiZfTI@Go?-q^y&Mf=+a@J6W98DdKgV zXhwH3FRYXD7o9xv=|sZ4lWfOMRBSpKY2HbcVJF9QJNcvDiR+V25tP9{op5qubuyw~Cq935BKy08(r+CoeeB@Z>kbS%JDA$iL1@yuK2<{-xuY)a~LdLlRMY|4OS#)s6xPw1>9q4FwFif=rn+L+)?GC(EI+%a4 zgRrw5$eipT;cy4*_ji!7Q`p$jL9Sc}J7ha3l7 zpwR0p^m}%QSZ+IEU)x#mp&jp6?M&@x$F`}R;kE7PmbcTRsGYkx?YvHF=X7E_718Z% z4QnUiMLUap+HrGhXOv?*+ScuSGi~RBK|7V&?QB$QC;U-65_j7%zTVF7OYK}dFZ31L zS$DJ@{{!ue-rdgAt?hKlw+o+EJJB-j{JT`xn%~YFsdn~Bv=cR{ok?Tcc{aSA_JQqe z?%R%U&vpj>*T$8vZ4|t36TYc74BOjy)7Zwgnl^mP+UQ%@#@XyPl2Y54n9#=Es5VMM z+L#;AhL%?wjV^7huy4c2vW-sTHW6cO!(6kCmrvW^K^tbb+UUC4#wulD`%D|n$J<%d=pUbPDRP^<7=v=Us?%Ga`1Ru#7LG`p45)K>Z=w6Zy>6}^yF^88zc zkF1p)F0B~YiMd591B_eQqSuO+hLC^KN{{=ktiIXG-7BqxD7EtXR4X%%wQ}-cE7rSP zDcagf-wmzE(#ma_R{WN<(loD?QBuOrv{oKZY$a%PE3HEXZ9ppDtBx`mWbK@VtQq<0HzT!p-S3(qZE z2r(9R^ji3>(ZaN+Eo{2q!lj!n7+z^1SgD25Q!RWs+QR6AVx8SB9NOB#9r+e4WLpT8 zZlQQ_i#Xf2Fkog2Qd7m66I#SwriJ@MS}^P1LO`z;GJZGH@U5AzADS8Tx*5riW>z*e zv%995b7jpuC}_qos~MM+X2Rl{Mck{I>Y!#``Zn{+y;;OQo0(wK%xtq}qz#(cq}|N^ zXU&{?*v!@2&D>XMMpL;N<1@|J9&g6|P%{C0nhD?5Ou~j{(rG47rkTo?Ipi1tdf_9hYYY2s6L6CX;Oc$?qEtIQ@k zlbdLXZK5H(iK@URN_?8gb88~ap^12_Cc;gc@PFQfn`RR>Pn$5h--O1^ChlEn;)+re zil>^`ceIHO2bx&1tBF}#niwzF#6N4A__@4^?uAWM&Tb+@vWd{iO*oHj!eDq4_Xjp{ zwoengdNd*Pvk{5UjSPI-$d}GW>YE!$uWiJ?yis7q8o8g{$cfZOU0Kej_Wi8X2S7$k+Rgl-+D3`F9}F{u%UF^$|D*2v}ojZEs@$cO(mkp8^^>yHgw zdfmX9js^xdHPBeyKu~D|s`(A<%4}eAas#hp8i)yNK<7mR`@I{O>MCe<4MbWrpk~y- zcHIU>t2fZ_r~$7#4X9jeVEM%cexGR|^>_oihZ@+qr-2dM8mN?Sz)rS-6Vk%Y;s#ph zG~hnHfpb$Dm_DvS>=g}o3~b;`p9ZG&5YO|Y9*0l$9DY;JsLpzdo9fZ8sb^DJJv|HR ziOHE~Kcyq(}#)HBnlo?4xHjMVB`|EQiXx9jmzsYgM% zp8jX*i9S}3^1*t>?ye_uOFehw>XBGePto#v9xtqC*6e!9CF)U~RL|@&^#Th~&y#Ub|%ht}jeCXB5kXjmQc1L~;yTRhMIYWe-G7UK`KOnp^LNLwv( z4Yib3)^fVImJd0#JWZ=*P(m%Xk+sYWt|ipB7Tjyeaj4~hRV|IiwJ7V=@=?8(2ajv{ z>uxQ2*J>Gdu@^dv|3h86#XdC z52+=lUoFyq)e`ZmhNWL>2!30`ysjF2nro1(t--0RhVcb8m}S;5D7gmBm>PbE)^IzZ zhS#1ooN=z9+NOq`W;LYh*C4G`ga6YSrrfW=^hOQ6FV}GQTn$|(YB;P=BVM~2WVY4d zEnmYJSz&KQ4IdZQpg6mRJPDycsRsAaH4GVA!~Om>wEk7Yj{mBO_)^W}chzWhRr98~ zn*Fua#FSO@Z$UMhnbo{Zs%B?QH6fwZj0&jco@X^RPSvcosm8&yn%~c>Ij&hv{F7=X z-mB)p^=hgvRgP&My{W{xqmstP zN+wrViaT2+wz-v5rd2W`p^{yZl{^osB*UkY9&VMaw67H3)k^#gD{0fNWa6_*_CKgZ z?`9>*mn(%2q>{NOD^XOa6xfAIvbI+8ORkdnYXoh1C8i51NtLSP)6_~NCseX;WF=~Y zDhci*p5adg1AkN?^Ra?+uPQKUt02Ct7+zGt>TE$zslYI{f{3sR8UiZl?Nz~C z=L+`PRB+F<0*B`nq-a#o@wkHicLncS1-q0hxPH06_pW}T_$kIWdb)cVAc$SgrB$~BoCStB9cB^HQ!2E^u83y?o!6Il+wSpRK%%Ed7W2EeR?VR38lnGmf{~&ik(j> zx~`?%wJYVUc`17gguYfOv!0eR@?I%_u9ecQTuRC5Qeuym;=aEW{T-#;+E~g_N?9je ziqxV~@fk1WEoW;ppiS79SNh z_m|MHy@b#WCFsbOaBM{h3m2BqYgP#rQ^h*tOL#D%gzW=MnAp2SdyNEwP9vQAMl>F5;a}5nirEoU|)q zw0RME`bDT|79stlNW`d%M2x41gBObEf2xSM!$qjL zSpn901uRG}AS1qj;}HdXdQl+WqXL01Dj>wVfQ=>vRO=RSS*?IS4+_NJ&=eqXxj@`$ z3y?ovK-qx;&h8X?8w+?w0Yjt{$gwPAx!gyjX8|0fz?^(AKMftN-Qm{c}Fg z-sIE2BOjB7e8yGg<6M}}%&dF@lJZ#`oljJ7KC6B6Npj6c-Y%a^vwXJd=aZ+A&(6pB z6yDBf*VTNA&WrwJJ_U#J*|9sH+|BuHS(i_SOg?gp^GTeY&nk(0A|~XsXkYaG3W0*%>K*e*XLZ$yvY^0DY-0c$QAg&T>dM_^R#D3|x% zx$JYvCEO;LF{ZiP)61nwEf<-Gxme%K<=drP4xY^=>{u?t59Fe?q+%tFaB3v0tHvb3`J{v->jyICAk$wE^p zi_nuY0pvl!^4M zOb%VnCUJJ0kry)J|u&Nz8Q4> zN$35ybiTh!r$<*heVfu5T$RqqqIAY(r86Zd9m%M4q=M3!>z&R5=X4fZr?b>Jo#i^| zNUNqJb5FEuqFoS8QP30wZ?}-yEM(UT9ciJvP}q?Vl(O8&9MP?d#iD@K9rV$aChM!j&PEKi-y-N9+%4xh%Z|D_`H zH5G}ssSNB$9swT7P(YXR;A*yMDXXNa$F*nRTEMfJ0g|O|D;m%mssOx z3fdo21ZF3N)h#KEu1Votaf-k-rQn>L!oBDeb_J&}!zYE`&MA~yr{Haz!egBj_Nof{ zy%c_`q>!(ag44+qZX8NMZdZzk%cRgQn?l6$6tw22a9~CXl9N;TG%AJUK`9vaPT}b9 zWTd_%^Z9i$No~nIuS@1&Su+3TCG#>hnb6o|9)%_&@0ZL#w`9s}ld&^R7CBTxPc4}@ z_mc^^p3Gh4WLBL@=8r-$DZ7)=+?>p&waN6CP9}FjGWs)<**-|T&WubD}NPfkKICy;k5 zf%BIW=y5gyo1+OV-j_hm)&y~8OW=o0g80o(VCJj@;{Q!x@7M%7ha~W*ZvsRA#N+-o zUgUnpi@h(NWA*X8EsIArFJ9zJ#N!eh&!W(Hl6~XZ?HW&`O*~gj;`yZ$kB(|QqwWbA zm3ZbU#S?uZ9{Gdu6zqscVM9DEtK+$}G@j3M;&~(y&)*Z`(H|bq@PFd5=^4+IA8~lR zk7IUM94{K_uVu99&~oEV4Yh&YA}h(qVEIC}hy<=%%_-gm{K z)D%m7Wi0y&W692lMK&Rp(C}Dh2E=0L9?KB>Sk%m7`K%Yqd9_%o?#Hs_dMq&)VwtTN zi|wIU`tK6?g$1Z$vD&{)wfrXDnNP#1QsAhRIzq=rqRg zp(2LE1u-P2$1p2C2IH_8zWK#)+%1MwTR}68!B97bkE$^oyca`^N(_^fVo*I1L(72} zyY5F}b1jNyr6^{fjN-<@D57^n(PKjtn^s3* zuq2Ao*-?z07RB*#QMe3^qP=evv;IVK`D-MBZzB277RlneNN$xz5}p&um*hy6MT>b* zBw=2Wd~}Rtp=G4Nm__2J5lPp>NT%P6`z5fsSwHV-H~kH6p5B>B#Fx+`93$2 zMUs&yPl&{MxRB`|$>5%m$bXOE!Mg~Nix5FueFWpmBiNA_fof_5VKEVO1Phu^1Y4aW zcw`kpfMEpnnh^|o9Ko7f5nR3$A@E8OWFL;;+wKUaZ;oIu5jM1`2xnV)I5+dcu}uvpDJER38O{KoaDjgh7yi3&?i+^V zpczi`qj1`8hSTR#I8vv>*?KsfOS{9--xQ9&Y&dz#!g)0}oPQ+4nKdDtO~b=E*FPM! z9^p8B3nTVz7?tf|e5?y&P+1sKxnZnN3FBCF7`KDMF!Tz;%Q1{Zi!dtm!+4_}#@`Ra z7=I&-h00-UR1D+jp)gc-hM~S846D^)_$~<}es&mzQ^RN;8^)(0LZ@#SBmWo5^e>?- zeI1H?Ybg6_LOE3&ib_@}j}t@DiwMOkAQU(EPy+2ji7^c&T{n~>)lh2ghSGL5lsD%> z`Fbpr|LqH<&$dtouMcIEOehl;hB9qtC^ILAGH+Cp| zu(2Y9&G{j0O$%XLYzW&!MDr2NSZDHopyGNqZ2J>VoK78pMa}AZn6=NR14_??n)19zi^? z58{-Wkkt!f{<9!~X$j)T)gbE61(9+r2+w^%=xz<-^12{)Ne8iLfsmOI#FvRdRE!8B z;-4Tadj@gmd!WEb2C}pxQ2hP`idan`g*k!vCkLVv709{3K-PH%GSMNBZ)Sm%=n3Al zK(y`!a#AG_>GOdMJ03{)zCe<<24cM~5Ebb_HY^Ba!VF<=VjvkK0x7{m8iE$Mq|IOgJmXM+AM3ALBL)8CgFrF7spfTt8x_`EhETAN_{< z5!lC%1HXMm{)8`1FMW}3_NBYh7lQ&{7N+}B8tcoQ5MRdn_!8sf%P~t|e(U?2!f+y{FwCwrql%A0-zy)pR9o8dpauzcqw@+7=)sPp3AQZHPyy_lZlg=d5pQUP9g zyLpK`2QPe#MXxR9kG+_A%L|W-UPzqs!sU<`lXrSyC-24BRbH4c@?xlzm)PgM=rhU- z)d61o?CHg=@1DGQ>&f|cPa0}HIauOJL6#>Q5n-dTEZ*uaBSbr0q}@WAq#2Y=3cpmf}W z!hIgB*y@4fS`T`!@Zj=14@x8iZM+BeLp|u(*MsxF-O2gn&b*iIm^8Wbxx$@;`R+ue zx-&k;orgj0)OotI+QA)rGk5;eb?2z6J27|M8F$5A|bm!G-cQ!9^ z$8DB7f2O!|WVAbB1Kk@sCf+MIZq~VxTjGX9wi^!;-6#%sL(1QcC$4Uk zS-UaINQ^bzD1GS0%o}bzyx>N`2{)!5aO2iCH!{|_F;?1*i}T%xm2_jk1UHTia}&8? zZv6V~%GS@W*t~S5v&ofZm9D7gyHb?u%A^=ql!IIe_jIL)gDcz3T(Q)3rTM8VbMClu z>#{2er(H#!l`Fe;xni}!mBv-B%vkKo6)9H{19#=;NLK`K8O@%qWPfvE@LL!5wz*(g z<3e?j3llS4I2rGPOQ;L2J}yW)yKv6Z1y6k!I@Da4ao>gWDlT}O6a1qtOxx>%;$|1b zzj0Hu)P*r~T-Z0&1*0)8$btIz9k=h(bdL%m{8R^KT07ovlIbvwzNRW}Es7>O?=ZB7rzTwD<3yvH*;mE!H zj#zJXByz1I70Vs@GS`t25{@hy=g6)h!gg;*bbmSE@xg)QP6z7i9r#}Az=#|N<|jF@ zIl_U{{ti5Jb->)(L7Y_`NY@Z@4;=V%&4GbR4oDn#KxUr z5nxNGn=OGhw)h#@;;Cti%R^i2uG?a%WQ);pTXgr?qPE4BhuCs+nJt&**m7p7El0-K zvS*Mjn|j%@=7$YS-q|p#-G<4vHViMep--j_KjUn88)8GVw+&^EHe{IF5T$2>uc{4p zcWltVY{TQzHe6A#;rLD)w#(bFYNZXc7uqm(hOjZwhR?%*B4C;oI%BOkGuR5* zzpWVi(~^(xEXi%R6mSJg9v543Ak&h0@s{)swWQA5l2AuW^vo?$)U#x{swD&NSkiRK zlJHZ4e#nv&J1kiwC*)-;shV$zucRf9##^#;s3rgQvE;)q3sOE3Rzmms-#> z+k&D53!K6%xZ-QUDrXD&Sz1v3+yd8U7O316v?~_$Ib%VIf&~scEl`pdx+^XCZ-E8r z(=9NZV8Nkb7W~`Sg0BC}3HoTx-7a%v8_ellW=?LlIVOqb911sQqMtd<&gOVnnxm|5 z&O9}9KHN1Y?26DiV~)&WbAIhKCtlv1Co9bn0B(BBFehn(IjY0NystU``_GK{k7hjT zGGk?fnfTtD5uRStz{-8Ey!6*KytF(X;Qj0Zc- zSRyZEWz29}V8+quW(=QTM)puMRQs5*{6AA(e=xQ%Y-gv z6O2!qAbr4urmZGuuQg%*audqtnDAh#3IC2UA$_0;7ymM0$aiCrGil7BR%3ou8RJ-B z%(^sV+MM|V6TnYe%+YY=Z(=nX3U(ug1^aF;NOkuv&0y8 zDWN~vSl}CtdD!2WF@KB*{cOapmqxs7G(xl7h<|g9h)FVHe}oZl{fy9d5i~0!qV$c} zt!6~mT_aSl7%}FI5ib;skl$%UjhqqJWQ^#&zz91@BNmJ|B5jBf3cZblPtlO4?+qE= zVJN;EhO8(y6h1CPj>H-AI@plMUWN>EFccUSL+0riidr~^Y`nkxn^#tnRqe$VH^|E9;a*LtE(lOFpj^+?OpV_AwG9+7&C4$wo>RgW)LdYm=TqeM-Q zb@%iLyrRdXGkWML=!x1}f+wd(k+dGG=j-7up~r}EdOR7dM|Uqh_W#f&;jJz++jKFh z*5zk`E@#qoMeJ0UC4suakEzRFwz?=A=~ASj%kl@h*sBQIIbALs(ItPEE{itkV!2Z2 zF3{z~bX}6i>moT+7wz7Fc<8XlPKO|4 z!PnB^%0nG;ujw%Bybjt&b!gkI!@7++IIPm)$3h(ubI>7pf(`?R>7dj{hvZ+{O#GnD zoepgZYqgOo*5+A;HZ`%@EDqL2&r_QgJ8fi4v@zDwrsJVDYp!c!c3zvVquR*s5#x>8 zbgt57^&%lNLz~tK+N>BRbo*#i|4U0?wY7NGp+#w}7LvtUB8H|#MywX2gSAld)FQ%8 zi#{e=9MICj{h<~guW7ONycUK>wW!;zC4Bf=+*zeX%0exM%+TWK1T8#=YVo1B7OQ`0 zqWxZz;&x4O|JUSPktQ$FHTf2!De8x4irQA16xnJr)>xC1nwoe%(BzGZCQHw0^5BRj ziMurEy+M<$D>X4%ph>BukR7kd(IJ{R{jEvM4-KZj)8Imz2ENrA;=ZrJyfh6|qBRJ5 zp}~7M4HnsGaNSVM)y4dt1`DogaP^D^{t6nr+@XP#oCfElHE^A$LE|(HCXUrWVUPyq ze`!$oO`QR6)Y;ggj%uYkF?s5IPF81rq&iCe>NvZoQ*EivFnx8lK2zt}9d)8FsqdCF8HWn>!?PqnHvA;s4@468pm#`p?^V*xZ`TP+N;L+&1!63qsHCEYIw{P`V-aY zFtV*9qRc86CvfV|MtCp%5KUXD0Rh6>as(iVq%4kJZmLE{%;8vlFDwa!C37;kS zlU4aNLY3kDRXO?JQ|vmPQc?7jp|MZd>hTnHqo>5(f6C`GPnomxDW|2MVm<9C`2(Nw z*S9AuZ+^nX+$T7MKcUd+2|e|mu=v&!PM>%pa+IEsviJ$_Cq7|v-zRMU@R<9xkMT%< zOmX02{&G#HYuP z7=7Up(t96qc=aP5%y@+D&__i7d`MN>L%tR~WMuS17P&oShrvUX?>KN^!ogO2@MZeob`asArClV|A3oX574>x0Q(~k2$X+7%KQhEjeS7-Uk~{D z`aXRt?=w32KGXf~v((}~>!02ic)R-?+jn2=tM^51iTgYmc3<3Q?qS+~5BtJ@#!vA^>?Ysyh~lMXm+A$il%ax+QWCL zmb**kyt|Z*xl3`+yX3#RLst16QWNhG?{i1Q`R@?)_zvDmcW~Zw2dhcgn+)1Z1ld4u;auajMN9oK~GJn+8GUeoJHJ-W`HbJr=~bsb-s>pYPV^g-8|@$DKv zny!(Xb4}FXxyDt;Ysl(cWAKe@)E~Wu|AuQkSa6NaOXy39u1%lvoaGQr0#b8h2h#x1-|-nh#=?RA+&Z!XbNaS5}e zOUV0P;*;4W+#X+IkJ2Un?7l?6%1a!PyhNYDmk9ZGk>kx5>6d$vkg$s!bG%4zor?rq zzsP~37x^uJQPfMj$d<7edDrtI=C72IDOaXGK^awVWh6|MNq?w}(m7@N?NY{DTA9t$ zl<69vjP{ocOmDnEYSsl5LoV>!?gBQN7g(xtfkK4~D6hXjuelenA9aCcf0W4YQsP{R z692_2Vd|lTl#vn%_mtRoT8YkWO5)D0#Na7P0(+#y;*aM^t3A*D^z*d8IL~eC^Zc!L z9UIRFJ#ZNO6t6**CJ$ooujes92X1D@j3DwPh8H?_xU-DZk=PyiE}t@Iwx|< z&*4A*9E<-xN93EctgbvOYVMsCuisgLAv?>K$7jhse^y|{&Qc(AmYou!A1LNu&yd@A zhOOCW$P77yy!{!G+jvG`Sk4foaE2x8&k!)@3^PZa!TEou8P|0hlj76#i#^R#_tShe zIL+m|r)gF^Eq-@Ti(I#cz+7Z>QnShJ;go$Q*>LLLgDEtvM!ur#okkR ztUASr>8DT~e2O>U6gk|iNLr2}3&Iq|T|$w+wH3K?O_7Sjipa_-;yG85L8BG9_2(ot zT_;&vauSc&ll1pE$rZzs6yH6`(o-j~+o#2PfoDs!U>TVbAtY>PHa(lx7lJ!TplyQWR zz$1LOK7y>;5!5doA#48;2Fe~`*UTfB4n0EokHd^W6JKuS>o#Vrb0FIJ#vf&zVe zE3oG6A#PS4!YAnv4L*k$Zgxn--41d8+#&pT3fhW844rz2b^jdV#;1e0)*YlI{UAL9 z4~m+M2RZTVAo>>%620#r?W+$mY{o&>3^~Y!?*}kzK0tiV0XjktFvQ`2$R#*{qRIiZ z6%O!X-2uvHAK>SR1N{4YKN~vsqg=QjgQ)!kx$LJ@Z$Dpd?q|&L{m5+G&*268MP1qb z0^_is=$HGbEZxV~xP6T9+{YrLeeAfmkBg`Fp}BP*&P(W7z4!6%?Oys-?PY56 zUSxdtvfFGg7ar~9$+^9l@7#;;ioGQMyI1UCd+GYPN93yRVQ~5$roPz2601GPtM1`| z@*d9b-6PJbd(f2JgTCJA2NbP3a zu-#1ixr^DYyI7pJi1G9E4Q7{ zx7+Zj+=f-sHgtTpao=H7u`K_qz+KPhoR@P13%Itr(GW^pPe$;NEDQycG0bB65+=A)TE!@4Zg`<16 zz{)L1NNl0cz%6ur-b_yYX8bcYV-UERtJa&@`D`=uE^cPfzRkQ^CHRt?1-@@HnqN0@ zs&NytS(_LayooP1nv-^MEsNXM3fZ-|gs(-xaVsm3ElErbD zp#NOMhn6)Whh+`x!`AT9ehns?YmmOWhK7S{&|nR-q}EU{bPYFutQL6+t3^H0)tm@j zO%MCkxM{2w`8BKQIItRR+11RPxth!&t5N#CiayP&aL-g%A$!{x3Xk5vmtd)EST8XaBN~Wo;BlZ*tAlH>S;1u93Ug&uF?YMC(VR(X?z2uk+GB} z^NBPEl%#3hCCxQyX@37Jjc$KwMtxj?bIl6oq^=;sZv|`3SCIW^1$)n}pmxU!&MaTS ztH~?4*>?p$-z`VAYB_z9m!t2qoMEQRv3#(c@n@FfxNSL8moCSB;&M^%bvZt7mNBPd z8U6{&nCG>O03*@g6LUpD-?9wfMaz&HzYNd6mWf)yOGW*>rA&%jijDhHMj9-|==M_n zIk6OtjZ698{H5F-vy}ILmZ03Vgyy0p9FAT>k;@V`=`A7t#uAnsU4pmV5+==Eg6YU5 zBG-5^584;=CVw%C5sN8xT+9aT#YCtqW~Rbotk*84|E$H_8@8CPAB#BDvWWDYMWR;z zB3$eiF+^h#k1j8wYyTqluUSOW^hL}Wya>y$3+d6gkc*iMDGgl6YU_n~s4irX@q-WFo?`-DvpDnO?vq-6)#lVzV9Q2)qv*|3l z9?W9VnOWT5HjCsXv*dK^;8ZU*ChZKGWQoO${#nKZ}0+T02?0hNy zH(H9de`ccAIaAcQn@R7enQU~PiI&bxGOo=O^$cdRVckqLX3Z3}V`d6`;0$D2X7Dg) z22mk1_-s3ah3Yc|PHP5U`)1IxY6cS}XK--f42(WcC%bMsJ=3SNGGID4ET-f0cskAJ zrZZ;ebapPEj>hEaME9A_+qaTPR7#?dD2cw8B#B0ne7q~kbVWhiEQ#JiNn*!J@}`F* zle#6?SuDYmXbA#bB&gSwVBif2RvwWMwZJ8?oGn4>a0%Z3oF-~yPh(5&G;W1X!`W^c zx$4vSa%mb<_6z#zY5X5WX8~5l*MxBz5fB7vB<$`2?#_!X*kT7L*a(Us(pM3?ySo$Y z;+_#jF|iB9ZV~?$Hh%N@JUlDh+}(3#-g$pJXUA8mgw-~cko(maMGt*Z;jFK$!|sdl zrM{S%>Wj=_zPR1l7r&eO%9>xkXk+1vQN=!(d&dV^$_F>M`JiN;kF2}q1OG4|3~cX% z)cQVH=i&qP&l`_kd!zKKH!2?UhHis52F&nA;y7>ZP*K)& zsEEw)in6w6Mci*xQTjM4!o;*9oZow*=1ouNPI{v2W={;6?TOe}PfQ))iDj)lvAwn@ zjyifG@3#l;KKH<@OCI=k&;w>`Jm8Sw0iQ7*sN2&6{yGn|ui}9a8xMqibw}hwcUjxd z9h3LCWA+kv@s{1OeyBTkbaKc3Chj=l=`QQvy5nMz8?N7S!~JYGJl^7lS99D@6z7Id z1KsewjT?T~af6YQ8_fQ?qRdNISYL5Pxx=m~zt$CwQ(fT{-|)KNv8_<+PDHM-|Xz;l_+zQIW_;h)^-B}*j7naBI#PZlMq`WYR@`!3!9wBb! z(ZaaA%oTf>T(`&TWA?JHj6E`E*kkcHd&Kv(N54ROsa@?+(cT{azT4r+V>{&J*7TF*($p#tWHs~8{BkT6tz{uSOw~TFs%~~Vzx-~i-w}#h7Yy3CE z8ad;vv8b;#A_A?^xP~=M?X6`Em9p6MxGZAw$|5kcEXpk}i-&1tv1@o)By=f@w#~|- zyjNK~GMB%7u)>7fR&u?J6>PRz;qDwOY>cx)MrXtK#f?jvD>RWT;$)XxN^fhNeTVS>T-CMf^I7^fc_V|<=5 zDrFku#xi3}PBTV>;l_B}*%@SoQfI73ch;mJ9#UlEMGzb^U+T;$JDv%rB*awWU-ms+1CSrF7o9 zl$;;@rHEaBDJ$_W{ps+RI=KF&#jpQR;gLU7ecB%y*Xs`*tMZ48zW$~TXMWSXMZf9R zkl*Cq@Hd4S{ie-Vf6?o8zo=I9FB+r$qJ1{M=)VU)slo1_G%o2UWd;4DkFGzd?wcPJ zdGrVEnD&ES^!h(4a1;1eC(`H2b=K9O;UPgLFI6Los^ zAH^L0kCtWpN5@0{qryu6(Z5e0$v5XCwO;U%BEmjWM!k=;`EN0uxm-+7R~OU2(Z%HH zUrc^h#nk)W2a4JLf#$@2pzUoxP)>ypRPelrz8okb>+~Y3+`WkWeTu02$M-Z`y{DA9 z?`h${_q4V4dpiE>9bLZgjvlReNB@m@M<&hRk)y>ss(kw`HQw@;TE)Jl?ycTZSoya! z=E)mM%zQ&r)85d+&TnXq=NsDo{x$7C@tRJ~d`-E1U(@C4ujy9FD|&eL6+K(>irz-N zqT)uc=!@|y`f=?g{aOE#jK;ns6M9MJwlB%@;R`CW`vqAg$xo2{-}MDqzJ5*?N1l_} z)aPW}^Es7PdQQJSJ)@FS&*;B6X|l+)rV9kYB& z`|doUEnA<^%D5*quk{m3cX&b*o<63LS&wOe{xNm#@|dXNW2#^DhZGC8WmEqaUl)A_K>=-e@Fq*52=dwkZf%pQc1xBD%|;i z&L%vdJ?$URBIgH`@Unmg9V(!fQwpeBj{>stEuf;0_vxy-Py6TIr^N&BQ(W!))brOp zYI5NoIj*=zpNHS0>rL-brrAB3bMr2Z+H{xN#@r>}z`OLP++Dg`c!&1yxkIy)@6gcT zJEXbYA*VOD>BEuRlsok{t?qf7Vk+O3fWNrKQ~Fcbd&5> z-K3`@Z_|gDP#gL7&FoAZ~es=Gxz&0gta!jeXbYYsz&x)$uybcE3)& z-(Dl%W7p{Yv}<&z*ELG5a*f)4xk|RDuhQ)WS7}YyRSK_nm1_LWrw^C%>AqfH=g${uZ_Y&;vEU;4hFzowbuZGAKNqO;r3+-f>H=ktyg+fyFHkLu z3-sjHd0MvlJars@o{U3k^4Ob4`N?@SIXI6Rx#iJ|*XL;Ik#p2`>N)xr za*noEI!7U&&XUQgvy?UOEQJm_OV)MH($QbJ6mcP!>{jH`iQ&04tf~CpESHYoI78tZ z&ye-FGjx#7&;Z*rWcu(l?b>ykx+R{blJ=)*wex9e`7(!I9?YSc={Z!ldk$Um&Y{@i zQ{-egMMr0!qQ3o4(a##EXw`QnzjI9YmoOznFu62hI&8$$p*Sb52m?f)i94dV&_#JwcWK9H+w znA&C^rYo}!Q_p^f>0$N56kc+O-sT>nv5ODU*CB@}vB4oKEj>u-R}PZJnu9cR^g*)m zJ4o{^50d?z1GH$%0dkBzKucO4pbGY~eYBq(_wJ`f$@{5%@P3-_x}R)cXVI*~S!9`! zMHxM^$jCQ~l0Rlri6N6>=48_Q{+TqaW+pxUzK{Bz+eg=z?4zKFeU#I1AGI*rN16G1 zsp{Ijv?g*dmG|FE)649o-*@)VxUGBWMeH8x+iDM8vfo4WcsFJ3-A$EJcGKeE-DK{z znnf`xgE4_$qurL z*g$jQCRo_h2 zN;c87+)eay(I#p$WD{+!zln@XH&WQ;jbvE0k=#dZr1<6=>8ANcs()((&DykqUXI&9 zf!IK+Y&X!?2kWWJuJyD%VLchOUr+s<*3!{3ubu@U=Iy%~A9obe~M-lJW((&VK z$!^A48rplUy|-RW zbqW?y)Q&~8FMbgfw^>B>9Od_?3u#a0LVBONkZN^WNF&`B($+T%==qTa`ohS2Q9_<)1kDk__M{cEasr%)*G;`Hl z${9JAel(j)_08wfu$yye^~O1Lee4{vq&cLsnL{xJvuW#&*>pdCHrckFO@WTHDfa0s z+Lk$s?x)To>rS&s=RS*~-^`@-M`n^-J3~exGpT{^Od9-g1}!kmAf7#gKJ=SGo;7Ar zaLIH^$em7G7fq)dgQwHKdef=S-)YqM(lp9gIgK($Orr-)r;)kYG-_~TD)rwml`^8I z(mvf(x?6TC8QssIn%gs|`-BWiY@IFb3wYBD^HVolQMz`9iW=$}e;@21eG*c94omqJf>CzEG~Wa|AQiRMpA zqVt|fWPCi4{CXwQxK9bReQp93)=VIWa}%k3_(V!Bji=02@${@&JXN?kf!d9oKohMe z(2nhKbgy+BSw4xSW+|~W%r%x49U4#EZ9Ekf#gOaF7;0TLhN5%E(TYLi==9IA^nU4B zs?caG>GGo~VstdkvWTXvO;L24qUd+Q81kMthFUw0q2Za4G_zwQ?S4I)u1pzC#onW- zT=poc*LM_k`8txK7L26Xbw<+8^CRfo&=K^^Xatq68BXqg!>Q@*VbnEd7>%+WM(I0; z((1ND>EP1{x|AA0&)g#D$Kh})*CU*&6b~W4SwpCEwIMX*^k9k$9Zb`Ih0)4oVYItZ znCR0`x;#3R9$JJ_(WXK4n+B29gMs8SaUfN397qi_2awir00q77Pd%sfr!epSH0oqO zitW>nQoi)1sq_2N+}eF%6VZn@{p(FTR`;fT&3n_qo4x4h*j{wfx)-VKJt?Pk zPs)89Lg$i0D9F}j4 zw0}ew+HKl}wyp0>8v;7h%DbItQEVrgW!H()cXyqu&fgCXyTJ38^^@CfH$E%iPk=~L%RcuKQj|bAZUV)VP3AAD^XmU-^sIx@fhY+>+ ztC9Cgjm(>B^!}QTu8+~tkuo}3wIzVk0s|=gp+B`v@TVFT{Hbh~9~E`c^XiQ(C8dJVi zW7@H`5v8|mL<0*OQq#nSWb4$BUS%~PL#GC`^i6#llTn{q`P3)Z?0Qt(ryia8QkPcD zuS-$2>r%_SI#eN|4!tR@O(#~>rn${(Q`n7K)F8SR8JDd^H@4QKO)YEE_`(|0DzOHY zcd9{8vZ~X*PSq*pO*IP2s7B5{)#&-js+8HMDkXoZLha{QA&1&k=;67_v^~5s#gtYe z|5cU9v{@y(eBGCpMETM{D_^Rz)rZ~(`p|)g-jtBwO;o{~%(A@bLPsx}_qrm5OsPmN z-W93fgeR@*?MXvEdr;+h9`vfF2W>y=PNRmnQ?0*l^nQgK?QY^mk=In+n(+%vlsnuPwn&V=-((iI$~}|Q5(xqWvv|Dzh_JH<7}yoy)FIR zZA1Io+fev(YjW0G(?xe{Nyc{#(9lJ06s1B@QK8tKe_i{K;Rnf@5E_s{eh~##R5Uoe2G;nJ)WJ>vZL#w#4kC z_AsDWs~r158?~!Q%Y6D?`|A2$^Xv9bOP&5!%TaGMvy#_ZySlHn8AD%b7goR2%HDjT z1($uH&1(5vyO8iqE0gt9YxnwzHpT0ScBkwzKkW?Q#EGT7^Y7wGJ0A3m95PW zJgFU;ctR`KcU&udc}%NZ@tD@W=TU9+>?7LT(}%UJpNF&?4Gw8vM;z3g)*sNC-Py18 zvE8ptY?GxeOU~4e9N4Gbdb?Nq;`mLX zyZ5(gpX|43HXXKVRrOmm9NDb({jf=ksj^9%Ibfrw&&M#f66pity zLK^q%?XK!@Yj4AL@NcF^`^w$t`hY^&{>-CEo6v!%9mM4-0u zHfd{HYud{F0ooF8e{J5}7TV0;&9wAUO|_J}jkO7F8);Do8)(CP>uZDN*VTIdt*v#8 ztfjTQUqfr&zPeWDa8<2R6X^}po=W~P8ay{`+)?n(fw2a@e8kSiD8&d~u`h$<}qcU6WVq;s&kIX?{y}7EX(FSO1%*TYh=A zE^NmPUA2sbav|^b*p;~(^az#(`DuM)%mCN(4A@AN!RIp zTixwV&<*PEr+ZPpu`cpL9o^?i)pQ9hd~~HB-E+gQhG92>(1K;L_>nfEycn1>8^51w0;D zIpC##*??OOpZP!fkm-LtB-#JPC1?K!c0qndMw4J9|9=0|M^a+k?ifoa&2x>c6QPS*`L#= zvs)MGkyZ9Ww#j=vGJ9OjKK53RZL4l)N4(Kv$+HL9=C9>*YCX$d`%?B}{G06BFZ8H$ zqBuMAnI1okzh&2as>g|--`Oi4>*e0cMh2rtvOh(phJg>|8ee-$LuP><^_!G6{J5t_ zNgrE7^SgQ+OSU(Rxvj^9^^S(+H|71#I2(>%*Q4;2o8kIZIi6)J8XjHIqi#JP!?R0z zxz@3=;o${6hEAwvxSS{Nv!bTqz*#-gv+EerI-HwIK#>5dK@g1VA!3Z zM_lb>!@|k`zb-n>5S1q1``9EyV6q-6DBVydL65QzrWo?#^yo2Wsv$W>&dc9vhHBAz z+?Y4RkT+T$_nBn~8=;48|7=5%Twgu9)m+2a!Lpw>=NaA()XRE$3k?1G>2dAbLId~G z%YB9x8$5dG@zZ6gA*zcW<~x@ejs(m5_^&X0Z717HD-AVU%ijmCHuQu%uV{^7LV&z3 zb)8{Ob3Lw>+hADLSjNrzjfS=L^_bIOvtfB{J%;3LF-)&6$Fs*aLsVrMAJ4WMg1lvX z#O^eBdgu{vw%hQ+S@v`39>Zn_nQvA18TyvfW73gKgK1ekeB19gY%$m4+c$ABPQ{f21L7=21i5moyZ*9XB-pn1-IaP8im{OT!ueY{So&X{d9_VCW>* zkzk%@Jl&uu)3LsDK@!=Ci!VNx8|&&*M&5g)Xg(Q<;u0^hVzDG zmTS#BUo_}Xq+wd&B}1ZIhrT)LieXe%8jk+WH+0*bhTOT=40X4q;e5p#2BVE>vPS4l z!-dspIIi6`%vhF&tyk_Cw1sJyIq06@?d&uR{cztfds-Trr#>)Lo-ChdTWHvyEbp`C zk)dgP8dB>#F=UNPleM3o8hj(uaHr#Q!;E2Ra-GBr!^^NV*hIcEwCJCPRli;v(tD=C zd)8Y+P8a#z?Y-f$m*Klj8m71WV>oRg*V|wFYe+Xr z!;-Lnh8Dk4(RQMddif<4*<`F{d`Lw-3lru0Iu)z0n5g|vQem>xR5dF|#jt^9>cGuZ zoUUxHs$5Bh$9r=%=UghH4_K)8EU!|-4rr)dlHEII_EvI)5}p`l>4{L#Fg7w5XzXZcl;Fzbb0h`V`DLTUCWG zPr>Ke)l|dzDbk}_U45IDf?cjPR90FF{yeIohQz0!!`7OrOmqt7M%Gf>hNa+g!`jM! zPzua`)KxY`E_C?8Z|FmW* zU2dj&6(pn5qUNge^<)(FX`uqnCnKw(pYq{kjCt;-{v1w*?@oVpWlu7$MhB>+ z(q|FhM5jVlCBx~LPFXHY#$MLcf$7PhsiZ>El93k-^)4B(rm zx}}Qmn~cqaTdCJwl3`h`wd&F~8AIQZ_X7OhTmz{Zxim5|;b*R~H;ym@%rv zLcV8clnR!fm)*Y6YU#%WS;r?@-FcpX13Sj5a`zHYW6U@ea5(`>>c^#;Z9y60k8bRxMtWfH%50wQxZKsu@jC(=rm!|I7pxlaPR^)8bW+F$uCB`9xJ~ zZ~~M~g8C7XfXi1CRCfCWTw9c=CI(1PO|K+Xvwni~OC_u8m8AFPL9!a_oPhLoDax#D z0(uWgRrCK&gin<;W&dd+p1w*`GhR%@ik*7({q96mYBos?yfhJU%O|O$Y9dbkn53)@ zOhlRflU4Vv6A^rJvRbfWB4&7|tFyD^@ziwnDQzOYK1x@P-d$bTkpWax+xDh7-Y6rz)2!6Olh{sw#1o{+`!U)n%)Ra_^dHYUQ7J zJl;7?4fq(3g0j<<)3bP7i=3`hFY~J9&sOMs4DB@ z(XHD|wPj&Es_mbtJTl_(z5FaSBVPK1#?MkkBjYja<}B52Ks-7&nXQ(0j)&#a+3FFb zhv?gE<Ub_t-BwJ%#*_uhbC&cP6)sSZ zk|!WhTd0;tO+ew=g{r;uAn8gMst?^J$UOxXshO=N;I&$$DmIybrrwLywyG15s$ZvTR;%a_v8XrE8Vn_*fhp zv`*~^k40C*I#n(t7LPsGtH{>!`jqubHJ0~%uwGeKiA7Yv2GzboEMBhKpwi4@(dX9& zwMTlZPWRiWuDuwK8pk)P_qWDly6YzOCwDxaOx&c*4olC~-A$6O$3x$2v-+`QJkBoN ztX^b{hxxb7Dlcw4&~uC0Fmyb|AKaqG^&F4&4qH|8HuAift?Fyz@pyS{tJ+a{ywo|{ zR1e4TaG1YMeKi>m@8WH0&gU3Z?Yv#NKa=gA?P~q?7Mej+NV}89EYgk|yu&b}VxI52<6b$KuY4L+VH3SiCGbq#BGIEB9qTtU`Os_P}8^ zrOjBpvOl8MH5!Y1(MMF4&sdzfd_&(VlgHK3)M#9EJ)xo^qY)i{Lb>;ghV`uz zN=eV!hK46qzb4VBKmVk9?;DLHMJH9PT{M~nXRFVDqL8^gTaA1d1z&T6x_vhav%?L_ z?`)KeZ-ZKVAPT`1m3py03hR=TsyjCd@9!!#CMgOHnzGtBA_`*{vC8img{>c1eQp^g z_gp%qZ0bkh@6J=IqGy!!gyyKKR#9j^G)Gk_8G{ZvIm-R{7=(D8R+iVspjYx~^)7o1 zy5Bpk&h8w8Hcii{Wy_=oZqXSPI%N!;KAurtgrTux;X<8)yZa%M;j*rAdqYLVGXe8bayr674Mk3_+1?AT~5{I2Gs?f@j zupfU>CE7(IBLAYA^Lw=1OX`wZ`g$}zO_S}-(WvwMlA6P#F&LLs^6t@?z522mynHk= zzh73mDWh>QS*$s~(Ny_cQs**h?PwzN)rc$@7!1 zs@C5|Vc*@W>h6o;M1+HeFYZljQNz z>uRC&^jY=4pG0W7+$+D{sZt{v_uzewo^+?mZF( zrFWER%aL&Ge^(XM9*Ne6@2VZnBN1tTPemDz#O%m>s%Fs$Y(95S72X+v1HSjw^qdhm zo^oH++%p14@7`BA%SK>tqXN}^@(8S+TcGYmj=-ch1*%u?5g63^fw~wt0u9$aP|a$O zz~3Ja)Jmrj$O(Cv(F=sq0YQy!~%0mCu3@Ufa-bvQmZf1+mC4M*2SPt?Sp z!?3yNi3)u_OpfzY6>w!38f<*3?4=iR^zWzY;f7&Y-Rqg!Fl!icGoPvc(wF$$>bbHG z9fn^K&($I6Pb{OJtDe%MSkCo@dM|y7WyilziPEcBdg+BKm43yyRbQ%P=~=v_f2oS4 zZ*j~0m#UxiE>39tN}ZJcMcv$2s)F<|{(kjJ4U;~`{eiF5o~}bNXw_@=zQs@&e|@cd zD-Fe(&Tmu~>!GN({f&zK8iAumZ`HiQ2sH2iR&6{Nfqe(xs@<6p@U(rW_N<7&Zx$Fzgwh| zABW35&_AfU=fe>{^MksZ6^=>IKB$D1;g}pytnAank+`H-Z5SPn5g&?GwUBUhYWGoX z2?$4x^&gdcm2mw2{!vY{3CG!P|EYIhhhXZ?|5V$;A<&t8QY+35!MpyS)YH8~Fz?_e zRcYA})U^4m2BZza$)TUstl>lCURIyg{w_ms+UbkB)@+FM#e7jOy@p`Rxi1pOrT5bN zt12lTj3E=hs?T=@WB=8!>ZKZtAJxC9tJ?;n>7;KeYu;dty!TDbj311}4N6r1(7`x3 zqeS_(8;na&O4O6OgK@9LceTuEFdi=WuG;(!!`(OE)!P?gI3M^!O}iY1tQ9|$+o3Sb z`|pR^x;hNu9e%3nQ^HVp!%wwwbQp@i|5Oe=q+he^FO}>UhLG*Q)B~R|d@uc_8kY&f zqTavNO8J6^iPE{wV*gp;&$Bj~X#26lOMm)$G_%42$@yw)GFi z$rFFo@s^>mbSPD4YJ?(qRH-^^7m6vTN|h=Zgaa=BRA!;{YDWK4%X0_e%h`V_e)k}x zmowtdiw42M--taD2Vv?kBYqk-2>%us@w#?{5SMMlA$14g#cLz}=Qs#m9gTVOuYovB z#!OEK!ez8EU(XvT_s%iq0s98x;wfV;Trv=zMaJAaS$aQROgL}IK&$q>qyCtC!Hm1* z_D9B7Gj6!6KPGsav(ttwPVgj4iR`!TEh*>RX049_))n9m{aRioWoS zFT>VpeX(&v8EzcW_y5;Hb4Z82SpBUGkFMJn_C8je=+Ia0!)V2mzW0%9?X6h6-R9A1FNrA++lVfgnE_bYUBFIJs8UJ@1A||V|-c8^Xmg`ZCRe<)d#70 zWx0cCAGx2lJpQ^jiae}&`{my7Y-i2E`+K9^IBR~nv^OGGS#v^CZ_LiMW|Oeq*jjAO z8LfNcgsTmgR_~1qt!#LlO>f*BW5f6V>xH|^Y}o&{Y){$n;^Vz=?VSxjm)_R16>Paq zdM_L#TOKpK7uJrnTOOVcE9)+d+C@U)i$z_nxq^FUJiZ^hAMQIS%BW z*c4HY+i&iPVROrI+vz<~`Di%~i0p|6Ps(wvu01iYtR34m?umdVcKpG)C!P(m<1@cP zkTKnk7d#4q?|wV(bvgvc3hdZHdSZjj>^X0y^uX4&=eVd4Ss&P*UAu?i;Us%L+$2Qq zi*CW=i8@yz@}Sy4%*fOk%{H`(99k*Up-n5W>H2Qy8(M)2CwD`~=@mG0XgBy}Rp7+--Qat_0teLU1~U^UF0tu`C$*e- z$H%TX8sfw~Zgjg|pyTUEsiM^A$;(mz}?;O|_i@lw>Hl#1NgEMdS z?TV6d&g^2=73)_z^JMAAZF$<6U!3oPNAH}Oc6UL%qYE#X+Xa?77cLmvMXq^wVb302 z;5yfZdpGHV6^C7TrgIlKJaXZKKRRQ&g)84K=!|dmT=~E3&KT6kl}*-n#wook+fMF` ziaT7{KB6;XueoyBww;mt!kKfxUUn8 zPP=hi>Eo^U&W+2A?}T0s?wlLa2^0O@IiYDMEDm?)$}XL-W0pJT{pcvYSMD59&=IE# z-1*1JjyPxH!5M2i;!G_Mw$gXR$sQg&b#O=N4e;P!Ejwc6CJ!D_xg+!!J@~R&M}&R$ z;99SO(Zb!6^3V-s=E|Y%iXAyaUpndvTXl9q_WOH`^z7K-)&%d~tw0 zub(%k=sMubByX->u>)G}kiY+JkC|7!dDx@&xK!fJKUI5Jc=>R~`t}HD>%(Oxwa4f& zK5`t|WAS1i{uS6BM^5XGQM2vSv&l!@5_@;w}WXPU(Vmu4i;&? z>@=kv%(nV+&xm&TeaV++x0c@G&%S)Jay#60tHjSu+u>wjB{qH07Ar?oV$a;Rvd&N? zuDhkJ=*mjmJfkhjJ*>ojL)+q}No8)_rY#oLtjyJ_v_;2mmASl`^cu%k=5Np2VCUM( zeEm!tbj_{ITQ|2s@w>`Aeo7lmFJFb5N3?-^iz@uBRU2#zt-`x2wLzV!Rk*)N8|>L# zg^ixIM%5ctctcKWtoTudTWo9%Gw-T=eo|{hwynzD2e-zh$f|q;tx;uBRqo{7TJB$4 zl~rjgD^{yJX`q@(Mxn7;e-D`>7&8qW?qb(6WusR=I))FJrtMj!9vfWXgpZ08tA^Fw$ zUE`MM`L#M1NzZbidkud5DG=2HYjDA}K$s7&!DllA@o07p-Z?K2S^I17w5UL&+^xX_ zI|ZWU-x^%2b|8!@*W~}K0&%QEP0oA+jEb(wBk};JB{kV)8*u!1O+J+Y^m$y9!y|x? zX0`ZFOJGv1T0GweDBG z17sUomy7+R|9MJXzVD(#za4cs`&$6oT&c?|ZU&&{=eiuVKLD04^*CUD03HR@W8>FH>+#L!{@DAap5$SF3~;T__Urv&s@3N$DgM|x zq&_$7?+;9?&qtg4PvmDc+C&PTpRGzy?%J4YrwB(`Jvm8 z2Ha|-A5Knfz)Rcu!FyK&eky&_Dftb!x{)7ler~|S3R|F(OG93Bq6H!Y8uF#(EwDGN zA%Bf)fwxl{vU86X5;q%igZeGd@p40MZPNlV|25=pZ<}Lbg+|=#TyyMd(TGDfH%Ios zMjSk;Ir1hoV*f$Sad}H4uIw*8*5@0snM-q=Dr&@!zcfRpePcd&tr=D{Y0Ub)&7=>$ zF}I!7482ksv)PDdsJWprpKRR>C1)D*7@uaye%+Xz{x(IjbrU{zzbTs3Z^9u*n&M@T zCj5F)Q_PQV!V|_eMdMXX_;<&qxN2y^$u*i{*wZHb#jGjhhvol}zp*?9c@E2SA+KS1 zE#y5|-V5@cEbk5Z43^J=d?w3hL%svccY%B-mhT4njx665@|{_}J7gbN_64#}Ec*u8 zN0xns>@&;0LyiHQd$+0ZC7Ls#WaxWwYv*cn(PG-r?kQ~jDt7Sdcwk)|DlEYbY zIV7jE13qUjhi#C901Qx9T(F`ow0iq#Tv;;&`uxJa2#$eGJ z5Y54&Js=u{MTjIuOmnqJ1D5h(!xQ zG!ct7f@mZbtpw3bEZPa8p;)vOL{qV7D~QHo(OMAA#iG3+8jMAYK{OeQHiKw17Oe)+ zY%JPM*18H}(Q*(?$D-{Z8jnTmK{OwW_LH@kgIKg6L=&=TLx@IX(TWhw$f6w~8j?jz zLNq0dwuER*7Oe@N%q^4l0Eg&@pORWK^Iaq2BNDabLi$H1;mf8eTqp;K}vMy&Amf8hU z!?4sckeY_2wt>_*EVT}#=3%LQATL*eP!La5SCgPQWLY(#*iAB zrB;U2%q+Dtq=sgxr6DynOKlCQu~}+uNX^YsdqZk)mRcNAle5(3kQ$w(R)^H=EVVnN zhG(heWzCbGEVVtP#%HPZAvHfs?GNz)SiAsPm#im?HvsVnSiAy=XTaheKs*E%F9G5y zuy_j)kAcN&5MAAi#e0Bw5G-B<#FJq0CLkUKi&p{hELgk?h=;-AWk5U)7Hsc?AH)M>@d6>9Ad5E$@d#PGLWpO`;vGUfL>4a*;wiFtix7{I#cPCkjx63I z#Diqx6ioEZ!%?17-0-A)Y9U zHwy7cS-et+XUgK8LOfI!FBRgcvUsZ`9xIF2O5(Y)c&{WLEQ=RQ;>ogjvm_oZi&snH z*|K=IBpxn{mrLU5vUs~B9xsd6OXB&mc)uhbFpC#V;t8{O!z3Oti&sqI8MAoDBpx!0 zmrTiiVJzM8PU69{c=05jJc~C^;?c8s^(3A>i+4}r;j?)8B%VHtw@>2nvv~a^o-SO^IdVPPXAjD&@ikT4S#c0$5X zSXc@PQ(<8%B#ecHwU96u7WP8IU|3iT36o)AGbD_Lh1HNS8y0p$!f;qv4hhp?VLK#@ zhlTZ!Fdr87L&AVqSP%&lVqrrhjEIF5kuW0`c0|IESXdGXQ(|FDB#eoLHIXnU7WPEK zpjcQG36o-BQzVRvg;kL-D;9P|!mwCa775d0VOu1Oi-mQOFfSJNMZ&;XSQrTtV_{zH z!ahkDC<_ZEVWKQ-l!TG8uu>9c%EC@b7%B@(C1I*8Y?XwuvanVX=E}leNf;~(izQ*Q zENqs9(aLeYPQq+i*ewaeWnsA_OqYf2k}zHt)=R>CS=cWL17=~tButov4U;fp7FJBc zj9J(*2}5RK$s|mfg)NgXW){{=!kk&yGYNxcVbLT^nuSf1FlrW7O~R~M*fj~mW?|VR zOq+#mlQ3=;)=k2^S=cuT17~63But!zjgv5P7FJHe%vsnu2}5UL=_E{@g{_k?b{5u7 z!rWQdI|+klVeuqPo`ubmFnShNPr~e3*gXluXJPpyOrQTp-FtvnQN8WnduJzMlLQF8 zLy#gh5ISVf^UxA{4ZWp@1ky+&fh3zERa6j>q5=viiYO>3N?BOws5AjZk)|LBQZ+U> z_cMD|2>##qJKy=vxxVW<1CwXgnl)?6o?T|G`*$z&?GyU=75e%Kef|o4|1^G9vVs1Pz3O7J{IOP|!vYG!hD034&%q zK|4XvP$+0A2$~87Z3RJNp`f)OXf71A7X%H4f)<0I$xzT{5HuPJS`C6`LqWSi&~PYd zIS85#1#JiXCsGx(9t6#Yg7$-;0a4I`5HukQ+7N<9L_sS;(2OW(M+h1ceBXRP(3B`> zO9&bh1+57|bE2RR+f<{O|D@4!?DQJfX8X^TP5kXU=pe-V3j1;s+1kI6x_K2WCQqUq1G)W5DB!Wgs zL90a2EGcN02pT2@EfYc0q@ZmgXq*(ZP6W-9g7%4^fl|;y5j0T>+9-lXNCD-B514>v{nSom4fz)putkmVi7c13fe4!MoU4fMbK<1XtxL&E(I+Y zLDQw6?ILKr6trFh&6k4qi=Y8h(1H;(VG7zXf<{b1D@M?aDQL$C8Zref89`H~wvSsy z(3mM`%?O$^1??F@gQlQGBWThTv}sg#Gq!iXOwg<;Xx9iDHr(GY5j1TI+BSm5O+o8M z(7Y*V-v}Bw1uYyw6Q`h!BWUClv~mQ^oPu_aprKRH(t&-=Qqa~BGBg z;3;VF2%0qyW%Drg@G8b}2#Bta9Ypp7JGBo(xh1kI#^ zc9Ni>RM1iqG?fb4N`l5xL2F6STqq^kP zDrjE`8dwD_EI|{ipp7MHWEHfs1kJ31c9uTeJw-uFOJfgX`}Wfb8e6seO*cVvtDwCl zXmAy@xCBkEf;N|+(N)mu5;VIC+FgQ%S3%25(DW*3dkGp}1+6bZ^Q)l!C1`*Zw7>*S zu!1(2pb=Kk3KKNL3ff_UhFC#MOwbf7Xp0FNV+E}-L36C2Jtk<76|~3%O|pVEnV?Zt z&?*x&%L>|Mf`(Z^%S_NTD`=Yu8fOKqGePsLpnWE2pcS;x1WmMpHkzQ3R?tclG}8*& zX@Z7YK}${0R4Zt!2^wn!tu;Y&t)RUoXs{Ku*aS_sf;O9=(N@rE6Excj+HHb{TS3cB z&~z(ky9pX^1+6zh^R1x$CTPGFwBQ6yxPmsEpb=N`<;H{I&Qs8i6Ex%sT5^J>TtQn- z(3mS|%?X-w1?@ROgRY=OCuq_YwCMzmx`I}npjlVYt`juu3R-r8rd>hXPSCh3Xx#~# zcLnV`K?AR#g(qm@6}0gLjl6@)flC1dYCeR-d5RSJ3VgH2ex$euAc7LEBHz_$z4r37UTe?LUD5P+$QFOn?F# zKwtzESOEevpui3g7y<>BfWQbFXz~@<4g%w$ zzN0z;#~(h!&$1-6F3*eI|zc%I5vU~dQvjslBAU~&}L90H@G!0Hf~ z9R+rW!0;%rJOrjkf$bqMJ_@W4f%#Eje+Uea0t*EHsR9Kyh`jDM#iNHW9uuudhN`Z|cFj5Mv6oHviV5bNSl>$peV5$_@DgtArz*-TQD+Tt7 zz+fq`SOg|Zfz2W?S_-Tdf!R`Ew+IZEdLi&wKKrnDX@3&6)03-@eD9|3T&PMMo)p&Gr;UAuzLm= zJ_VM~0MndVE+s-fC?<20VYs^4K%glE zjtZ=!0p?MGeKf#8DzK0Sm`DXS(f}i=z)BjmYPuEJNdpX}0!wLtsZ?Mqjk!;{6hq@KmO#=+40?TQD=|sEQ3ImL%0_$mj`BY#( z4KSbzET~a)2)3KE#8AWB3aqFBW>kS4HGUrJR$xgDFr^A?sR71Rfi*S2oGP%V1{hQY z7S#Zgs=%fiU{n=YRRheb0=sHBbKMFos{y7}fo(OwxGJ!&#^M=n1@_ed1FOKo8aw8? z71&q&Hx(ckW0cKZ$-8I1QDzLl;m|g|8*C_M0TY>d8mb`=O`ByIk46p(VY=8+?V1o@X z!m7h!Hoy!ku*1fxk8#|6IvHS!71&~}fN@q}oeeP03hcA7?1Wo^g*L!ME3nZ97-Q-R8U0}QwSZ^1YZw2<-)%_Q@0t@b%dc&>2hP&Rl=~iIHU0}u)*l`ya zas`&$1*TkqEq8%2S76Ou_wKqC*mKuU_pqNCi(FvR71(qa7@NR5+<4B3aeaaa*4>r*C(fsAZ&&%h+zKqb3rxHM8}I7$H(r;q^q9F(a4WF(ptbgaf5Fb8t^L@-0Fn^BuWz3T>x59kw0a$s=-7%jB$DfJ$pTFH)fcef}ZXS>M zlRw>D9rFb6`fnGxF|L7|t70Z_`eW|9IrW~Kr`*L1E=SL^Oxtq(0}jdxo5$$e}nyWVoA>T;bM{AWuKA&xKirCO zx!waq{w_H6O{n87@a-Gi7*hv)`fFh2*MR$f1?>1raPrH*gfDe-qvze+={YxdUFha6 z^WEHbjvJbGH`}JW`Aoi>*XMzS&vEk;nW#6-&AG{Lu9W2FH{x;pF>ZcmJl2hIV;lxI z#wT`j*dRAA>4$N`dSRTfFx1)A%?Sp${!U=r+qwCb5WF5O;3v=oUJ4D}JhmS8S=-I_ z>NuB5ZgvNv-T<6$DK}4cxY_$*Aus&1ko|uv7VAY60p$E z7INtPLOwIAkS7%u^1a+bctIEPwUk00mIy{XrjP^274rBI;Km1|p1y@#E*xxmmqL!{ zT*wpJ7V_j^%#E@91oCQOT@{oGMA_2V#({1BDd5203wZmj0v>*?fUjLD;Oy@U`2MK^ zPCi<|-yQ^;{8<6NxU+zN+E&2L-z|Vf3mo>VV4qhO@WmwsT(q!&9dioU+l_J2rl5{= zaL`Ew{ANr6PaRXhU56I%gMJ0PC9HtQPyzqdzJM3EEa2LW3wTXX0aveH!1Kx%@Qu<1 z+}o=F?0G(4ypzxMFoxQ&OZhzgY(BqwBA>S(&gXrf<@2E(;DO)I=dBy_`K7h_ocmHf z_g#|Dm7WGSJTspcOa*tGk+qo;9$7SlMX{xn`! z9qDq@_<_$fuJ!j+4!JXxU00{Fac(NNJqf<{&{X!_GnFrFo67HPoXUBxPUQ~Ert-Cg zQ+esksoXAiDj!Li%A;bZ^7kXB@`wRbd4Kn*9NcLtKOH=k&()vGjjK=P#IjR)m18O& zF3RJZH}cqdDUYk2$>Ta-fO-8ikIQ_R$G>mP<9&q+cJ;;s1KgES{@$=$m4qUJf3_%mp}YDm+yWL?)7*s58Ri_sUPR^ zQ}5*R;@7~;zL?9;EXd`8!d#Bc$YoB*$xes@z@mh-#dk)w@=}BHcsI?tEO=C=cn-4*;9B{?i5}#X$o&0KZSP> zp2Dif6#k&Y6kgX9jBD*F92+==+d8K3U-xtPqpRRU&*nh;o5LUP$>AaI=kWRUIUK({ zhc7J1;fR79-jN1&G$x1BhGIE9haYsz;SSAmIH7h9FD#eCZ`yNs=iO}H`y=Ml*}U^$ zHov(en-^}%=7iPR@cGE*2Q!hMmCfl1*<5oZmV0OO(9mqY)I6IL>mZiP=3(}1-hC&F zYhTXd%&)Up?aN}X?O7c9CdR5;nZ?gPoyG6wXYpq#S^UL#aGL|OcyAYQp&?lqyAa!8 z?7A>-aGv)w`N)r%Jo8j02k+11V;_RG+>ptCF3;o{^E3HDUM6Qu%;fJzXEOE8x;H8Z$@e+IsTCiBp1llj~?lR5I>WInZhGWWnZcN>;X#`s>7d3erb zULBA1Lnm{k9+SCio5>va#AJ4tpUltMCiAji(|PH+bYAd9I_K<6=TRHex%J9)_L`s0 z2d1R+oCGkA!_xW3?pSV}&UNdh^E>6zx$T2A-i-0@8k|kzXAh?F%@5N!{Pi?`;e|B* zW@Z{!o}9+LBGY(s|1^F+G>tbjN#hTyrtuCR#Jj1y;X*1e{wkFx?@HyK8&kQ`ic~%` zCzY3ErE*wID&HKK%Fh_7T)$Z=Z?2ZgZGBVuox3Rn%QYAqZ(%a4 zJme)LbF+wKKEcVH**uv`R~Pm#nQPpc#4nt~7cA}>3a$nPD*xOrO>`N---KD;22Kg~|$ccT*dg}#ZL);^KD)l1}n z0IdIQ0zY+O0=GFbfxr1+0_VIsf&CUv;H5bexLWiCUfg#A+uKjzq@W4B-){ofzMsGo zf57;72NU?`_Y=70ss!#aFM;DSz`%`7;056cyr>m8wi*dM-8+GkZ^rY0Gx6Y8Iv~- zv3e{=dLjRM41awhhG*>r`?Vgt7skySl@r64$H#C&&lo=6GKL3Ni{X!K7-R3}Xihs8 z&AUH}X2)yM++{&DXJth5>e12sNw;V|+Z5yFRfy*Me@5~Bi&6Z`p(sB4UKD?_GKyEt zjN;6R7%y)~6nk}!;+^%PIJI;XSGyg_+s{Pu;60Ii{*6eU@LVMSm=nok#)IJsi{$1l zB6(h=NIv`5cy4rQJSQF+&#!J7&&QXK=Re&T7jMFN4jC|>x!rgUt2LgxJH~T|YvVAk z?>H{CeH>p}HIBE<9>?zFaojax9RJyA9KRJbj)#;Q$9Haw<@qPUOzjxUue>^zYs?$V z&!vv#zlVm17?Z;s)WC&%!~kH@gjt7Evu+%XsjeGJD(jNzH1eLxXt9 zra?S;(ID=bIfyF{AH-)n4&s$H2l1c>1Np)EfxPasf!yu&fqZ)2K#rd@kgxY2$VsgR z@(&d-p56Tc{QhY$FCP!!#Fq!~2ZaOp@2COXx%&W4Z#aNgmm0u(F<#xJ!~OZsP5p6g zz_(=d=dwflvrqf}e6MPMKKn;M{`hP^Uc9RxN3HJ1jc4@ZD>40eb&q~Lpiw{mtyDjL z@#ntW@^D{PZ};V%&-Ud5X??lt;J*A`>%LsGQeV!$58mWdAAWLsAD+CT55GSZ#z0Zw`L*6_2!jfy?IWf-aM&PZ|-%q7uP=6i?6-e zi#IR8*mIM5af5!n_(bzwoQLt|s@?3#o4@SI{BBR)|6EV*mEM#04C=`tAw79z`JVju z?QkA`Je)VY7tVK{59fB7;hY{3&gWCjkbnyn-{{kQ&t#v7#haG zZNs4b4P)c&eJg2R~9jhpxF#;Hxa@f)SP@wZpIvd@98 z-1v>I95$ybkBaZg2|c=Ua{aD6(F@$gg)Tg3PZ#dEx(in??80}(cHz%MyYRC$y71sX zm;=sWn9C2CQ1|O(m@Wp#BzIPmByKQl?_j4}jv|apL9~WP4?Bc_|F5Y-K zl%M)El!vVe<+_ETd~r-Duj&-aL#l@I!+YQnj(6rB7{l%CGo3NERA;{5t20k&)S2%% zIzw~ciI4B@#2sGl#7px!@h`(W;q#;u&o1AI_uuTu_9Gp+?VBArdQL~46Wfv3b?L}E zYIo#Ae|F##r#tZ1TRZSqi#uREzYhFv-wymjV~oe<(*fh^V(c~5o-e)Bp4aEL=cr-r zxl-%){7KpNJmGpf_C3&!SFLNuEoZdjkH)oQSLb%Ty$Z%*yW5su`l>B^z1@~$=CuX$ z+m_38ZObETx8+y-W1Llgwi)kBY{n_wn{nAX&G?O?rW|^rDevFZ zl>5(X%3s7Z<#3}ZZ?D>v8{BEa^N(Qcve%n%7Z@Bb9@B)sZ`XwD1vcTxYmIr?=Z*Qm zs>XaLw=q|Vz?fw%8gt)Ljd{$4Cpmt{lbp2lNlr+6lE?LalKaj>hL zBZK(WkRVR-3*u&%>he!J>heo3)a5=Yb@^^sU4F4nU2gq*9X|L~9k4%j_|o(`oH(iu z{}fV($NAOauP)Z+&>gk;)g`srmRy@h_o&UAYC(T}uNHUvq886uUyD^iExtFb7S|81 z#r=G1aoV|>{LBY6dEK)$d0RqF-a|EcZb$$`A0TObEk59ArYLJPdN97nudj<;q&58S&P$JZ^# z+wPZT+Y#u1Un|SAbIYGW=XY8Tfpb;ayG2@ZpCTv+C;r zK7%o>PR$75uSNv$r!4|_vm=0)f8)>j@A~to+5Ye=@@JnAe?IQ(&o6!F$K&7g#Vq$~S+}n3;dkzNUXsqZ5Bp!L&c=aQ#22?2$jHch(=2SL+X2 z^LY{NN-m;fm5S)>&fn>~xZmkS!0)tY>u~G}u{*4B`eV?ihy-#2Nb&nRTy+`f( z-lNlZ?o!&yyY!&zU3%*0J7imYhcY|fq3?gVO~%~Y^g{4$y7=`iYE*EGq8r?zC5L~d zof*H<+3LU2?L9Z?!GxRSRqiJGW^d5Vu{Y?H;|6Ve>lb<&VQy=#bd^H(U!i#^SLk%bD^&aApJ;T{PxP$s zPxR5-KhoJDKhpi8%jC2AGRADUOaa#~k=No&bgTU(`ue+zv}NW+daCh78t^6blvx<60o*Ezbf<{XU)KS%qoe@{&pe@{=f|DH~r{f_F+ z_>Q6)eMid=pQQuoXX#euvs7-!x70A|TWaI;Ep>Y98|pCd8)|;<3{_ikhW<9r(3y*; z>Fv3vX-f0c)cM#cx}SZD-l%bkhN!RUZtU0ejPq-%yXhot7<`hN{C0v~!#F|}`2^)( zI!@osJx*<#AE((zkI@%d$EZy8V-&XQC}l?-Ky`J7Pbh!@i%<$u~cxuls#UU;g?D?Rowa+Su+BdiKm7nmBC_QJp>H|B0fb z7=!0IUqxYW?xy>Fchf63cagDp7oBdii;_<5qH7!oQpTEh$=2;%ntSOTa?XB-W;S|5zCo|&zd>tjzdook;_0*=@dMbTs9ep!v9j$G!juQ5+rTPhL>095mwBU``sBN#;=*(4& zD>MI9D%12;T6Jg*HJP-A-tk{UE#6*D>-(*yYByHVQ_rlTYb{n$pD$mbb*ZmVQQ220 z{N0!7nSn3USHHeQ{)=9suB~38^rI_jW%^3m9k`Od+q{DA4Z?UZx0h3e#mlK$$a1QF zY#CLYyo{XXm(lN=U!?PcUZl@%Eu~i%EyWl^7~|#W3sg1z1^T|+3$*IpB{XW_5-RuW z^MLrCr=;NLsmzxc!zE=gg_T)M-@LtuCiGiGx2``&nNL4Qx0*gjiHDx0vq{fV&(hD* zyBnUN^1Ys+lq(Bq@0^8HrO`r)-TO4X756k>GSDQ-TCCL z=25-z^Dr*NT)alEP!C|IBD=vO9|Y{v(q1wTq;=lgCq+P2=eH z)v>gq!C2}THHN-=X*7*LJ&G<@7)3DyM$+l|BdEvT;q<0$IQhDU(da2d>Gk&_=-Q1T z)Tqf28XY&7=Byq>Z+<(F_EsK9-wYZ+m!IxWSNHX!%l3YB#?_ZTpVEike6KgnzR`#;*;9b{IwXHvuay9Jh%;= zc)B&6+#5n)K5Rvwc4|fMWVXcnIhZo9w4i?VT2P%a&FSYCn$bI7Hl<0ifNS1QF0&!uP;Z{&XuKqs+6Vg29}`@<^|BxpZL@0KmDjd8$Y@_sWiQ@ z&PmbVm!c|FO3~f{zLYlChbryyrmaN|++z;98X;|M%+7ZycYL^arxx;MxC(ljDg#}HF6t%V=P~K+Su%K%Gi^A z(m3$raby3mV}{!MmGMryFO3)1A2G5kA2#~WK4{dwzu)*VZlCe`$g7K@GgFF$8I@O#!cnYYkbcXff0I%2-jcHdm%UfVgw zyKA2^;w#KDs?3;S%=*D?9NU?1R9=~944jf~W1YUadaD$onnA=yPI_QDJj`H z3dWhA%NiB;`5V1oa~e|%eT?;^y^Lik4_x0iEOJ#mciYwd#p|w#1AcVP^ZmiKYWEq} z#+>7>&A~@pn||8sTDwZQ77zc(m0R|G*T{WuyIL2%?(%8B#&!J03fGGDOI)MJJ>#lU zd9Lfok?F3#o!PG8xrwgVuZ(g1I((q3<-TsN#CGjnE7vt~?X6hbb!}##%kPfE)%(+% zq1kJ`4qZ{WGj!Y7wV{VQF9`i8BqsFOjh3PNBmU}q@$ieCzb$vL*#93I0n_InS_0G0 zztcY+-+pKlOn?49=-U?`erO$7{Pwl4KC~02f4=s~*M9iWY?!|H&~}*q_RxTsKK9Rj z=JBhCro{B6hxUZUe_s2{L(2j`iI`o`ys-GjLmOlI!$U*k@qwR+2*3BA$D(f@zV6WO znEvhBryW`#(~ljRAr{|t?XM0ElIf$a{nE8By7oWUKIhucT>F-5e{yKJ&=-8A*l!$~ zFw<8Y+A-5VT>FG;KXC2)t^K{VkGJ;g*1p`@e_Q)(Yd>vh{!HI&?T@W}u(jVcG>N9K zwf3*pKGoWfTKi6Ge`)O_t^K04FEq5DrvJ0{dDec;(43mS&Dx(?`!H+2W$ml1{gbs% zvi3vPzQ@|%So;`jzhdo6to?_z&#?9rhUVGy4c7j^+6P$s{c2xd?cb|?dbJ;~_TAO~ zy4puq`{hE@&f<%!{cp9;t@g9kzO~w)R{PLuzgg`otNmlOPptNX)xNLV-&Om#YQI+P z%c}iXwa=>dQ`Nqy+8-4RiRpu?{Z6&7srE0`KBZt`Og~cXJF5LfwU4Ow3)Q}$V1G>i zPwn%m{XD@OnZBLcpHusAYQIhGtEv4nwNIw@!_>Z)+TRik82T$t75i0cUrOyiseLB3 zpQQGU)c%m#2U7bzYF|g~->7{WwI8GQUDW=H+DB3QC2C(p?SH6!4z-`5_AS)@gxZHt z`wfB#HGKtrc6-tBhtP@+FwZf2x-3{?F*#+f3(k!_Vdxc zJ=&i~`|xPL9qp^5{d2TWj`qXRzBk(6M*G-kzZ&gJqy1;J&y4ny(Y`U-A4dDYXulWj z>!STzv`>rnW6{1V+FzxH<)fngQnW9M_CL`+C)&?M`<7^blGUR;J|x<2MEi}W@&E0FhUUT%Cm)Bgp=HE5vu6cINt!qAAbLg5k z*Ic>g$2BLed2r2rYrb1^+?vuEo%^hpL zSaZah7uH;`=6^Nkt9f3{?P@+(bGVwf)m*LSXEi6Qd05T8YQ9x-teRKVT&m_zHD{`M zQq7HOK2&p{n)lRPr{*^`r>S{N&0T7~Qgf7=m(*OO<{vfZsCh=sEowedbBLNZ)LfzF z2Q??Cc|gtmX}(W$e45wOT%P9dG-s!II?c^#K2CFRns?J&o95Rvr>1!{&7En!Omk$K z7t>sr=D#%OrFkyRZD~GBb6A?U(p;71r!*&}c___2X}(EwOqy5HT$1LGG-srFBFznH zK1g#wn)lIMkLGtYr=xis&E06eMsqZpm(g5|=3g}DqInk0t!O?)b10fODdtKnenfL3 zng`L`hvqvp$Dw%*&1Go*LUR_Hr_kJl<|8x*p?L?*HE4c8a|)VA(A&D@ zfCXUi0t}{rJN*sa{2$QqL%R>gfx$sASP7Of@4#FzxC{on!AJJH84L)^SaM)VSjL0{ zlfp8#8`u^G|H3j3n;Pb3ur@4Xrh(aEa6K&Jn}H8v8K+FfA_I%WGNu@qCIG6s)~vm;~a$apz2CXS4IBV*gh_%+~vS;nD}v1VjE85uK1#)XlwUu1k28N)@! zX_2v5WV{s_Q$@y2k+D%^{1fowEaRBSSS2zZiHtcSLQi~%C!e8^ZHGG2#_ z$syxz$k-Y(euj*ZA>&}kSQj#$g^XDt<5I}j6EePpj3FW8M95eWGTwuX=^*1a$k+@r z{(_9LAmb>=SP3#7f{b|};~L1=1u{N?j6opd49HjlGG2g;2_U}z;_WZ~{o>ItKK$af zFMj&snJ>Qh;(agv_TphLKK0^7FMjjlDKEb9;tenU@9@vz3PU2%k3F8nk6k?1#aCUt z)5RYh{zBqGBtAvrWh8z_;)x`_Ni6>1;t?)B;NtZye%|8QExz31y)FLQ;-M`*+2VyQ ze%In@Exy(8-D2^d7LRH1kruCL@q-r6XYq9w?`H9577u3eSr#v4@kx$VDSYO?_crv6%SwW=@l?^yAN6%SbPc@-~L@oN=NR`FdGZ&mS66^~T$K^3o4@iP_AQt>4f?@{p=6%SE( zc#6-bc!7#vsCbHs@2Gf_ihn7KkEVEKiXWzUUW%`!cvp%)rFc+^&!l)sieIF7LW=LB zcsq)Jqj)rm52JW3il3r*CWrMRJ#IsF&*~EKI z{ME!mO?=YC3r+ma#M4ZC%fy>Z{Kv#&Onk(|D@^>r#Pdshy~Mjq{JF$~OMJG(OH2H+ z#1l(=uf*F*{HyN5qe^_J#A{0Yq{K5ye4)hqN&KC}!%2La#EVJ%mc&y@e3Qf*N&Jt* z<4Amr#H&dBh{SV9e1*h2=o$C}i3gDQ{D_y2`1Obbpw}<$5h)0L`aERB&P55bShi8WPVu<&J_*;mFh4@s67lrsuh^K`3 zMu<0r_&qbfcO9i z>n}XNF#E#g3wtkoy)g8`$qNfFyt^>%!mSINF8sML=E9K+D=s{^FyF#;3%f0RwlLVj zSqn=oytFXU!aWPyEc~)C%EBQFYb-pmFvBas1q=Hte6KLP!s!Z&E4=M9U}}Y%6*gA* zS7BU*V-;3acvN9dg)0?yRQOO~K!x)ZmQ#35VKRlg6t+_MNns>~gA~?Lct&9sg-aCn zQ20V&2!#_A7Eq7>tK0c?d%kYB*X{GV9bUJ$>vnbBey-ceb$hsO_tx#(x*c1$SL=3Z z-TtiGnRR=zZa3EL!@3<UKrleyH0Cb$g(0_tWirx*boq*XedS-TtQA*>roFZa35IW4awow|D7w zE!}>l+o^PWlx}y@?Mu2HNw*j2b|KyVquY6Odya0m(d{$39Y(je=yny|exln+bbE+y z_t5Pdx*bEeSLk*L-Tt848FYJsZa2{F1G*hRKkw`3dj0&apVRg8xPI=|&)51nT0bxA z=VJZ*tDkfA^Q?Yu)z7E;IaEJy>gP)R{HUK3_4A;9?$ghA`Z-QNuj%J9{rsh$v-Ify-K}- zs=T~?cE}cGWs5;6vckL6Qd!~jd0A4|tHxW&Rj*IXMq|xS94^Y%3?{Vei?+d~p_g2WH8B`*e{T?>z68YujtnCrH@ZZ+TTUOko3!AY*4{TH#@5_qz z2z#rF_Q8(3_8}GRgAfK+^eV8~L*%|)huv3_o9+u#U3n1}9JWewtl#VOLtB-BvfI8l z@z=*Z#Hv!*EamNOvsII=9y)AQwn?!sDSE1`ihs zfkm^rh~jc=D}NI&m;Iz)yr&%YQMH>cHx&!!!Mbhb$H-oPY`V}>4A-RUL|yDPEO?I2 zZYzI6$~A7b)l&}Ftml1{0|lMD#9bAY)+pC5Gc|7!mt%o z!(#D-P4Vgtk|3+?Hu>@?o?KY6+XhSMj@iqW6)3R}W^WtbN~>kbv)y1U6;FgEyKRUB zYr9G%w;NJoyCKCJVWA6VyDdV3-bX}*}7aUvzVmh z5_l##;*wLzbT{1DUbdgH+ROe|*)ldeCM3-JJ-Fr2jOf(NgtUy5@a)vstfaKmOj~T{ zvFRCU6EdPxf)bLF<1>RA=XPx0WbB00?4Yc)wB*d7=!}%0_>`FVxVZSZv2BAp1hsAz z(t2{+u`x-hV}pZRCMU(ToDdt^62)4irlrQWh>wm*YKd~eZCYY=@&CuyC#A+FXUE0c zidXlxGHfUp85f(?HZmzSDJwFeP3z!TIr_}3IQ&EiPQ=NXMN*=(5|MJqb?}ip2H!W+ z?e<_t`Jj1?9l62v>p$VBG_%1RN1V$M80?4$as&sps8`RC5mc{kJ;(SUNBy8ivNSx% z(JaU@)yy3oF%A!cJCk2JHqofG9o@JJKf6Z5iuyTUsBB2h_vjC*!ZzM zyLY!G;TXe{qbCfpr4OBw6c?8q-)%^Ibg~WExNf$`PO|5KVL{!4%p1bIbwXOV>JZd8 zBR)AkIy1gW&=_2Vmiqo`(KfO}ix}Lbv57$$@i|GExJ83PI<;-ns@*uxnLSo@W@1`K zR?uTvCC|EJNT=4e81tmV%?t79f)5Rg7#bPgwRgW^L&9t$;*%yMW@Sd2A_jLDOp7S!d(-%0Tb;rkUOG)d)#XCGYD?8KNSx4+kUI!~n@3wfao-;Mi zFTHzOruE|Ly|fEyZEpS8r^sXbl@j_Ew%Kq)cMfVSx9L#x0}r2%K{%zLFzZ7vXi!F4 zYV^1E2Dq?U>{Bti5Yl`GyS6%uC6NjzP@I z@We#Dgneb%g5#pIqHV!3nVGg=ycdHdGq}XPZ@u)v8EKw^QYJ1wCVK)tlM>Rfxw#x2 z6N9&@rv^_>a$0Q3WHjE(6XLCXcuM?dPI6Kzz6m^Qages)*tC?CczlEf<7Ehr&dSP2 zipkD;yp{xfVa4k!@IQ|=QAEB6@sr1#d}vcp;kFr zEz?nyX@j3$deU1ALPp8`PRD+$;pAn%r7-LLMqycRgGHOe+sihpM223>_*c2H_--z* zSC&|pish2~U0xMGdQeXG>xWtIcSebAuxLy1^|A%Yf;H)?3y>~Z-vKq+lRqP~}9 z-OG4f$K#!?I+kl=mihuQ%RWoix3Hp@?S16wN!O>-I+o1$w%wM8<>JZl*cnUxC67eX zCHE+4Z=0OsqsiNR{iYXZ=&R((aNyHMUf)NPuT4IOJd+)J_q8=P6FAE0a{Ya6fHAO) zbQe!LT+(}x4)UZ&Ncud|xF}LSR?>38a5G6dQ_^UNkP9bix1{l0EvF{wl9R)Hhd;`3 zJod`U`N})-(d01SNhQGm@2u}%+PD)heFAflGf|~ zs~0iSw+u(29$!D4$ufez_IpRrJE8lFv0S z++gxvlPFhLqP%y!s@QA|C06w`gGqjfwO$@;B^_o(dF+(5+*=aITT$*UNvB(JiWLj3 zXdWllFR{`qtthXNY`4LR?^;nlvn2mBD;~7sS62Mmif65O!HQR{c+ZNJaYINw4XoJ4 zisqv)@&{Y#C@ZE}vCxXoT5+uv-?QQ;Ry=COAFL>CS+c)>tcZ^?GyQ}Wdss2TiZNE4 zY{ltTe9nsNt@xf5cT2=~^QTtaC$W;v_Kg+KNyPqtw$eAP^dDBb6h5Y;e1Jrht7*li zR%~aj?`)-eO2qvnErSwASTWLy6C|P@Y3-Et`Br?&iVLmyfBCm~jFrA?rES=^)bB45`;$qI2dm9!zCVzb z&k4zwA`<1dv&80BY-Pm`Rt&YG`MyB80akjL6-QYy+KTa3OtYeV221@jtvJVu&scG> z6<1jC6)V1B#f?^!25G5hw-xtV(R|+^|Adu3ZN;Cgc+HA;toWN1|FNPp2uZ!>=SYP| z*9WW3e0}}&cDS`{UNs(Fzv2%$X`D%G85Gi{ed`YG+O}%dJ}9VFkW8MxA;@WuyiTp! z;jc_le(tb-;hq*L*_(W}H#R@tJt>>*s^=@hr>&XM7@uWTY%PAiHE?fYmGF7t-r&YVLqKCgfc-SPoRe0<0`txKtB(eUyn0W_^Y=P;Ck#(Hc=Q^rIZA*OK zd7#L9(Cx%Qb-EXM*XocoC;UK>Gd(*A-c zyf+^&3fQyzwpZD%Mczk_7X_}_Q{-H8yr|OVu0_tB$BU}%*@N}Rle!iKG~a&gOpz_U z;k*t}XNtUS8=dKh&cMhzTMz?+jPN^ArSSW~_jaHI=kE37`y;oMPplp_A~7;*QR4Eb zV~K&SzljQLV>hZEt(xeCv#E=94xCG5)Uw3YQKu7sh^m?t)VgkT&%~fM1Ec09dKu3} z?MXZkb>&!4Qb>5WaCu$2;q~bq-o;$rT4Y<(Gu-d?!_W~$jr|8+dnsVxt^C1X;L1qJ zcHy6fhZR-ww}+1|a+Z^vE#bY3yvy0czb$gwBz+KPA*nz!Wq;`)@=?0Zw?%k=KQATh z;kM-m@oLTr$1CixHSTlt#FmbUvZisAJ$$>ll!&E{Ns_lg^30_jx9$E{k#gSdRm%5v z1E1id|8KUEEjms#YmY`v=29Y-I!-ccmppUH|MtVySEIXh2x|8p_G1q}daV9D`|`*- z_LZft+bUPRg7*T#Xn#ozC?(^>WXFHg|Z5KYQD9}GTai!Di_QQ@+ zAMUPz=)`pM+N4KCCvG;EHe>0QxzscKR+RIW-R^T6JsmCk9zD2axVeRF8*VNoTGur? zaf7+E0oz_Rm##*&3lD5>=T=AmSGGY}9ASz2&DSU~8ufc#H!NK>m+X8sIDaRmv(mq3F;||Wl2&JS?`m7wy zU@27GC+$2YWs3Wxozlbhs88D2Ue*@(NjtC0+TuQGXSl3gX&q~TbB82fvXX($&!zCo z=1!$g+SgkyhL8NJL!Y!XLg1J_bB@R1lrGsP?Ue7^M}5-xp@8Im>!iFr*XMw>6Q}dM zRCloW5aQ+J4w;qW3V06TaEU{>Acr77h|wo~1IvE)d)UH0AB#3yYxxGnWS3t`{^*Wg zAPe$yBS4<0>`%*!BEK#Is-e7np(JxKmqCNzvoToMiMj0a_+x)g*7ZWEvhuBOUnI#f zNR~;D2(j50OET4yY;7ffm%@{!u({TS!zz=MYO_BtujVzR%GJTbG8~ZnE)28}@yfy9 zLHKJc*A#1ZAa_`aHG{pfi`RdOx_`jBG;4h>)(n;{%YTVArE%I)pC>oZ+$t9}`g%W) z@)hE+?}~POAln>Yl(yStKb7S8E6IU*mgL+~rXxx^UMgj`%f38o%!1}0t4u8^^SaY+ ze;{SdKgDIRN9o(HATLs7`)5*eNDaIFzpUy1dslABPFr8yX*nxPTSItciQ?D z_k#LA8Q|%%ebLipiyyRR@2+&8;zwG5)kkY3%b;^r`hKls*%E!NC|pkW(MpGGV2NJZ z@_Gd>jHf@gV(|f>*Vtut7FY6g!&ZKLjl3$D@q`_AT#W-1xtLwOzd`hGCwVuxzlZyaD48`Y$+xC$)CQDFFCUNn3Z(# z6yIYr>uP1@?Y8Rpv}ER^ip`Q{#STBu);VS{H~!adx;O%Z9C^V{)`MuFalO8+YdKcA zU5=k@eURC*WlN-j92X%kllYTocUWT{#jDoo{opy1dS>PtEAxDbO!H8h{c9WZApgD1 zqs)duy2b7qgu31uGz+s zl3>(rXw+?h|J|C@bzCeAa;&p^E^3OoBSWgMD}T(rJxVr^y#F@o$oya5x~tUKRQ@zJNSqknzzAy{-nw2`gTA5Tn>1?G zIPd>mNsK9|DApGgUnLP?l#navb9^MGc%u1x(3KHU(3* zl4_6=Qi)>4ibvD*Xm93$4fRM{Jc9Pm<5Yz3+r7Xkj54GcZNn5l`o_1f)vi$Y@*82ZPm(jMw z?>N0E5ACHN9ggjMP0! zWw1^kpY)mNZKRG{sIS$3ah;c9UCH`-p+0$?

    A*7dE&veefKvrIu~CoJdiEX!Y6 zC-Y`2>T)eB+5Stt#YZTI&C?OgX${J?(FsI->|c~vmenUwuA?kilRl+`NS8d1K_#vW zHYq+29JcJYcnUy2%D2U-NBfoi>-UtbK3W}*)yS-dWqDYa{RU!|eU_{*3io{>^7N$7 zL#K5tng4%6Zz0F>Xwp~3lOy_yl9R)Hg&*bor=CIX%tw>MCU@4O$zk3ZCDY|iMZ%+F zkSqRZ5`99+N%RgSC($!V6NjFp9=v?TlcZZ=mTM;86QXZ0ir0Exhra(xkNj6!-v4?s zkF(^LX|WU{GSZYAMke4J*;bs$%#L~V!%x0VWZOsIy^<>aNg;{i-yV|ie69cM8y-4- z9E>0Cy+#so^1E?zet6SKTeTl__!)203Yd^G5`Qc`i2pN$Xn_Ds5ii4~;+KO>j z%(vnkD=xC)N-M6j;yYH{Zbj*1m;Fg=hr~eK zo)vdm@u(HQv*J%yyk*6|t?0z-F8irq#adRBJ6rm;@$qK!!fh(=Z;80HX2jdp=7rn2 zp+ppFZsmtqk*pYIMQLr8?MGN~ycJ`um~O=>R+RU;lwWAYC01N%#aFGk!HTBF1Le0` z>94JL*@}0q=!MtaJRd6tS+S)R$%@h(C*@+Tm|?{kR+P^yS-;wf?^tn{6^~f)q7}XI zdP{l8#?1JH6+^7p#fk&1DDD4JKEsOAn<9PY1y-CP5g(FEthihv%D-l%->}kVClSi+ zw(_MhTFQN4rH@ZyUI4kB@ zajF$(SaG%$&HE1ZEwa+`y)XNH#fq<6@hvOvwBjBs?ziG$E1tCC87p3};*VDR#frDA z_=gq$v7)!!N7%p9ih)+FWW}0RtZT)_R%~uXQ=^3KJ6P#nR_td*>C=(=BdwTfMf1K# zex8*su;LsmF0kTaE1GOA%D-%-*I4mQD{ivlRx56|qO#&=Ry5x~sOPAaK5a$m`IF-` z-&cq~S!wBYlKj7{=q2|p(!N$KXGQb(V6u|1hSjhKMGcq?s}dF=2vtDPU=a}zp??hlH}J1^0s*pv6)m+cm|APqYU)yP z!J@U+T2s+l#l$KK+L2g&f4}Qovk&2%J%U2MzUVHM=9qs;(w~L+`9$& zA(eln{I!ygL$jQhl)qR0QOOH&OqYAPz|U0vLMis&6FVO<4Mjh4zJ8)IcOZCTDSE!1 zHadS?PTcFe?#&rqFmB`+(f{sya|#Bt71lTI&H2^-ks(+9>D&5N`nUI~JR_78>=g6_ zU-8biY68QzwS-@6_S*-n;f=Xjj;!w6ldIY+&n{n^%k68kJ-#-}b*1ft+56P;ZA;vd zP?faH8#;)4VyxZ=!==qP2R-%f-E+dO74yPLCHcXDLFYDmJMRh@h&uA+juLlWOE|xx zB^(I3Ldn&$!`_nlVXH7Nm@BEd!GvI*gj&LVo0Do5qMVsw*JGVR1B0a!KM?m7nUJ>@ zrBuucyXs5BN&7p8<_9N>#{8gLL%G2&p#m-Ux}XWgS~4)05;AQ{2oBd&Pu=h!?mO}s zU3bldaFXTOeQp{06W7KHZDTT8kl)-jGPr2Efmw)q}s#LBXd8_aP;1UrUWa3snx7)3dYQYHU%U1 z?X=*SObNb-yKjtkOE|M)cyKa$W5zD27I*ugpGHC(_oviMLu!t+Kd~;QrgV`Bw}kUT zU23Kvt&`MN`023;Pklc6O4i(^W>fH+u{=U%{Ni;7qLtr_of5n*=+a(PXec-63U!va zT=d(7hGYJ8l{k)o3C%}|-6U>)aFd3v3(nV4Fan2pbmj-o3;Qfn2j&Y#Wjgv28I=HZ zh9HhQk+_`ZanN!3%-q1pHT!BAgL~{{bi9oNgTd%nCD#oM9xX9rm9X1cvwo3X=dMny ze9J*`F`DZ+K%1 z&LPjRdBMU@`(Ed-?OyL_n`mtc_#1By3~y)&m+W~6Wt4>MQLeUPS4;Tmilnv#ceC}m zH6~QBb7b}K#u=^8B_9kQ*#C<4H>;><>^7_IX_wXZ8^^dE32ir8r#Fm14JC)~O*a)rQmify(Wj%KWDyf@RmA-30{lMKntlnL^5O%X5YBx8j4s1zg)=cyCNu@9X3X4mQ-Y<7On5jnO$&xc+rm-lDY>WM49}L3ty+n-%w1h# z(rLFlq}L@hBfTlYQ1%xYpP3(Wr??RoiU2vjO|tvv0(AK-D)-Aj_z&=#7| zIJD5%+Hn{&6Pk%}OcA}A=$#1-#3-B9U?7fy2|0slm~l>7iJdj*i5yoRFVoJM!K9E0 zO+bC-xK4;3;cq)`{%Fk^I&$XddTM9N+G5gq+)hr%{KauAotZAVc-(VO%HO+oN^lyi ztx4xtMAFU3C)auFlWGo^1SA)ad#{u7duu01{U$vL{f(rX{E2m*dKdEdkX&3@vQElB zJm`}nZ_-`JA4xa)J+;a8Ex1QGWhO0spPFX_ZtRfkq=d$o1AVK#wVwrE4U`nu6(#KO zRMN8VzqjA+{xu^S$}{uoM^#Tv>$h`YO-s1`@R-KY4Fdv$>c>`hZc9jP3Exvu(Aa<5 z)U+Wr;~MgI4G4JK5`07JhgA>UHfYz>w9|I?s~O(t9p%mUj(uR_!SFrJ2gCKDA=`#l z4GW#Nt0mmryzzM9y(8-SR5mpEcW_sC#_q5G-tEyd^&U&O4Y9CY#mi-9V&8ACz`yq; z;^co0mrFh`+6k8-0rx;IB)I*>myCBXJf=iqJogYTH@^jQ-pX*va*6TC_X%Ei5+$#P zpB`iPSMD?_)%@sTdk=|&9|h<~`Tav+f4;x`rvu4erAFzB_j@!!4$nenX@ zK4J4^C*IEf+{$k=hT@&LjN)y@2%bxkpN{PxK7#)%DLz3l#8kF9Y58K@nzxPLupo%r z@*=^JvEZm!aC9sD6Ng~Z@jbFNuWuMEX8H7bUMj zS`E`W;R90g8l;JIok(blNC!niTSOY_r6$@U(ln9K7LlG232hPSOiY2~HE4@Szo4`V z_0_VzzLP82 zg5R#$);uCff+a+OiJc1Y>oVvP{ALO_ITEj!SOSl^GnQWu&BYtK#G4YF|2dk5{TXA4 zbuuDziS-gJA?}gjoF$kGOYw#-kqvW#n^-RcR!FdfXg0B4Sdb*Vp-bE>!Sm4{dEJHo z`|w68kuEKqOJqy1gvgcPOk$A)=W;RSw}8k-@C!E#-Trb0_^lh_i4P<=lPEB~tN=Dk zu!P_@%s5s((5-;!C9y?<^N3qaEb&7L&Ls9qa2~Nwf+fT&G9uBg9YBAcH(euAr7d#^ zelLm^5}Xid`M&Z36mYsJi!j4KrvkyvCYIPKHO!67P05I&<<*M+{Gt{G6Q@fZ=QjcT zIuo%3#|L-UmZGc+OtFONPPE}6WZz~=BJRc*p{DS)4BR6FRzhgg!`CLE2zbt79R!a% z^h4zgJSmf)gh-VmKZo#3u!MNt#Kv_gd@U-K7r(b|#v26_mzjptmou=!G=w-H!8yHA zcVE*CqQW#Id@Tc;O*4o;OK@H$>diLIAoS!5MGecJQQNtN1 z3SMgJAf7jM>?vp9MN;ZT+1~m}8AP2*+0>!R0H4rN> z+t7=>>^ih^7%IOe6M}Gw_vZ1mTpLXU5K@1(C6S4AnhuY9?qy&{{6; zf0keg@f)dZem-g#VJagyC#97P95@OjrGlsacRe6AsSXS^q zdpF}a2#9Z%`0%w79~licknKTXho!K@lNv=`7kB9RG*j2Mt;q>V_nnvF!{ ztD?!SFoKOl>PBRDrV4`J^caq3ykKFp=hsXF=ygUYJ4yz5x{|7%g6?^QW;NNm(8nW&2&d#OZbC%^e z1H+tUX7%Jr*=^OS4F94 zezYy}5YnX-uZzaTT7O2geWyzO=k41R&3mf8{j1H5J#HkelA@%!Qh>C+LuX>O{qs~Q zuS4Dr$LQY@JGAsaCrSrn$KzDJyefJuPnFtX{5lL+Oq3Clhw!pl-Ua;k=wr^k8`t8= zD8~XjH#Zx;dqa2x?jvh_pWLimzH^n4Fd}k$^`_ztQ2d9rcCdt4mUF8u4`V$SZLQQO zBe#rku|wWrx(tn`b~r@;Lf#HV{i~u3ONZ$qwS8+_B*&?2!aqN6V&`0kzI8Y-|KSPt zua3(@Yh|HHiPY$~%-S<2*S!&O;dLpmM5l?x6Djxl;axnIjfb`g;~Tebs%A zKHa>%x5+c4v8VJpJmN>!&2p2!co#3Y2u^j^E?a%ciVfn;+&t46eT*;m2w?nkd(j6I z#qo3eQ+%nxC8TZL6@_B3slH;PS!^n6Di9Hcd9llxLY`i07 zBWUI0vZymsNL<(yoCVUtaSRb6+<5fvf(} z^7xEQBoBgCIm%06KwpuxA3}~V?@(NMxSSs??@ojxd0514DDU*RjFGh4kro$i9Y%RP zPHZ2CC(_>s5N00E2fhwq0`be-$csU~c}*%_Z{@&KKkN7m^f32U0rGkadLttO7%BRX zabYI=2jOdN2J{t~I=_b;-;X2c2gi^7@Z%ln2M%R)&Le1*puG1O&{w2h64NdE$~n!F zi>m>|q~gu;SU&5FoI?m&6&RrJF`%zVc@a6n`1t>cXC2wk*efzBCgy*~vyQy`fa76a z9P!xeUwPIsE2b{x;IKqrEO%^FGW8Te<`{Av;j@pjHTmYUX}mc{pIThJbm_^DFh*1O zaHBk@$lp%sxVu3;>+t5Yb`@kde0`|$K9!qQeqQBwROYp2>hl67$wspr-kU&~7r80( zIzBl><0q=jyA`NM|3ysa<$TJ#YD1YZhVgz9a$jY>#uutQoy6gttMN-z=7nbFTdy+j9$AalE_*7zq?<|TgWy{0lRYE$NwQR?%$9c3CW z+@j>ZhI%`d4a&XBpD3SIzC_|2dPVsfiN3w5>F=p5*8ouNXDXl2ba^Hd`iZcAthXBp znf8_BEdb>E%FmQe*dNAsRrXTyw*r%<9QDO)5Tvqc!|naDX&*R%sRx9h3_bMMy{!;lX<&mYh?oG58B0bpX6QAWR|k8 zGEX^NIa)bhS*V<(oTgl;T%=sCyj;0fxn8+dd8@KYDL2BSUGi)^D8F+6a(}`0-lzPz z@|VhH<E0QzEAK)=TG z_nlZyFJ&L4*c-$TQ(1mD0&mn$z<(uW4?<(>2Xir7|BdU^(<8Og^dP9YB;1DqmKiZV@^rR=NBQw~>-R*qK|DyJyVRm$&Tpq^5dFH&BtyiB=Ld6ja5k`Gm|y|*cM zC~K5IQt}Q3>fNh+K>4upG38UrXO;Xei1}Vs{z>_k@;zm%@)PA}NQBp62^1?PhO?mpxmsyQF*JfQdzC6SKgug zv2wriLFJ>$CzLNKUs3*1*`j<`c|`fK@|g03@++kq8$k9WQJJdjq0Ca|D*3sD`a_f> zm1C8KO5PPoy=lrB%2MS*B_GD2-WAGqN`8J}{3hiMO5Qxm_>gj!vQEj*HB7%td9U&T zB|qmd{W0ZJ%4d}?DS0av_5P@AQNF7@qWoBSOnE~2m6DGav7D~TfHG6rM>#+_OgTcy z+jE)!Ol6UhpPv{%LpfV{f$~D-GUamRD&<-wA9!LpHz{vZZd2AM8k`Gx@f3|X|vP`)_d9Cs` zIV${#BqRz9XYq&mYb77+WV&COq3osPbDm5er94AYpJ{d~=&C0FHTa`PMHOf1bKUVTlQs#e5`IPcmuFI z$~%-lR^G4tneqwcQ%XKB%lxk^-%|cX`LXhtk`L5U->dAR?56Cc?4#rpx706Co~=Ab z$wzRRUaGuEd9f1P7K`8MM!v6sDEiob3&To$h1kJo)W{Jzaj)<488u?~*b(Lz-oD#s zRKB_B6ZILDfp3xUdv0AG+2474=lXG>G1~@IZp9A^wS-@9ZVA5|%F1%J;d6YOGs$Xm zCp)v=w|;Mpt(+Rnv1hc}fyKcz_-M)7GdFlquz$$6;~+dbZ4GV@)&>{A>(kt@x9|dZ z*_ju1jUU+6>e{=jqpeSBQ2?GxN>W050{C66{HaJ!sLbm+55Iwy8tT+_Rat6HMpt)R zPWR^m{_WG!;J+jPN9i?360Ip2o7=78gCC?9Z)$gfJ&H5xE81;)Xxip>XP>|h)G|HL zfO2wPNbga#!b0uVm1PSo{QlPT#0G!Y#M(8BoLy7OE-Ukf+}l#B6B?dw%k4Tbqep$p zwuH*3+WPtvYE$Y`t7`(@I)4M|=u@0=@PpJo?z+5;3P=Y(@b~f7^{BkA-Rk46Mmzd! zLa2Lfx0;ebM(qUacj=|pH1r~&ZYpX{seKc_diP3t9$IIkwF$-a{)BgaMZ3G0Ekbb)Hc;UymCy<$5vk5 zxP}?6FIYn>hg7~{jR?(Xecm;rHL1sp*5tH-J7yfk2kHDFbweBSaV%fmKdkDsor&89 zR~`)SYaSVz5gc4UxVC@U%(B#-L#l^1`YT()`zi+1xXKokjVQakY(jC5s=)TNZT)u? ze)?#|z`7CjBO9HcxRRZ1uB3!EXX3$dVMSW-!2AXHUA+15&2vH6lTROG?lz~_)#goT zN?8#0l$=*K4Zq?yKkUg#sCpypDqNGcH;|r|w0(QZv_+6}uF62(@yNTVxy|Q;o|Teb zn~_kL)OY~pjKncSnF&nWmwtC(OS?-(JkW3*#`@p~NyR-R6sSA+fv~39xhs%vM%NFlm#h;#V_Lb_zEkgq5oZrreeId z7fr!9ZY!!RI{WjP_YbNc+%T-}lFT7Br&YHG2JK7^46Pr$Ex&PK?Vy_B)!q?zrfr%y zWc$z^1GjDbJaB)(?osuRdPg_hh1pZEebmmp9cO?3_I=}O9iMm;d4%SNz1P$nDY1Uj z=JwJ5k_SFYcwRpZ+1-|qgqAcvp5bY8B|qKf@h0s|*qzdt_=(p}er`ybr_J^yHe8*a z)cD7+Kj*rln~N%nhNkDIFHV0F$0n)G;kq|{b6{-s*Ma0VXTno$UN3$ZaMcUxld`9T zy(`fB>06IjUGWQoCC`OZa-IwO^T+N={3Iu_>E+Yu#uF7AFwYmTruvD4w0hcqhYuB!;%ldXr*^yc`B+YK?-F-2wRLUR2R!(#J z#jq8QVt9f}fxRfc4(C2?6wmjA9|VfK*V2nzT0LsCdhB>1&^-fIYsd;~fz_ko$};~p z+A5dWsm|3yy3#(~kluMmN_A?jtI}V8LprULtGaXDptQ7f{EDRIucQ@$4YBcCk|~JE zhqbYQ`7I&%c3XA0`o|1Nb`Z5cpz)MdMJz5r+gp&GJ_pJ5o z@Yd00(PGt!#oAO9g2kG4zprt0H7r)%2w1GlO=Cj+L+)S;Jel3&ozeQVFS%`+`(q1M z$~mgxAUxd++1|f8zix3hY!vL2D}7|u;2mS@Ppcfd^GPc^YtW8?JFMKnLCpJIo^1oF z@+yb#oEIEeJ+R(Uwzw>1+n~n5wW+XFdqVwc@?oj`uvAlu{h=P)dsg*@rFx`dKx2O0 z@Y>121lTIrsU!#d^K=dkKiN_(f>m*1&U>A0UPo2Rd1bU!uvF7&sc5HM+xG_6q@|~M zzr#|w>bz>H{PnO>3D+0x3*4PnC#eT653{Q|(lCanHuSYNv9j!Qd);ORx50=Z=sX^NZ?-&3(m3IG_-6LS9Mv9#pvwg(Q{;*T;-#7MK>{Lqg zZ`wStQ<=@~HkaC|g679zk&K=4?sV<$9I;cdUbfEzJLUa$I~CZRKDzqr^posV;M?ug zXth%XYNuBH{JQn7pgp(~ysa%M%iVIvR`((LTsyqp&T}7H^{Ytui=V`#=kxm+>JU_uIJ?c6#Vz3IREb96*ljmsPKh{ zk&Zr=_b1GI!jmte!~0XHINMcpdU>tL`K9M=Np*QQGw(kbHcolHMY`zZ0+xcG4rX#lE87I#!4a*TZ9l1fAb;V4Lg$;`2ILVbc?0rD=nTYnItX?9US{fa zJrA1+?#1Y7kk6cJa2;ds6WvE*!FOW8SE*|hwljAB+lb(k^_KkrZ=k#cHFoBeNF)9X zVwXu#F`;C;Yvy)W=VzH!^yTiy6ni>V#ySv^&P{~;9E$BK)3U(9YWT%oSDBaN z9GqvdqjgB%NQlrE+SXDdHr2PnAj^V@6y{Q6{I6k3#Myv(v~3R)Z- zsQxa>oUvz1%U=-@)6a}YYQdcY!Q*qh~*Hwao!p+l@r$l ze}WXh%-ji*(Jxb1!!ma@ER$EmGJ7W)eVM)*mien;nZO#B8C)cDr@KtyVh88&tEjuX z%wZ$vcE!zUGKr0>v$(s=ViUCzDlo3cIIri+EIu6(k0RFQWtpC{E&Bon{)8A~X%}!t ze*rNNKwt&(bVGU?ehK#~+=A5?akR=AEXL-Q98JMuG73^Amyj%b2L9Uxww=wwvUyHq zPvO7!@ee8gv)tE)X6(HTZ($3!2cOygQEE81?jmK%@r8`qp!yS#9?u@5r8Z_C+; za1P1G{^1dB3ru9}H3mUAG9l(ja27#T_;%wRPSF?c;DhE&!jx25#Z5`{)f*u=3m{BM z3*$;EiK-#s7tPs((VRo@Het9n*CQe39dEs1> zyWzEo%!$&fHZnkc2-VT{c2FLHyrRs&c)U>v!Iq%vIk6VaW^tV{f>Im<*?8O50zz9l zJ=W6mQHZ=)Fgr=-cadBSn^fG}8J8YJQM`u--j|4d=r?M6xSRnq0HyKS;@WF!sGJjD z106>3ju8wSp+m7}V-m*1xU8t0LvlPZ;*pZsWifZwY(l$MN-`&YBR8U%j$|F}Q2Bl| zxY@LwcoOeqYr{1OKfrdcH{AI#;w4EhAs#_-$#ChButCx@qvOFsm*5RA4FnB!7whV4 z5=Ql3hu`S!4QB3Uzafs&4|Uuu6K0s9H@df_u*_Lct4&@AO>VExPpIGQmW2O`74nlK!QyE<~X*133Oj0%%^SQFqbWv!LD zo8imwPQ|kg=IENiyUOaloAEr-X&us7cyAULn+O?3MGmx%eoQGcB~DV}EFt__iC zo$-xn9j6rQ&D9+yc$^Y@!-q)aHZHU_E9*CPNs&fcc6{_l@$b2b9`esp`O{i)Lsj4(X@?rx@MD=_^ zRj-LtjV|15z$j6jOQ@6&C44f;D@)Yu0ubd$L&ygS^4N-9>@fku}A{#1*y*F>7Omv3*d*&QP|CIZ;~GMh2)4A-0+7 zpqv90QD&e&-YA4%OSqYewWx%}y@@xy-vKA^mXaCxO5*1b+UV)AMo0Hmtb_gKUW&Og zaXjMpRq^RXNLz?E4hykJf+fUWj0P%xxSWB<@Q!nQ$r9pvVJfSf6JObj$nmP=noH;a z?b(=sk*daT`~GGlVsMVSW=`} zn4xUUi+E#N6Q(h-H7L4~S&4q{!5be?2pNXBjaLdP%ETKJjL@+-R31W^RZ{$Hf)&dc zG4LCSFC{X~AtUa_TXt3dWUq5vTY$;RhAcvjGG`btyQ&g`t%&Wadhh0e;S+$iwUCI` z^iTG0%)%i;@q1(|Xb#+LqO%lLLYShk3;8FDI9tly6&g)!mf$Rc2a$U!b5OsrU5XrI zZkHm*@Eb~zqkWQ6$2}E$V-EKDM1gc*77^{hKiNjH)eqtAz{apYvJb)=(}vLVEVc(Z z3y~#~UP5SkY~R7MczDc?hFgL~qCJOD?bvoBu4dN|D2x!@nS|=bwi<C7+NLMjPv7~5!-EahSA_1_b?oU@fEmXJ!!0VY`4K>IVh@g2vrrT z>LRpVUUQIME~>K$RZSsPbyY-_4VW&f=M$=WO`K|Ux4{PFi|SlLRb6qaOCzPS0V_mx z7NM&CIMwKGBQgS!-3Et&Es5?nBF(~@j_n6`8v8`P<8yJ-Ut#K@=;MsVy|yP6jz4_+pLmuX{B9ROxS_iT^+H zdN}H$D@P6=hVPegNoeg-_yZbN#^I8m7GAuz3=+&4F4oBqI`4wl!;F5;9^;+Ma-13O z;y=EFwVlJfspLrh8+eM)SjOe?pL6{%K_|(W5!H3Bk$9t%XiB}>sCJM{q^9{qlH#4I zCf7QnU@8z-SW{R_U;Z1!fBpDRTIpPGvLu=;R~f0Zk=AOO!PNqB=j7}nVQITF)hI7D zS{Vjw477wak;DsE%!`?Gy3q-k{AC8|Ch`(Z6Ns-gXNpm{(4e?Toi1V*q38GH#1jfzsNh!Q$GT2-tK&cyLf-+?|^_&d+}Vfip;l|5{P^9Taf_AoF9 z^rlKgl|5B7szE9=*u!#r!Qo)cl?sPbl zByqTe*Gozf!<^m@=Sq`PW}CxITZdDQgoB65;k=Ulc9>b>7$xD$O`h&12uGWA?) zMr)Rl21=Ubb^<74GZNv5WUH<}D*7!(_vEm;a#m;7`7a^qCz>S50H-bVgpJ%j(8qgj+)!hbTWomWVNv#Wqd+IH%xYwVI! zO^LAw14Q9GHp_O7lX9J_MUt#?0`!-}$wntz%9Ybk&s`}({)x6`cdE%VHbRn(9W|vp zSD50oO$I!$wrSC&k}PNbXvRuwBqVXeorzN&F3YwfYrvx}Sp&KcLudPCIMYibogV64 z%lxNW1;ir6ti7?mouq#fD+4UH!Fg({&q-kOB(R-6GjyvYx9Ng0goBwZ9g~JjabjB} zK|;=TW-R0k$6_RsvFe>AoGDeDv@URV+2*V^Eii+7k<{<(X9`qXZ^qKu(?l+pmhw!t zon1uT81s{iubOrlHDh4ateX|lm=-hPq;IiaN=SNn2CI-x$LwYY+iiMbRszW*6-MSp zcWGVR^7MV_LA)WC0%Ulmu{J4#r?44u2}vAJaI;)U4q2NE8RtwaeNxQ0^Yijj=WQ_F zpTc-o+6SB;gSWwE8+n+>m3ApO9_iyn-ubPz{B5=6KlyiTIh*QmULm%{DXXBvDaQ~- zj9qt_b1Ne8oQRr!S?e6mOHJmU96B}QrUcGO2UZ$_=aDhv<`i~_A?G=*tHml&m}fPal{$&MbZ%-@~9!doDRN)ei-(94-NU7CV+@xa7_$D{<#|RP5;-B51)0C8UK@Ib92;p5+>$I z=T%dk$-~Y*cd)|&OMm56AsRnz(%JtYz!wEMBr=nK&pFSETA8^xtzUx_+_L zxxrMePC-v{Q@V=IKL5wuj(*b(DtozP`P$XX)-7ATX7LIcqf>ZQ-C!CDP4qmt_~Nx! ztj6H|VA)ND=uEPX3Z6=*9^=VHEis#kvSvshmROOB7ba7-s)v5mMvbhY+%j; zWI1h_W*Iu_qOn7ltj4r1%fYc*zGnFqD|3dA8#OY2^!Ka@Bk-Yk@v_BBmRtB>i_gdB zT(NrXvh_pH9cd*bdCpCAq`Lfece|%EV5iyXcDAE8K45>tS8HFyMPB^QVPfZ;>%BL4 zZcMnzy~VZFd9&lc?FpT6S4+GezmqtnUWEfsZpB{wPGdsnl%b`JaYaqP*ct`q#p!GB| z&G#^5UXipA#Q5^|puGJkgypfENO^k@j^shm%EAqSy!AWsiUgYw5eYNxKq|hG$2;jAbWD;u{)Bn*y@2{gy?Rz!>%9zWmpf0buqfhO7HXV8_ zH}bj#de=k*kmJW!4=Ba=V_)33^gw!KoY|+yImCS4F*vv4Du@Khxb9hHXW)t)BGVBc zDK755bdO@$vt8-?MJR+$l<;s=H|58>cZ&g+)f2910a=-Ey%Ey(@D4$opru@5-c0l^0?5iB9oT!|sT&!HF zyo$th-k{{8JM<-alcrayyi?^pD&MK{{VLOEFWd3B$}cM4Q1bC8mMcE*zycTt%Eijr z%Eihnl-DZxR0Z{Gl>3ywQ1ZGw)5XUm_^!&wls1eE)4M1KD8p&d7Y6Q zF!jVo7kHz}l_bjDsq*bAi!Uzd{Ziwf*7z4x7GGOf#9pHezM<(KDnC)Zc9kt0OX~4A zGs!IF86@iAi{~STTPSu5GHop5xwjxQl|z-ol?6)fF{yWsa*|T)7UCDEyhM44@@l2n zFX(Mn`9|ff%1Y(!$~%?!D8-&3zt}VIQH_6Ec|iGFh# ziAw(VHf8Q-NbXI@!O9WJG0L-*=P0Kt&r{A-UZ52FiSm}IEOr#~YL!p2qlmvj<0HOG z`3NH0Q?J~s+^6K@hfIG=`LyzYGUAK$cPhWBJgnq1iOkOjfyfg|-VR4Of%XtgQl=_< zD6^EgO5QI+{b9;6%F~tNBN*xDsys(os$8U8s^o)_EbnS1K30o-y;AHv(#5ARxJTpn zDu1es_!i||?ktaY2$8>2{z3Vn@~F~7`wG2eWp8DFX-UIQSMhhsEqiEY*snqD^k`k zlWmrD*s(6>lfnr95MA%l;7nOk`EeFf4uU$d_eM1Wa^hGuTZX0{+Dv2 zk`F6Wf4j0)*{HlrdAG8okH=>;{yAmD*W>S1=3~w*{{!VwC4KNS{!1l4;!);<&?J5F zlNrih$^pv3Ny|b0{%};r%a+WgU+mVkqGyO8J`=%Ajn7ev??l88QF)|ttdh@&v%G0a@udiPuF4lF#kV5j`4Bnv#kV53 zQRVBDwi=PY~OL^mr8!+!FWE+ zPWqLZ${ghY{7^|Z4%D~tof#><9YLSUbnC$QT;*WpY05Fm z)0K4lK>ZoYdCCRKCCW>bbPGZK|59#N-l(LT2&UI5f26!i*`$0(`77nGmGmpY{I4ln zly56PQ2tFx#}m}I@d2ImDt$`7GN7b83hE6}j#Q3So~=AbNq-g8pQpS~xkP!Ha;1_E zEvUa)xm9_qa)+`;NjDeNzgPL7@?mAO@@XYqQ&9hP<-5uw%FmQvC_VU2gZjxzy0W0$ zPdQvUS~*b}RL)VBD(UBf`By8;m7A46RBl(^uDnx8j~M*kre?ks*V!mSrMP8d-o^7!(gAvKJ|SXoNecL_F6NJTFHO5erX{? zn=8@XRt&GG&v?95iQ98S>D!Wb`YJu}Gw2UlZ8yVDV#@x5Vc-4*L3mNz?+-3L{9MmX z$G@Ji>F7p#Yt!QyfA5yq^ozFlHYOEWM|*AhglUs*I=V68p{BgRGu?)}e%^L?qjfZ8 z({Fm-c>L?ailZCd_cys3&u-c?|GBhI{)8rXd&1{kPHYN$n!N3vzhi^no^px1-MVV5 zufXMLENtyQp(Pv$eNr+foS2g0@6=?qyFW{9>fGdDKEI>A=lNE^Q@f+7%ZVGmJgw=1BK&CHu`Z5nO+)=-{Ju6% zqScmLn0Ty9WqsjoYHmxk68)ZIT|8{@6Bvhe8NY7pJu%@}7dLupPil1+7q;4k zr{TyxlJ;`92io4**!|GUoD~x{W5(RvWci0S4NRZW`u6x#*JEvOZ`^qN5BF_tdgHyD znvT8qP}95bZEO15`+e$NLkd4Vb5rjsf0e&xm$k(k%yzU*w6k{l8{I*xt7UV>I~}7Q_J$Ixa+-S7cR6w0iB3(aID)r)o>50ne91d} zJ38&`ysgVNdM`Z~F4}W2Jb6#Ikh99&;A)&dzjl70Y<4(#k*~>(T${ffi#{g$;lD2t zN8CHckK^sZaZ2iS;-)Wpowzw{VLm2c%BA^;+@`cz!O5-mq~Njh5+@xy556QX znT})Z*yzVGvO`T6(}^wN{5?JVN$m+Il50|$>~`zu0eChX6-sSNY)`$tC7ijZ*NH8k zURpG<)iWJh2{T$(c&8sb&r0;&#A8{Q$NDS~Rh>N3d6Eb_rUY(gm$bYI?FQ z5#C&_<|MyeGc*H7({dl{;<~YEZ_|ryw)@Gp0h1tGIPQ+3R;wu3>IkBRlZ%d>m$cY_ zpe@NtYV*3#cF)1Imoj>txc-aHO;cJECQNK~qt)Y^Q+NCPDSltO>x8G>3U}V!xyggG z7v5q+U3YhHN<{m+-tNJ9-4dSO?A@K(}hu`Z3*|?)7h8QZj}sob@xqZ^-rR= zS%3W?S5ggTaL`NZRo%T|N^!3eoY|psa1;i^m+Z*<1G_UDd(=LbR+5?4(6csBm0g!n z-wX3#ZSx0#*V6iBU0>WIlvdeuXU2{vj(>b#@9LbI>%6YPy|-u9`YX@={F(c5Yjf-R z)TE4<6;8ROSJvU*b~&*HXVQ%)hBOsmEc;EL(V92qY|Nehll#F3Y*Io_`txnc$r!hU zWQ-fe%1xWVb7U{hk;FE5KW_6R;fN+CVJ2Wkc#B(;ii=vkMLY+QCz1~A1?PV^{?}zjHE&wO_srV#eA4eClcV#78c-(br|<8;eP2)H01;^_Q9#G zzM{!E8*$7FCx%m|U%04Y(d&y+Mx>0i$8CSPZ=4_6e|3FGtV)*k!MC$hr5Ec%K-UL9 z)`t{XA2P8%TypaIkQTo_^gU^P7@Gb;w|v(FZGXl3(0$WKTpx;WfQ|TJlN;;9?em*u zeMo3`V|}OychU7B5i5XwiPhd+RtT@I5Sh9{bZ_$dv3h*g6DtJgSgJn}D}{Z&qdf&{ z#8{jGDVUKd``z#wn%|sU)2T6WH`a_Ct`a_PS>S;pt`R8}ZmbcRA?xUGu|@>&zP{O8 z8(Ae5VvTt@vQ8wzUOIH0m^`C3Z93Np*ix($TT`~-*iUTrPAqKoVVy{fTPJL+6Yxr_ z>%@Gl6E>{C*0^<|H`fUVXV5m-f7;(ox=vu#h^!M1N855(?ZvWAY!h3}bs~}LL=O9@ z>qJguo%pp`C+umh_5`y|cyUH@&7yrb>qIJSi(|9ho)TRt68_UGMaH+T6oL4a;uWkE zzkl!krjM{vyrnBeQjlxKLRl+X!XN&JcB{p9O2X0&ehdD|u@ zyn1Iiq!p`(SwO{$B78UIClF5XXB}bN053Q1_~Y?d}~9SO>#P5w{5M($EX= z@S7LvQQs0Ss|ZxX-|U{-i%Y{+PH8x4RcSamzwp!J72W;g{n=P~ZwPyL^l0EJQh=j- zJ;(J+PgO?UsHVi7$sr%g8@2ynxS;tU?BYr53D&BFM)&UO`ESh6EW4=G-PE6}3G(0c zWnaJL$9bN}IeIqNlO!C^WSsq2PyRdXYQxvZSWg^Pb_nZ<3+stBrPVccGOYd7=z4Nl zY(256nqb9o9*o+<8j{+R+mq{4nhq4Xu%_U=2;r=0cRZ>q%JEB!ieyDe#mLEuf*BW> zR0TVjF$F0TXS60x!%nI>ebKbml)~BYgnbUaeppzFmY?X2l_kkqm(klVJA`_>5i{C* zZxd|Q7ke_eu0VEiT`6vbKjv1)G}ykR8Li)+T;`t!3y5{agY_lxMfgRx;LG`jCCdCYfm{J>t<1bZ-md|>H*8py)fA7pXhIJ;W+2*Uz(P%yL;mu#jnqFRb5ar z601u7{Vm~z`+HOeYKt>52P!feGoiVD5Bv>>vZ_aB^-S}&CHY<`+BdPsjsWcAQXJof z`!lvbas2RoE#WQub82R^)_IGAuAv9RTPn;-b65OI^I~RJ)se#%b{=tSO@COGA+px= zo6eP{Uw|u3PWu0@wFc{q_tK(MtTX|vH0l5PN@G3o|HhYaA}-A1QX^h2o7ax*3It!r zy95dGFZdF^7_##vXgedmgy&H>m(ip7A8v*Do2$+Pj2Uy0#CRS+sm>XUo^d5(Ty9>o zcV5MqlItYKBfos%mtPa9rfZz1`6E6!A*1%OgKJX?x{5tJn3igLf}g{ z9dO^nsEh51fcpx@mti%-1!UKA@_!Egdr}_L~?qOi;1s^f6b%~mg5f+N?vo-<(A_O6JBjO{-m*y zkne9OwbNjf=Q!+G4|IBs^_#HO*`&N3mtw-GzKMC9PE-9&TD{B3wy}D*giQ5b6Gruk z8XF1uRv@FPq_ZT!^ zMYNbz(PB){KxTo9M#dnQX4`y*7NPPlXU6%=0fSFjT)=P==pw;>P3 zJB8=9y_Yj@Iz`@nXPj`apvY6zzKf~5@a{SbPMkTvQ{ik@0xwaRqr&MZs_Xd?m2==n z_&zH02A0%w;PzJ}dSXdE2Tp%QVs+ibpOc7RK=eCVr-f>q_UzB6VGkdNqVPC6o%!$r9MjjBuPRf(uhOb@@uTo2IQf4U)fr zL(}v&M0{CL^jv_r z3MGHyd$#`X9YIE2_VI-44ec&TLxV!SBNvDo=;q?ScU)LIb8XX+ADOF2`J zleVT2ffA(I<8A&%WJW9EdLG8VdMfpx9od7xDyp1i2dUB(W7d-ccT7}R3TF?U-q`2c z`~}EZDZEy0N@1gU=afCqzU8D+s;H95C4o0)HB;p{OYV6mf*&BUXB`6k0lvUd1hRM= zYu2Ou_YD4J=b-u)sAti+f7)UEn~&?3R)BY{W^vU?<9$`X#P_z5YSu&MJx}&u_$!N2 z4KHCyHLoHN*n-3~R>LbZX{_pQ23Xwz1hOAS`W$3UWAUv_VimmHf@8zHY|8!kx>uU> zBm%6Ortn8dI0D*V+>ZPicOaO-GbdnSIJ53WDC?K}_Z0pi3vKmF$dZFp`^zx1^hHz# z7yUpXvkXHhi#K>>72#j@BE<1FfGqw7K-LEQvjV)mDU0{)W?e*CkNa^H%O5YcU3LbB zHg?1w#kbw&hlZ^|bkN|ItOk)H0;k0o9)L79?kqn7Y~V};tUw9#vJ){`xB&?qjns8NG|Zr(9!|&==voTSe!JGLK_;0h zPeMti%6kX|`1`#wRou8cU8YKa0Zx@M2xNzl&g=X#RZ5w}sq%dUtiXQeg_mAyQ*hiiX89WmLUUsX)Suh!KZ?Ru2FN`gnT4+7ImyW;jYB$(d`{L`ljP(>EMd~SsBr~{@ z0nXqj5y)PT^zR{?l>H@>Saz2T^dhi_c{#J^LzJ1lg7K)AyQvFM@58M3P5TKH&~qc= z*qNSJA+R5cfy2zd71C48zXO5S7~uMuE}u_&a684bfcN>>Z`u5b#|-|Scm@wwActob zN4XfTG>ia^$T2%rr-LYtAdka^#=vuXc$gjPXEj}ldGgi0AzzP8VVO2>n^1@7%t3t4+{rrQhT{F=o_WCHt{ljp-PAjx$0i<4_75V!jTBocD~}57qctoP)SH!>(mthO!HgVi!AjA-^Zf z_V+@7c6by5fmO`cq5OS_<8M61m*4!2@@X#~Liw+={4*TOSU%S*4oc4&1b9pWUW~rj zjkI4PY7VMQO~BFtYN-^V-?9S4~w zW^)cOPe+@R&a>(bE0a3vbi2B=_4U0V|RU)i+jx8 z*j}4Z1>$>Se{G}>sf7);YH^2swq&>^7i!#M8}TC%vEMb~l-~G=DVuB~cXF~JCfu7p zUQ#G+_$kzSuS6k6e4QdU*+!hxha!HX#E5GlCUcu@#ANQXBSBPbg1xcRHlcf&8(VE7 zrS@f6*lSOauNuZf>?E7*b7XL!i}p>Dp1p#!zOvmmvVDGE*>9^fx6f4e#Yq2vuIz!i zd(Ok*vw!LGVN21Id*Hl&2yh=9L?BR#RM`tJg%sU!Z$T_}yL_5e_SJVG(d>n{pq711 zU2OKk$C-kh+}|%kpqaHj>ROH3GGu?xy?r3eTDY&D*k5Z|0^NMfOYGd|vSr-YUyj7s zj$3~EbeyT>znOxZpE%8qdp&a62VFZ@OD7cD(}{mSp;8ZiEZu`ZHC2A=dYCGss4@uu z^|7hP<1hBDUUTzD1&Unt21B}<1+K9Ttth>NnhPvan-32_t9k$);5jPiV@!ReY^}ey~ zK8$krBgH<;UC(m4jGB*ruT%e&+wKpMhflxSMeak)6I%iU9LtVNpiG}Hk*9!prn^68 z9!{SOF&$zPybw#7JjLA^pOs_+X3+SUBfJoyEle(RmoquKQ5i7~BX|B(L$VF^9$~$gyUz+>VsYEd zPW5~Yfw!R;NMX6$m>g$*ZcaRBAi(YOGz3r%HynFWPChj4Rqk?@!%fFJB%6CrNd zV=J?A^HGn0Zb0N{J&ydVm_OuhK>qlnMO)B}_Z}u+<$kO~GOfu=NIt~mAG-gTDASdUaW)8H7=oM~AM z@Ju@of$V0aUx=*n+wbd;fb)zwd7d3%2A*f_jMww59yNzq^Hc73kv+Ek7H=Abh>}|O zorwYCY9KW}3MqRF(q3XZ&#_mSZnoe15EomK{)zIl5!ZPsMUw2vpv;)hZGBBa=VbngLTXU#H}UClfl%07g++ZZ2P zAp%DzpHwziFaE$3?z*$=7u@ecLAKu<6xn|Bm;~~X8ry!~fGTDC{U8E5OA}DWB9`%% zI{?IOjjNfr{{GNB@fS z?@jw>A^)AhTeteJvUP9pRkoAEud(Pj>vL&oM_92mV)^GKTHa`2EZ$aVufJA+uZ4)kdq!1>*t8RWYJWM`H(0H_caX}#J z`UTOb2~+IzA;J$WPP)BuJbIiTz}`aEa}@nXy^1 zyLQ=!oqS&T=C8=P9xEto`{Dc|<*N0?F6a_Lxh4qmnYwrl@>HxjChcN3#H>`7m3e9q zL#3MIN;N`IsnV=eq6X$%33okzTZg-elRYJa8J~DX6B$lb2`Mc7&9w|gz z*G62wXs-9W!jBY`i^_U^tU=LD^*Mw^H^cGfw7~fvEkyjUjrdoKJZX|^zi>1=)}Cg` zDCk_!^%`scg0Ag56?9#x7*8qtm>IiP95SBbY%=NU+c(3x>3S%?8ei0l%xx8a@BEDR zVV-v_T9D!LHCJx2(bVWJr7p5hZ`8RDfT?2o4o7mQNr`NuUtwgev^TM>SqOK*F@pTr z9$YN$2z{?wpq1B6Y_k#cUc2o+g7!FzK0;LP=FptDMR~}hzHlQ4>DKbmuiZq$)j{C~ zaH;UNwS(1T$9%2SnM6KubMT@^Gsv}abaQ1HADoNALtEcmXZ44NCid|)i{uXx z%{dOZI66*fkID9jBxjXHMT+L(i`Xy^U#cNi*NLtT#tE&hdTFtl6{4zY>m@#_My{`P zQO62xT=1-HF^oEEo{u`m%CN*lhYyNmtI^PVUFewl&@nz#n?kvXHUV+Fi5;iq@(~l6 zMWr;ecM#oRlGlbof?D3E3Vnq&TVaaID{eBe?a9|DS`Afxt_!|IWn1SQt3qy3 zt*T9|U6oidB26sUpY`~y?Kxqc%5gV(TKLrGf=}@E*^kmGPIudh!8M8f+iCLI4*j3t zR9k@CQ^UQK^RU~C8=PeQ-rULW&C!^Ba~s6h_|B z^$69}YD8{pRJ_Ay;VaR&EPNGo&$-7WayFc2YK=1$3oG1e^7?bWscW5Stf2Hw>|&vy z^Gfg1ndI&AUu3hxuVXcRi z9U+ujNBAJE>yh3rhp&=6DXMztNVS0P?IYa+z7r49^S%?$KWvTdEOPj6Y;dX>)u@iN zB#rAz=UZE9wd>4z`Y!WIt=F2^w?BnW)*Bi21G);*`f`)*hd(CiL}njDT&d`~f<2P0 z;V;iWMKSz#@Od<#-xk#Iy6;MkHRyDs(SW2uO5`F~gAdWfI{F>{0QTvQkvj0G@`v~9 zo9NRW7*)r6P3(@`cZ;q1S}FI-TxhXS;#S8-L$yiS_ZkK5`&}EiWx3;ovTkC>pU5%w zAekKb-7zWm+SVqunETs;qEuDam|$bIqZJ9D}6tAx1&O%j$gTM zl=K-Z{pZnOerwX^qfH{R`T4#-GG~+eem}BjliZc+*!q)Z?n3_4UoUyCGHIfL*ZPY%Z;p)K zrHs|@vjM~d#_Cf>&J{-^=YCmhqmcU9OMP;jrNYz|&NN0?=T?(PQibY++%|n7Y&J=` z+Vtkg)u#N&oN3pkH^wqLt(2niP8*}yHb29eeD;UPbH1g}&{n0L>9t;MV%H5qe{ z^pQ75`bZuMO|o2<%(KBpX?m~44s*h74FaV#=)v4%Bg)f3N~$`A-ITjh>vC_dg-__4 zdbjF=lorzi(LZ!ofCl%f{Mu#u`cRx7P9HnFM;)sdj6j|#JA+D(V^ zA!WWvmhF;ubsE_#Rf302B73Dw^ban6udX&tncQG}TVxWN3{ZJ(H?n+g zbhIqBu5Hde`Ta?A^LjEo&F+XTYI2Fp%`4bVBqjrGMUm}*E$HIW4yXcA4>>o#$>M}_ z^IChsB^)KZ=vGGx?}t|HUJFekXN7C+%4DvI&EDEHs71_3(FaigmLIS3j0j z>WsZgwZ@gINKmPC-685(z9zPAH|@R;G~ZL}`e3A>FOIoeS)HRdT0ZIx=IgbphE2}b zpC$J$r%}Sq*2+x%q|VnT-RjJ)D#(}1M+Wbh#4_ojsnGS<6xY%D`mI*tU18yc)>e4t z>$RH9R0CYTE-q6UQZkjP&@#Qs)h9Xknlinu>bp%?E2{6mITx<2*Y=oVQ7&!s7c#66 z&a+m!xe|>Nv@Kio5u$RBoX|9Bt({2ofId}pPB0p-dS2wb771!#%Wcg9t@I8nwNtZ% zZc)PaCYG0=JZv|KW--o^RJziP5one*3v?2?%=URpDU`U~-)6(Lq8&U^`jq-p&vEtj zOpZ1v|7O;?(TQs5>gdX6+aHIEgpbWvwzi(%CI$?%&kzZE8SeA!@75h9n3 z3SH$)W9ma2w3Ft6wGD{BH?c#Y64jc>EGng$y@Ti$qn6fHiFK2p4I-T3?zHmjmP#W8 z79_}#57O|Lym{SHxkcV4nuOEZxhof0oO?|yb0Ku0$?)8jO8!(BB&gaxRp`sEMr~z< ziOMT7W9@4ct%jm98LqND=^Q7owp6QdGJK2@D@Nq|te!&hfYO+Qqc#?GC&~kYbK}02 zZoc{OwM=?VHpU_6#(jGnxw86JJMv{sZC{&rK5Y9QrgiQ9%(tzZcWy-6Hg0a*x9gE9 zqi@qATgKG(w0+{R7vjFP+&*Ek8|-iB(fuvudS4Z3Og6s4jm;*tDu=(i_Z4Z}{EVs* zxq(pe4xfduMB}pXRakFX?K6p7e=Ib0l`|C!54+XmXwYq@);iNzLFrRQ!n`@+(jQ|R zGZ22bjY6XwzBwB|5PtZLM}Adb&Efb7aIJ@x9U)A&j_^TRzt*IYbK{Dt9y(Gj;CuT> zw}9U+4$||!6B{=heAsTZb5VUqeww+ZMs%g~tu3|2b!IpLuJsKjHpVUVu-@=<<63{% zr2FBINjlqUZd}oIL3<=y!(Xj`iemWf;PYrezb&Zalb6VcywQ(bWhzcIv3A$PAHe)h z-M9mo4m_&-;r;q1YMftRZkgZZ$chqfl*9Ha9M4-|yPE zEo-IXD(jTF@q=V?OxT2Dg>d(?N$JKMIC4LS-7ma9 z)yCrH#v4}*zioXU4d%B*zez+kKi~I9=4?{m???7*63&I!pEPq)+zLc5J{9VYVTZp_NbYEjz1i~@_=g@H_VsV9M_(^_zQZJCZrqzA zV|gi~;wRf6*8!vADPz=%6P+8^JLH;uh|Irea{5IR+av_VND1BMOk;#P6Ac7MrgXg7 zMp%87kOR?=n8G%jj- z%1kNq=ZYzFWTr$FPVF2;Tj!!B2OAYlHMGw06^+cFPq&ac2PTl&j#YxDv|DQayuR)$ zWqZsdr5_LBtiG+od1g(UYZB7%2@PC7#qD#8Y#z!PyNyFBfG_*z)7`D!e3|l8B%oVkfgW(@pRJ|N$ zUVV*f%(ULbHeul@lgNa*)Xgq5nP9o8`ZX&%90-3miA?#+=yvUlG4AQR?3GYdQ9 zg!v_w3xzxAR;F+@z@g?@BIyrVIlZKroG_Q7+8%tu+_yz?XZ72wXy-+f8y(LG*K=g| zOSY}pJ|-wQa*$CBMYZ#%V82kJh(f}xjuB3Dt0ROkdGf&9!%WINoU?Z;?(q<q|-a7k5V>Ub&IBls!VP+QF)ZV;`l{n zT4nOEiDq?vX!4|qUsl;lG|b!e3Zv##UN+fjvdd(*iC+X;PZST5b6fJy?9DNr}ls6Wt}3nUtGUm{gkhz z#+FUT9>09nbR*11k%?~$?@ubcr$P4sN*LX$-%i%s-^>k<>)t1LIs zle2oDMh}bn<=;)OeCL{^=HvYrP~OeNxn&M6FpsfhRInb1tx_i=bKz)GRouzCAcso{t6 z;nPRMDpt zG|p3|`$ch-XEZPQRGeo_HkoWT@r#~W)`P@)G^^O;N|T8ur6zhtce=?;les2($m%we zJ4_xndBjAwZ@M+{%aQh%TCUXmeZHyX_4Y&6?OH3duhV>6SDo%Ox!dGklVv6=O#E`B z{1lnbXq{5?_4)Ze@a6P&^~qHxDzl!S(*vt&ldqek_Q?;;=9eRt&ihNv&)Zctzs;!Z zzKjQJTlw(IkxJ+NrRL}DYLh2THkv$dvf1QClh;lDWb#jwk4*e>sQAA>MEryK{Pjz{JpEds1&6j3$^piUB>lZy8sQbs%d`c`rsmT-*fA4y*`$S(x zi{_RR`~O+eO*}|C-6!ffL6yxfsrQM>Uvd1BdY`!70yg+S<0_MfO>_^bFu&+N@Yg2W zOtzc+-XwaTc(AZN7RN7oLPYm&x0&cZsm4V2iK|Rjo9G_t5fi_B+W7LTd$T)C?u_{H zw$%K5K8GvQqvmUU#NVfl@9zoaM^9w%{Ht>tuz~}kvL)f>N{Y8^#_{*m2-fpLf z?(1~lx8KAsjSbhmVqGL%)ZdmE^)Z8J@-HJNKN-^4FRDxLS2nxD59S)Pq8n~p(#`K;;ueWGs*@6X>yr?!a?UuM_- zD@-0X(QHqx$$Arizp=^I{k?`JleU}eF!9U3n_l_qRg=_wynls7%jNB#rOdh~^2@)Q zUS)dB#J83AE1TLdwat9E%CN^|uZiycvh5nTrAfl%WD~y}DqiQ5cu`-``?#q6@0O45 zMWf+b&oW=FP1>5YGs!jai^6=_Qselt=0)Nc+xirfGLx%JW|~}UqWhY8CjP!f_Yu1G zztiMy6Tkes=_i^mM|ByUz8HY&ceXH#9U0|X*_{E3!Jw&+5q`Iq2N~cZL6Csj_HF@09d ztl{6V>66N5mrjmNI-|H^=8UN`CtRJFGOc{_tVFjt1NwI_o;rPYqH@NJ@>z)qGp|le zzIx*1($dML#eMTmOZ3j~)%%*h#S^DZFE&@@(UQ;OYsLWqD;*L7T=dweL{d zx?LyO+410``MVrv?YJlb+^s{#W3#?kS~%{<*bITI-m!_0n2< z{X13vT$K8?eA$B510BkpyR+PSE4S_vUm(Nq^tiKse8WI;zc=05(%Ig=!Bx920bff7 z{N;wcdYhs;e?6Q(m-3Cc%SJ8l^!M!XZ;LkBDc*S)rC=o3;ymGELP>Q@5vmQU6ZVKXq)H`YQ}j z+0%yV-zxnJ+NkVdc+kV84~jyZ>fCEC(dlrOx zxWT3ccP|L5A9j0;JFs+AJZ+9~`)IqR$W!6s!Ke^axEaEtBpH)1|Jji zQP)rL;8*Bw6Nm?x!;E`I3h|rJSr~AsbLbAZ!DV4njc!Inp*n+eVV-$blB&^?33e`Phwl!5;fwbQsG{jJDY*y2bh+ zo>v=Omk63xx;lI`|7OSVR2iNg4?I-3;LJ@Az3&jkC!`0jiao`e>r`4i?d;Ylt?Xdg=pNOyg z&Xn5C(!vcbEqFMryZS0TBfDz`cY1O*cj4gL;|xX7rA}I~%k^J)y>OR zzSDxS+OpGv?%|1$Q~0|v9TC(3VZ$8iR9JszI-j%PSAsBQ!!urr7M7#_G&jy=R_`n< zQvGQz)T*(Ka1` zbyFk8!|S1VaBCRzz?0m`?!Xn=PjTzvIqrL5f`F5pFGhENVEawF^MBw;E@xoy<&=}$ zj##{7hmIXOpBFSu^bW2)KWLVB_JyaUrP+CK&V=hH#Kw;wJ#_S#b9(iUmCu+yHR1lv zo<3{Z)ajE;6Lw!2E1foFip3gr?r3-4IdNL$%*oeIo;hnmxo$|q^n=F5ENZX*<0~Ux zlo&sg$|lTI%nQd18WP4(pxyi)co(jl<%8VyT2|(K{P>Y!Su4(&Ryk_&wM7#qmQRk& z_Ia1im@R$q8O4Jy96fAw_<#K9$(6G!unZYJV*K!F6N^XBm_2jSdQlwUu7+H_TRGIbp}+NxSnIkQ*H?#qWyo*rw^R28FVPKup((U`>G zguBUi!vVc|=bx77Hgj_MO>ofm{gXqR-HD>#vu~D zPVd_%zuy&MJ2mh>t8B*1%0vT`wMbZa>lbT~!U>ZqXUsg<$U$sU`Lv4h*YxQ%zH)}E z%#7KUy<+ySci1tbhm5n{nmf7j`ijY6*0iSUw$VdkVFqf8!tx1IV^hj!OsI^h#@2Fk zO0O@~7SN}+byBi?uGhmdtGiv^uCrV;HivOx2aFyUbJ6Eax_(luV(^T~Q|OTB0LZlI zvns8v!p^8Dx^7x&sdcxSz>;e#7~r;%L8H#=6|1yRxw&wLZNSqehi!5|?`jL4Gx7R~ zG26&1UA~uSl(0TaoXa>*V#LfDlP1raHDl(i?nk1V2lbBGh>k{v zV)1Ua+GMbG^5i+EUf3s=(Jb@ArfIFy+r*EF9~-ob9~VD9-d?w~_MSj2_OUH?s-D*} zyG5+C>3-3e*f}i|3$t#`ye;GQCX3R)9NdximH42R>*5XKY0T_U@!EN3#xqO?wai(V zers@B+MSkp-mL4duADH@SUEFfnP0Pl+kRa-p>jejZ{jQ)Qj;O?pgWeD{u6?u`(2*x zJ@rweTZD6>(9+2hXHT`Ab;=CO-mOoVIMH^gm`fX4%4bZ9suOI#n>yLbSfBntOZl|v zlf6f)WGrvejH|Dntb>edtcCe_*QUhV zXdCH3=OO&(EN<55$i`R3Nze26u^@@;P7 z^L^UZeHvShEwP7(^0mU^!+vaf)Zd=p#bODw$zKZ-?{Ax}`!u#1+hqPK4$>}qekbZL zdxt%TW8Y|(KN}iP`umfuNB#A^-L^GFVDVwUH$CcadDD2Z->kWl{@%BBrSWwfV-HCk z<2Oda6#lQ2cvsyQvme^6Uld1@VgD?7g%A0i#p~l0;z&K-;wipga+cW~tyhd{KP_!7 zQnVhmRu7d`?b6o7x3lULDRykJ`8z3+fnOCPn^A0!{hsM6GaeuDmt*V7vw^<{W3dHh z^NaWAb6w1dDZ*ytrA*-Sd)}+n>>pwf$gDsL9Bj> z90<%9xIL~uG_W^Vqf6lSjCxDpw(O`L+3?I9#MBG*OAtHSwX51QT-0OrOW=Ais<)|E zY%Q?ww4Y#9o9bBC+S;Q(y3U8Kt^Q-tb>3@j_5G63FD~DMU!iucjCC$O_%)=?QU^T; zMo)4F@#+$#UU0`$qh?m^glL_i^0&8*S3Qwt$4L8&rCGD7<-}v4w(m4+-Y%k5qzCq1 z@GLkOj(~dMPktuCsjw1W4{w8Cg-hVq;kV#A_&9tDJ_lcbFT)R@jsvbf(8ej8-Upro z^(kt_n*gtddQMRGm*5-l&+tRo)OI1o)AL@A7f9q4OjM7Q1iyp zH8(6jy+n)KPqgj#Tzj`$O2DfX@*AbHaa# z{r_Qq3;Vm+|AD=$6a7<(!9>DXstza9Hs*#8UrYV6;E zk70ivZpZ#Q`X2N;(b{Q0_U3l6q;j@_$B9<{PUxq=zVLLy3(+rzW3XR|J{8UqEx+ps zUko3{{s{U{;BVlY@L!^(kK2h<*uRW^H(ViFeqSeiJ=_9!!oQ0a@1N*7c5$n6pDda^4}A!{68l8-8_{n< zUyi;C{Rg7e|4H;`(SHSB#{M?^EB16d(JB8d(aLjzsCGm@1-&o)B0Puii_yoyE3r>S zuYmJJ%cqL)YV7yH71+Otz79SCH;I;hvuNdf9llBUUZ_hU#Y-10UK`QmMC>PFKL@=K z{Swh+GWKcM7osmhuMtfigb!o?F8X@-G<=@$SJ8K(zlHuj{7AHNr?oV(avv+2Ef>8D zdLK9d`?=^N(62VJ-ucNPrzsCMD`fjM-UeI|iOSEHfHp~&N9LE#h1^s07 ze&}bQpNoDz`WW=9;SF#JdLcC-z;~|A9R?IxKIdXyrXt zw0b097wo6Q3$TwwACLYe(ds<|`vUBX;8(HVi@p-Bf!`tgN%Uvo&#?a*{de$9(eitT z@VMQmsQh0L&E5gM9~=g+fU`u4cOCj-(dvCK_GQ?=i~R}gKgRxR?7v0diT)ORAAUf1 zy4@Jbe+ziDXywgC?*e;?R<3@8pO5`w^l|7@;Fqv3fQzu-Cz_uJuzv^p58;onZ$keC zd>Q_Z@ZIQtfgfPkt*`3S6dog5e#ePcubyx)91E`&E#5Wgx5Edqe*^tT@Fnc8pzlMk zLqFQ?N#*ZY(emvfTDf|mpMgFY4u>NNzY={K`b_j&MDu$)_T|_gM1KVR`)~t%n(!CV ze+ys3{wMT5!w*Hv=VQW;vcXA}za2b5w0d<#?+FLM!J?%9 zpPLB37yJF_tI;2Wk7M72{!8@N(BBfx-@DlVg+0Rt&{Y2BqSdDZ>;s31mhM9IiK4}y zihcw98vKT6@xO)sglO@ffj`Cm68h`#Em7qoJg@>bfhgCntzL7xg2h<0we zO|*M}JK&w7m17nBhG_A=i(V^Q{LS!J@Xw;f)1vDUyS;a`%SlH&Z9CfL;iw^E#XA-D zf&<_{I2?|EW8vkn99F>V;0^F*cpF>_?}uN955sk^7XAqS1ilD=4gVkf1AH642Q|K{ zdTKma>w~ z9jJFP6|VO!#Y~MW8Joj)Fc+Q(Pl9K`bKu2rG<4%x=C2fe7Q7DX9ZcnSGrSKz09V5` z@cZy__zZj={s#UQz7Bs6{{jC6J7|2&@;?!t2QPrv!5iR8_z={4h)S>b{=~=OkKh)l z-&s-kZ{hFYF1Q>18U7Xi6Mh6UG_GcTn!%&tv9LYt1iQmiVLx~}914fSA~+6~!E#s$ z_5Pm9u>jrz7eoCXh{9LGhu|a7k2n4R{R#Lqd=74bdXG!~+_1I>9ESLk^z+9MsJz*a>7@h|&g;&5bSPpN5H^F=0Qus~yZTKAg8Pq#YD(^P91MY^38W%J+hhKmlpx$#)_{s2e_(iC9Y80;bcEqvpaySW2h120oI2X=` zx56*O```m`HCzL0;d=NJ_$+keqE@copuY*pc_ZEcwa)F0q4V;;g{i8;c~bNeiMEhu7?}oPvOs@8*jCIccA|jegM-M z$IOC9!((A**bSZy2gCE>MetI11uTQ*@OpS7Tmoz0O85|b6g~!j44;NC!e7I;;JdJu z#y740$G|VbL2xp3;HB^i_-*)I*hJ%nmQPbS7G4gY zfIo(r8jrL1&EXYr0{k}oE^KPoZi?Rm_JgOx2IF!TuL64|Tn<;kZE!nmFurE#duSZX zm=8~bXTk|^GF%GphmXKV;Sb;wa5LNje*=FD--hqOf5Et26RTVo!jbSB@LTW)@CmpP zZh~9kHuy0N?1EPQFNUMxcj5QpGw^xX)~=D2?szy8UJGxAx52N%yWj)xLAVuegPk>Q zWB$9rvCxelnf*uTKY?4|R`?ox1J=R)u#?79%uiQ10v5r!a6ViIYvGUJPvDEtjo+Bx zSI}RBd*EL90sIi2r129=cM3cUo&!h1G4LDkTQIKi3QOMvwt~k%H~wPb33NBkV)|(G zhu}A%8y~UoSJBVVIE3kE!3*I?_yBa{8y4?x=>LFCbl-3GrZ5M#fhDjMZiJiQ@1Yx4 zFh4DIe{O6I&w}T`5?Bgr;Bxp~_;M+{tEsHz778Z{|1}r{#x~e?O-lE5uOD5 z!!zI@=*A1o&p7mA_$4?4&VyBODRkonmi`g+N8yw3Dfk@x8GH%80^fmuhHZ48ZhqUr zQ(-Sy0EfV_@N#$+oDS#1o8evXzu z4fnvm!Vh3pBFrxv9u1F$?O`X_2c8Dcg6F{Da0DC+FNYK16nHhf23Em^@GkgYa5-EB zH^VLPH}JP`58MksfFHulj$!?q!`84Z90&{Gm2e`Q2Cs&*;q`DatcFYB{csIj3m=C+ zf}7zM_#60J_#S*8ehh<7VZCx-8+al-3Fg7xa2UK07Qu0F5}XPv;T(7?{4%V8%i*`- zci|7=lki#iQ@9=OfPa8*!o6@G{1AQ&GfoWKp&4uq+rkrIM|d*KgZ<#?a1cBf7Qu0_ z1eU@|I0sh2h43rzYp@0`hu?wUgX`f2_$>S>{3ZMid=*xtb{kf1@LzG6?iwi7d{Lhf!~8afKS8c;1;+Q z?tnYtK3E6SyV5T3D0npN08fM`!#sEnEQA-qQSefD1-u$w1Lweb@GJ0Z@LsqKehYpF z*24AhIruZU4Q_{jgl|E;5To;NI&2P)g1ImOPk}w*Kv)3B!pq@AI0aqC zSPj?14R9~q2ai8B^xqy1g~Q=!I2PUrZ-U>4kHhET3-DL)CAbUjhJS{Cg&BEad78oF z;0bUVyc#|YpM$@GFTovfC)@+~!Y}j;^XmY=1ZTjX!(YPJ;qPJZ{4jlgcqhCYu7F>M z--6$PPrx6;J#a59=oR`O0%yVN;BVpY;BL4F{saCCw&@-EYX{GQ=fHAU0q=#&;1;+Q z{ucfYz75}le}n&kS$)F%v*FS3SU4D-2QPzH!mHsm@M-uQJfUyszau;q_JRZ8K=>s% z1O5a)3*U!-hnMsV{a*&B!K>jD@W-%K|1kbBup{gOd%%1+4_3h)a3}l-rkxi0JsIY~ z%ixu89;|}3a6SAv{3U!H{vN&s--T%d!hADe3)l*Fgk4}?H~^jv2g6bD5_koi04w1f zcsu+GybnGAe*m9=o8cC?9qxdCfN#RT!Vh56)5H3w z;Un-#_!N8&{tUhW{|NWNI+%H8SfA#w9n6K@U=P>_o(3;~7sFy$0;?P5bKx*J5{`kB;WT&+oDFY zWv~{mhrbY;#$vyMufW&fyYMft4(^A|&koZc1>3^oVMo{n_JH~DGVsE3~S(WxC*X@Yv5YA4%Wi;a0A>3H^HrN8{7_ez@2ax+zt1@ zy>K6_gZp7tJZ#5om;>9ub}$zvpnJd7`Z*uHFB|{|!U8x1j(|mQ94v+<&_B;ufnEvc zz0e8Y(a4*~k>)?K8TN9h?isR2Dif9u1ndmE z!5%Ol_Jsv-2pkHB!x69umcUY22Fu|bI1g6Ag|Heffi-YBTm@Idb+8t$ha2E#xCL&7 z+u(M%1MY;o;BL4F?uGlHP84qYhgmQi=D;?v9n6IZ*co<%J>UR15Ej58a0E6;5b+eOJFHXeZIB=dnKF$ z=fNtt5LUw_um&!NtKe$54%Wi;a0A>7x4^A%8{7_ez@2ax+zs`uGxft>xDVFB{V>Ze z&=fBl=0N?PzwGT`F4XUg$le)tgFT>rKVRYcoqTZs90-TP;ZVPkuXy?$Cb0yT!ZKJ6 zD_|w8f(zjyxENN$C9noAhil+kxDM9B^>72+2sgp4a2wnXcfj3n58Mm)!8*7fX4$o| z+94a}z&5ZQ%!Lhphr!b2WA6(Gz=5y;4uSqT<0ABNuo$L3e_V#W99FRPd+zPkB?QjR&4fnvka38FL`=Ni%IXf%t zryS^hXTr+c4m}qpVCr+wJ+S9P_d67pz5sm)914fS5wHl3gT=4}mcrEMr{`dw2dm&h zxCkzW)o=-11y{p0a4lR9H^7Z>6Wk29z^!l_+zEHV-Ea@w3-`g8-9u`BNrzc58|J_^ zFah1~YgoE&=sjRQ>@|SOeYfcUbvX zp|6H(;99sIZh#x%Cb$`Hfm`7=xE=0*yWt+V7w&^~a6i;fX1V@>?sr10+}Y?kunlYn zb72B@hTUKfH~3jHn<(`fIHzXxEt<)d*MD<2lqq$#F^_q=zcH7+NBM8 zJD3X-ururid%%3y7Y={}VF7f%zoPy_9}dUCVpsx8VHqrk6|fRk!G&-UTnuaAa<~ev zhHKzjxDM9B^>72+2sgp4a2wnXcfg%+7u*f^z`bxEtb_ZZ`~4Vex9n`rPp}P4z|OE6 z>;VVBfv^A$fkWYNI06Y=@o;6Ri^Z0=L3#a68-qcfwt8H{1j3;C`qdb9K)*!7P{!-R~V)`?f)E2XkQpc82+|FB|{| z!U8x1y5C7M|HIM8!D3hfOJNx-hjZXOSOpitMQ|~!fy?14xEij5wQxP$05`%-(7kVF z<#+F!8MkBK0e8Y(a4*~k>)?Lqe%HzTr00bFa?sy*vhX&9CtzpT4fcTfurC|{2f_k4 z1df13a2za#Ww0Dpz)Cm=&V!5KVpt8Az#6z5u7a!K8n_m&ha2EVxCw5CTi{l>4Q_`! z;BL4F?uGlHehAg=A217M!*(ziCSYfn5BtIaa3CyzL*NKl1joT*SOQC71+0W~;5=9b z7s6_|1lGXia1C4w*TGu25pIH;;TE_RZi74FF1Q=+fpu^{v>(k4+Z$%VY?uSvz;-Yf zCZKz-()N>lboYB*rVl_L2n*m4I1~~;5a1mS#Yv6LY3a*B0 z;99s2*24901KbEV!L4u`+zxlZop2Z24fnvka38FL`(f76VSi=A9M}fB-yO4d?~L9J z_JH}YFD!sV;7~Xmj)3m{Rr5Ozy%?6jQdkDdVFj#&Rd69(1Q)|3L8{sCn8E%1F;WoGv?t;7F9#{wWL;b+BJ6^#om<@Aa8`uu!!UXILyTKlC02~Ml z;1DOP5gZ4LVF@gSWw0F1f%9M$TnMY-5?BM5!&PuKTnB66dbj~@gqz@IxCL&9 zJK#>Z3+{${;9j^7>Ib!5|G+Gm4ckHY961joT*SOQC787zl$ z;5=9b7s5qwF|3A5U=3UjSHabA9jt}x;Rd)FZh>3jHn<(`fV<%yxEJn&b#On_2L#;y z1Ks=ewmrM|>y7QO=fVW+4D(@MH~Iaj+PcK=*qI)?a1lh!#%JL?uW7C*neOa%!WCz4RpWnVD037 z-@%x`-Whg-JzzfU3k%>7I1~3}VIne!X zh1J*nZiO)ydjfWb`LHh>00+XMa5x+Ri(m;Xg=MfDR=`R)2hM|4a3Nd-7sDF39Ik?^ z;TpIWu7kC3J=_2{!cA~1+y=M99dI|?1NXvx(EYB4wQu?t!hXqu*)RvTf$d-}Ou)|2 z{qBbO>x(`B4ul182pkHB!x69umcUY22Ho#=SUwf#m2eJpzvE%yRp<-hBDfgVz~yii zTn*R2wQwD*h3nx4xDjrGTj4gi9qxcT;V!rr?t^u3KaAzF|G*sB2DXE_FabNmeApKb zfCFIx90Es(Hf~)6-S3T9yA~5(BHCPSDXil;U-$fi#dE)dW#M+a5KFUrIy-DTe*@7A zM2lC7UM5=np8ZZ6kcce3`tGOrOzi ztNkC}a_h&5g2!?;RGgR7z3tY5?jQWB^{|Wg799O-$xS7(#9!XbIsf9l@m5cl+-%z0 zZ?>?obi)4dX7dXytkW|kw^-PYH?vI3X&q`Wy&3z7iZI`mBm8F3M^@1Grk|T0Qwpv!=zfmI`T2E>OT2dFo%}ESZ}OfqORi;wiGE zH@Q;5>6wp7%WBd@T2|&N%P2j)i9S?mVfUD3aE}njvvOUO^e;MN`d3`K^r>cS5)Vek z-!whr4AWv6GcCq~jMwe|{EVq)xH02JTc4NlO$)st<8`yljb-Y&+~Csq_f5;Z%l-vr z@yiWa>3?FL)4(z(ek`M z^J5p9-b{@g{42AGMM^s{tC`w3_y||o&AuV^W7L+h%mqpu%W7`1v(lA!^LR%y#V>Fb zw8*h){j(*mC#@X>N_>=> z?IFt`c9g5Jt>q|#kNM1(W9eT!J&f`NLoD7Z-lgTy z&4ZR-XgMaMReV%DN6&|Kjx}$7mKm*XZDT>pGn${-e3DcX&m?r7*=FQFCByRSM zZWbxmCb}|--9)i%My0t+*7WE|+-5C8hZbdkP5n2|i=Ukx=5SK>u%lbWTgMABmY$O> zx7kf%K~|V|nw6@BsT4(O%f1cNqvG*lM=MoM$Jnr=_3Njt>LZ+;Jc>a0a| zPmA5?s0Orkd$6>A>13<%*a)GUNqX$B@ewPvrsI(X2xlb&w03?NAPi3iXl+~=AY7IV z(3*BEb0z3#7UrR~$}m7s*}?!@NiJdOM*7kPDxC_~+aw+vDY)Zitin;nb8)mXB#a}d ztZ5d%=q_tiU858zqown$MJ2 z%C^MBVhL&#%Qnq74zbia(@iXvpcYar-%`XfYjO$8G`eA#0+p%1Njx@Mps@nqtD&Dj z%{3~FCD0UsZwg|mF^a=j0woU`mON0&uL@%clssrya(ni?eo>LrV)-k@&L+00sMz7w zn!nOk-I8nn)7)D92CO*IC90R&ks&RXssHg0Teh%+g*yY99zW=(rDK!MD6W_}W2$|g zH8Evc`Q%xNZgU3o?_NB0`s_rd`_`|0gD>H~&0K7saCRSXzNT;S#A(xu&1Lzti9M%I znxs!upE`ZU^vS2{tGzwlr=ELSaPqHV__XPh%4e6_S7d#RVHghhO!Ktq(<=3e=DbPP zM6p?wrFJ&TD^r{3DgYRU|aqvCK7J@XJ`d>q)_Nd7V0S zIx#r)<}SfS1A~s|w?8W=N(84Sf~kqzf}lJR9Fqu|YIR~F=#U87BrL*(iJ)&HxJIj& zCxWgC`=(DkZrMdYx2-QL+jp1sapjSH4)UR8t7juV>m8}9ebl*f_NO1`EG+&bTUnzGVj&AV%>jS@HevnUR^9Ao@wngWTE*f7r zXxQ*Eqs~2YU-AA--y~0#$v$O0=E8F?DjI+8s8JV>s{cxL@*CT_UOB{v+x-WzQ$F0C z^nKBwi-uiPSl{f!&%Nk8YkhL!W8Muv3GQ-ImdTHAyS8`Rqcx}hdb;o1df%hR3?6*$ z=+UwIuYo5&+Me|3R%ov1cjFKA?!N+VTb}|C+i~XcY|7{ zFSNtKr~B^qA-|ZN?3>7Eum4wmHaljwhdNBgGSoJ<^bL{xAD&9=`wwPOJby|`jpy3d z!cQ{EYDBzzi<6pf^t9wpUOg;cQxm^bw6?iyQ*4;kE`&l+expr%8EiGS$>eNb_(<5r zwjTATdFJ(&Q2x{g@+p7gO``q+tN1>%`NfA_V+Oyjun#QWiwDW~Y72|zJI*%H5{s*R zW%v13*?QF9b5^K?+5FwCvs{M(s!9 zJJ-6LtY6Y&9ZZ>%H278u4f?KibUE-l*3p(!{j8B9OJlxct^CzK;i4X>UjjE;6xFTK zB8$Fz-N|&dQMHM_Tdjc)zsRp{L;T|MIq<}pyu7UcSoNfXowrji@yt>50?;y1JEmC` zv@fUGJZlwP2p7S{P_3&mu57WT-O)lz>U0|_ci*n=BHB)?W2fTvg1Uc^elAp9rH_Th za2l+D*TMPFmB-TQ*rN2y;Dc}t{4V@4d=~x;{t{{*lb_$gH{fo#4<2J3r+A&A`)0N2 z?wi%dk=V6ADc%gY0NxEB5S!RHJmELQX7-I6xIwh^&!hhw-F@@g;=PK#i*Sv{DE?p3 zo7oO7{Zwehcll{=QNFJKjM~1WCtzoI3hW6_hxSt-F8&ZW6pn(Iz$@Sc_$4?4UJK_! zx4l_8-1cVt8g|#erayrGAawm}_O<9w!DpcBUkm>Q`pfWD_y+tVd>8%&{u6!#-PoJ? zYZ?#h-wL|z!R+nPJHhVoRM-!m4&C-*=?c-uz(akj%56s$e-`oPLXGdK|89dCu#^5@ z@IJT-u7;_<>EOR{r4c@*ciWxu1@vFTm!aF_|K?Ro^w#ir*dBI= zZhN(KebEQN0_cC6A@y5Wml5uUgf0CP^sC@(cs;Cw3t{SSFlazi<=23(_+9vY_#}J^ zy5nM2{r+T|jZ5eEw>Gqs&K7C5)9G9*zdifs+YCVc(ulc&zG3Xc&lTwX4qN_r%@wq_ z5)ZM)N?rV1f%{RB=v+bYftt48g_fY&;v za|O0pSZn@guD~_If94AQ|7xyaq8&{B56%_z>i6%?6>N>p73AAo!36_@PMRwiod|j+ zf+?CH_);P`Hqq5=liW-}TTKsKkO)po1k;%*I4NOw4WBqu(5s&&KpH(U;3}ruP)##j zIHPphlxdS^+LTD6X9}+A)o*-dESxV$j+X!5n<+T>J-#(|a+v?WVG6-!1bX$i)=uWx zU@DEwyCr;h*6 zJb^Xy=RQxM_t13xtMO*t2TJS~@iWg8=)JW6U(6E}wXyMG8wgfCZ0Ijpk1AWYvvG21 z>^y;+C8@BOui`1?kRKg|v&xLhTVf*@zj2)?F2 z82)FTz}nH~4cxfxf945d&uF`_@z?*%6NK&XpLv3?9scLe6ZB!+KOFr(>^wog(|b2| zox1t3OcxV3XXH{6kNP_<|w^akTxNfc<;?)%oacT z;=NOnwq0+wa_<*hy!Wc4?N#^ALHxvv_g z9^Y+o;zgzn@K-TP#bR>^%Pc7PwuPnnIfUsJXcGs66rh(5lJ6U=S3r7`TV+end{|mm zlfNiwR^}2z{lvlTGNxzl7UEfY*xsfJdO2fynM;>`ry1Q#20Kj8$TuyPp=;3v8Jby} zpE1M?H)cFz>+>?cXQ4M_{Msz`lEK5K*h>a$Ov~)5^_g+ab!VlkrdjF3?0?fX!Kqm{ zTheAfH!bLyC8H(|G&vaLXXQIJt=adb_CgJswUf8rS^HdQdNaMc5cJ7%6QA~yK@X{Y zah2Un&j$qkP+K-r5rY0%Dnr_dIk8M#CI_cw>5?@oT}5dg*Mvy?!no?IWo?L9T(4s2 zor8<+w3UQeTd36Wi&bbhkDyYA69<|sZ=q7hN2(4pt-vic0Ua-r*HOBLb?+Rsuz;Lf zO{;(BK=X_C&Ve#JN~KhbhfzAjT7B6J>1Td1jMBmIpLY(d4b(%8e&^sEHCk+hpiMV? zA3$q*0Kfu-amfI!T@?lh<;ei8=~B&72vsJbE3MsaVgZ86_L<%}PyzL>fG?jPRnBMcGFF)=S`qAEiytzKke=>_VQ=Icc))ofxIOQ2?HzGlQy z-L4H|3Dhmk*Ns?J7Ia4#OQ3dXzIMd2kmSg( zy+HkfhV^srLR=Zf60S0lFHw~W%M@sJriu9ys9(^qenFK5-4@0Ys9(^qe$jhr_i)!i zUXfU9sbw~}CD;C^xwZ7rVE+{-x_GN^Z`xx@pWgrOw8yVv@ox6^Lr|G_qAkJc zHt})Jz~JQb+xI%9Q^%k%5uBL_#wT+726OW|cM3`q!3l|=SyCUH2u{|VNErL61&QF< zn41i7sV_K*+X3?-2M*TrB)e6}-AjMg$&SNLb3|^`$M?-Yy?@N!UYU43Z$P*Q z?~`*Rdc6NXZ%fRaHMy{S!qoaHjZb`A;t*3D2llr;fT_N2`1*wFy*|C86DXfB3-T#u z(Zc2=IJ5SD<{b(h4?l;w5%uGL=0-U2*lETs|IRxU(esu+yY(=yP4O+19NoCN zk)0NIaCo9rGCN&|i=JzW`qOX2HD+$)L_1mQj>j+FpT_6?y26gNg5MZ9vHP&AEi9Vv zPKmA5Zj@jhThUJs~G=AyR*lMiS z{3)JaeAw5_5cQ|uRPp{kX>LT{j9B2Em=C}DV2VHeCX4E)@_o|W$Y3kPvnl;1pBqd> z-Op*s$Zp)+$aNO4Png90_vL%VG{3F@{r0u4EB&JW(2_bgqTiD7?b61=eZQs7jchZ2 ze{vqee?BiUQoYz}OITvYc4oIt(fN~q^+jYeiltki?zH{l{dwIpYX7|6p;+QGbEQox zR^E(y#n%2OzeBOs%6G7LD27LBpneEnwM~6RB0R5t!rX|?4F_Cu+0{UU*%7s)-l3=w z?Rc;pu7a!K8mQL&Jl~9gN0C!k1Ad%bkDq-ehd1&@IleW@ZGx;#&1b)7K^!O*^L{C z=bm9V{g>#k5bt$#H*RO)?pb!r$30MNx_f5b^j@~3t2|nipNsRA5=s$zMfUaLH{8jWf;2+_;@GtP6@FVznze90hJgkR%2gk~JDf$&q3q4PFi1aX%}(?oc`{qCcJ-`W=z}%;hB9a=5vl-lq>35Ka~y z{vDCr^IS2Kb3Z4YC?|tVZn`FO1^ePhP59d+sXJL+N;&F?#>EoaI%q~A^_xCCsSCS}9y9ck; z1SZMhb01XLta^ltmr9n$ru*O2WM2g<)CJEYEZ7BRT0cVVlMan>$|_D?1jRXZA3!cwtz>j)mu% zEv#9*uw@u?Mdp1u%d`5YEgNQG&5t{(CTnHJy=uc&D~`D@t9Mqvg+uN*C-a?*Sku2` zHO;&yt9rq{?C-XH;MiqrV@n@<=&|&kCob)9Pr>_rZtA%7=$Z}>+?3T}MfiVY+Q=W9nM|f9!n;cvaQa_Br?5+}tFWt5W*!40zwFbh>98@xr|B}WL5?N zgCa&I(b^CY6&2eshy((OW36?-Xq7rt>QIMDi>+E(wZ&NzwKzxO@W1cc>)d-11M2tn z`~Tv=&*fUcE+xbJGW)F+j3D>W@Xm)_7&Mx?Y4E=6&#R~ zwR?ER^_iQqHm&~r>$^Jd>{9(p>)~L|_G@bWeY$Mvyt(Zr-{1CIZ7TM?ox3f!Dw5xI z`FJ5Q})i@P_N@Jbru^A-*>zX*HaxKO@TWnZ#bVDR$N^vUZ%yDCD=9st%(Svh( zYOjgR4N9H~(K&NXT(GicuCe{WxxUKCpfNc~A4QV3Ki_@#Bkvyi`463w{rQ-clQ<(s zs=see{@*+!PrwK@t@@uC`9CxA3DN)7j9h8f>i^8hKW0XL!D_QbX5?L%k$2=(l}D#F zL@qsU(GbqbGPm}M1~AWZ=Det6#iGQDUb-&zlKGeM50t!wIoYY0t|>2JHh!rgyTV^F zT4!IhiKfNZUq4pHfXuFD7uG8}3iGm=Z%vFJt7ub>-E+L@qoap(_BQ;}qxo~qx@YLo z(bBnQc6ZZvH%ULl8GP{AoZv^1;AJ|4TaT9h`m$APciYGMu^&#}AB@f`>9YQ&t60y2 ztL&bk{l49$j|3Lk>xY+Ic2&=)wbf1e`1vmDU%%?6lAci?)`HRk#6Nl*?oZ(I28Z9K zA5!~kTr8erVkFxAVuJE6oiBmU%sPC`#y6O^Ch^X+c%Sem ze8B{{>MdT*1b^ZgC;?AF{gYHM@nYnOKLvFwCHNChVVWI$i&W5mon-J&M`S`5MB(wJ zUI+*L_sZX5{7vNJOT2auJ^~7lFEJ92F9msj0*@~pFQhN{Aw=QvB||zvUO?gTrAH;z zAFQD8fx#z*3PJIwMQTZ zckT5m%^r+EGVkr$g)Fcy&SYw97g6L?l50ptnYxN36|hG#^?IBsXJ63Yvd6GMHUr23 zO8(1`1C{K6Y$?kYxy)1yq|01tNSB#Sld@sg@lH2+ zc&{r&@j`_tSwrBJP|6ado<`mgFnG!ma0pdO>Rcu2Nt~y|nYg}fbprm_lUTtkN#-M9 z$lW9ZvDCLo@}kqEcE-hTt71qq2cfb_y_{s{n5f^7JdUZ8S?-%8dofkW zY&2P`{xNbk$&+KuH6$0XAYtYw<6DiS8bW5^QoR+8ZOCaPk0J9JEU1FyCrq6}@_CZ- zFqx1^i6D8m(4-C{*(pX|M3OhkOzNE^kBy0Xi{x8WV=5(g#La?M$B|jcB_#L9NPbqj zRUPw6YKJ6{U&r!ZPI5_%ncp%_W>=@oMVS({SxP~fLZxhcm-0VL=|!Hw8vCg59PjcV)v)DOTVdOxy-xDs zFYa@q(d)r%Z-#MN%jh2JqjfTIXScNs?~{ET!NW1N>A;Ukkbo=M=lZ z$J+ZgT5V;(4;S)oB!fnM4gGgRqnd_JK#y-LW8TpDhK}*iG<1xAJ!u*CBYcZc+`XXF zW!xJYVep!8TaNrfVf%})p&<;J&av+X!Eb_XIr@u)KM$R_Er-7$XOhJDH`Gg{Faa2f zUyf`iGr(x6aT#fu0u22N(lQ4a`c={+X)r^#4}+Fjz|g0XMzWiJCTW=mO!^h1Wg;;2 zgQR697$fDsL0YB)LwCflbM0grwU8kjDbTQahV1ILoLEfs z<Vhu0;DW{``T^mB#?861tF26%H{9)=ewkdx!Mg8(+fK!#nKj9>cljA= zhu@veR8#HeR5KcMhYkqv$BKiPhdM&^3d9XU9Csc3n7oPW==-VVVEVMODcjD1G-bwi zDjifOZlZGR6wdN}Y`Zh%cP@_oc@iO{{8zoJd;O>fTtDiGUO(!=rhe3uynfV;7xk^i zi+XZXx9KVHitcf$9*UD#!r~s&n|oMCjnm?+{NXPgD>31iP?Hi{Yl(32PBCpfB=WUY zF`AklC(&T4fTp$gkjR-4XQcv}-&H^z$7i8L)=|ZDxN5D9mgq0;;X7W9C+2<08;3(e zwn?~dc&Iizt)?{o+y#Z^!&=L6B1l+; zGZEb)u-wY6CPDp@7_o87>HzjadSHsePd>~hZLL+>wweL0(w3N>&6uec)Y!I~fuSN~ z3SpWA&myqJ!E*Cz1}GC6Qoi@gsL4>1kMOJnXJQ$!+KXbv1TFf7n1~t_eY0p; zOi(QjmC*oEBaLvo1gE=NpiW?x;|~1YjT2KYK?QtT#+E2H0toj>a2lIEV$>m+#*Fm> z&OMwf(aC5sZTACZ@nX*aha6-*U07#?!P-W|7ZWtsD`jkt-li;qDJ#}I6mY2snAQQg zvW)tkSUm83XXNeRAk0Q8VyE>_4H{F zF~dkBsI+)XWrCTvPLPkF`5MajQ~Z3BkD&QJjVYW9=58h*LG!&*#=*G6*DXV{QCYcG_R@ zZ_Z~)$l+Go6&d4^-8cnjSF;P>Z=@28)M;_4xaK#z`;A60_RD%uDs9ou+W5YdEF13} z!cqXB9zUa+O+wbG?HeDHM%#Gw3#+-lT2(`2=%tC%vPTvWiCX590llhvv6Vwy9>$OZ6hd~Zd3^?NqnpSE;1|;)~OGJjT>xCdW1cO zHNMra0vosc5cL?+pBC211Z9nH^~rkBNZpO}`-OEXL0RKl{g0u*mpHMVCh(PV*{V?+ zWsYz4S$wJpo6M^Xqry~=3Qf2A+#hgze-?PR;%vUvchg;2D7b1hrG11G3eAHFmf}Q^ zuo7o%t51UZeg9TptF&!316rjYz163xwsjVPEe=g@Ud;eyVlT}au9V;e0xOGH!d=jj zTYVx6_iVhIZS}PXudyhg44K3*46GLklL=ZA?^b`(edyNr%OJs4p8@tvSPxpu5!ZMs z6<6KH5$`jS36u<#dG|$*`S^Q3PISB%kjpfVZ2J#Nrr65A3QXICaVmjDNMEW$;9N|E z*jg}0!*_G70Xw(-M9p@fjM=o7FO)HpsZFdnmcj9ZZ9nh1j*}9m;iii+#`ZDPi;{8e zN5(v1oQw!LnEEVE+nUDI;gUL?V))aFZN;{mEN`zc&LATnvxG##5DCs?o*t4Xw!`Ez z@-Il9Da^B67^kL!DPI_4R~KZ|n!i#;4S5NGd5v&Tf|HqxCV)-jmkpkL@0U>zUIHK= z;b{rVbxFFER!mS4@r~Cm6n&%USWHkY4wcaog+?0THVIDmXc6BK-;R8D84&~(@o5>` zo4A2N><<{7DA=4AjXPtbg? zl(9w3Wmz%7loo3s3ZRpDw0<^D+Rbgjlbi0uj@UG=fTt7u+7qybM4-g63-|n*-)~CLclb#V-LOVCH22 z@)0!OD`gy*i%mYli8452L#H=bc^QCQ1kLq+89VYylZ)VQI;01Im6rj?MbKP_$}R>ZwzVn|B~RX02>9_g1vNmnO*&7WP8CBL3mk$v)m$3S=seB zxe#coJ+~CFbZql!E(UU|DdKgUZY${iUv`^}pCPT-WdD!rf%v}DZN(;+02IpRZ+;2D z(aIr;!o0u1@M0vkk@X0Sbqmo_1va@na0Q~_%+I&@>E=7q*d3Z*H@KFIUpKH}IK-M< zH@NbfDr|mI@-~_KXH*rZ`93aw!(o_T2DZ2#LpT!;!_z9$T9GAd2eo;>SINfANr+?ezVa z(3OAsOT;C4gns;!%Rk-trw9M^=ASI1 zSta>E1N1V=PY09%nweDPJ>DPO@0mS!t@2Y@pQ`W^&Gyw1EtZ zcnRT?wvre&P-^UzV#KU4ktqfio5*ZK%{S26$WAqB8tJkaVQJG$35Mldldrvja}7(9 zk#dP)X_7WUGPhYPkW}$(*G~9%Y}W$kFJ%$uPCMekJm(%e7;*lDgnR7eJ-Xy}&gqid zrAsI0Da1TrN4j+Foa;P+@b8dqRYam0yd=^^%&%P|-iu6Ex=2)&p&(sW`n!ah+4&Mv zCwC-B)kccm8f6SAT~Ee^G=n>GQiNZ+WSpZ}ACg{vEJccH%~Fp}O5S+gj?R4aRO!mi zhDN+&N{?+OAf75+{^(@0PTh>zNjCkdr9M7ftX*o_!R^w9N|7#BC=AWIsbM&3Pc|%R zrkjRa?8$~D$)sJR{n|txC4=eS>5@x2mNaZ9swrKh-}Gmyox|v}SD>Q;yE$u301Nr>v?Q@v-)lxnUvbR*>ns%^CaRSYzf8bHnf1jn6S|4g>B&r1CQ2th(?v{F zl96QwvqVY#b-{5=yUEJdnf31Cd|{38Iq*;AuAO@^g=XYAi#T7<uSwNM>i8o&4Qn4R-6(k#Yr=fX8m^DG{d4>bh80yme$JTThUae$rmz_X3c4qPp=a$ zYAK&yimYlWO?OGHB`v-t<~mQ?O&8tjBs(`JHzyy~K6kiNn&%|1J@vE`d_Jtp7oR

    R0m2pYMtJc&M9*8a zeBy$Y(Ya?YzhJ2)z5wT6uwvfg1=h5=k{bf&yBSL^Sh_qy2au)oL@CaXmd>5OXw{(E z^HwZhzF_IX#TSeJ!WG~d0)K^z;2BBWBzoORs#nQni_TfHV17hCxy2fYYQ|BeXc2Qu zI1R;{>cyhyIPp6LFIuv40o*c*0&$m#RNmyCHn()~ie;$IJmUNoTsL{VZN}VPihk2w zQ^YlkF^D<5j+ zM~twv+l)N@jL3+{puFSr21W+t_aD%IK>qQOp7==Ag1O5U^oq>Hm%REdIDg)P`STad z?>lJr@qOnlox9}hlE~5pD;F(WbitBH{}Toc%s=i-i#3)`VR|UrR{9eAgT$|5_hk*i zfZSl1yI5NPVw$gX`O^N7VcL4Sw*4v&1Pj`p80kqxCtq;E;$@MA7c7lHtw@oo6)9eN z!PyIzExTapvR?m=nhYC&TW)g~%$>K$vU!^?VFbp}f>nJ_8)yZR6HiO>wehFh?d%LE z)6TLx*f~D_VkCZ`yx;R;PWRwlzTv6e)+JpYydv?+!1{!%{8u~I_-?8HSBNy;{>)o;@%hW=&I2xAYOur&p%%-ny!msN&$aUAEn8+B zUNSPT#UaY>Cq6Nc%;FuzOm247-S&!*WCGq!xF@h4?jxC z(VUNIJow^J5a;*t<%6erx$a$KB*pGE^X@a=5{Vtzr(0GHl%n3eAI+2H@o@*Qyrh~eSZXN`!`yuZc7O01tRtMTEZ#m?-?ba4) zuDrttGY`w+v3eMOt#&&%Xr}R`|2Lw`_ef#OzCZc1KeCsCRgS!(mVJMkU+rBkJm?F) z^>I@4Bbftv-g<2C*oF0R>p>fN)VAJ-yna+z4>w43$2^m69&1_q5y|-(T};JKOBoaD}Fe5D4+vK+S43tvH0OgkMz=Pf%xG-d%kGt9+cDDC4i)l zZ$_hANFln|tGCboOl7U(8-Ocm8}U zMl4$~FHW4lV)2o8>@6DgIsYO~v<#kk_CzCm@y|B0^p|5$O@7dusY1 zr3*BDoYIpueZR*4UFkZdKUF%2@jv>JKUwiCjW1Dpsp6#? z&;14Ea!x05oDpwSyo-o(_9#B4_?+TPMDTyE=+}P0^@Z_#OpN)tju81E7vuS87U@DF z?0352EJgYeW&BdbOBJtB{23AXZ&i9X5po|?`Y}zXKTyi~yQb4O2kAqa{*}^x_Dkgd zQ2QsJ{-b<8%}3-zc|<;BN4|W;6BYT8BIEg_A^G_D9O-#VFIMCOYm6^f`f8=OD%KF8 zADxy+ml>52T-w;twGW!wu+h~8vQMv~a=>wELMbpP9JyFw} z_s@4V{$u6$X+KI=|&-HP`qzNq-7;wOqe z^k>R#tr$_{9*gm(C~~}!o~byGn1Fq>;<-d@E4V(8kLv?z@ed99TBSE>dX>^QC@r6V z13$+j^F5<@K=B>L&lUMx3i;9%hbYchT&lQQaf9MUBJ>gex5&?HGSate`rS(N8^V;& zw;PzwC;dr_-&@dsRr(c8e_Lrf;UWKLN*`9*kMYI)d;**4ZI#YcI#=mql%``0@()(J zK9dqRTWRrci~LKK=F_Z{w?^q}l&(;EyVBK4|5E9@l-{HCBT7G|G}k}Y z=Ov~2KqYBDqQ~+$&yfC9=`WRbFdr~INJKj48`Av71L-bGbKW7Huk>+Bk5ziQBE1qZ z{|d#+6gMhRV-Khnc`+5^w_2JO-kRT^u0>|R_Vu;{-e@= zQTiWBzoGPpN`IpCH%dFO70XK{LeI8J=P2D(={%(eDt(I5Ba}W}=}AhTrS#cKFHw4# z(q&3tru5I0-mLU4rEgODE~W2P`nO6yuJj+3{)^K8Q2Gs}KUDe?rN2?y!KIeepUC0T;B?<08fDh-jakM4UG$ z-a-W59>qt9;Cou>eMFqEDSoZk5towW}h{kk{L!`zrQVl=Tns zLzNz(I8t${;!MSPiVGE2DPF30nc|g-*DLN&yixI1MP4^iFIf+PPbmGg;-3`%qWE{k ze<=P-QPxf5KdkgOioB0P`ALer&LW+o*j=%gV!k5ZJ|G{R$`MB^7AsCxlyw*Bvz0DY zl=T+zKT(?Bi=iA|mk~E8(k&fnS#N>7P9uGXqPQ9a?fT1qTH~Knd_hsxWAJfb%>3^w zeyZ4@Xmi~|x~$VczU4`p?`{$^6gw*RRP3WjKX>G#!zUu&1|v>XoT=#g!7o*Mx#CY0 zW&KCK^-9Y=0Q6?1U4Qtyl)h2%SBkP90RR0;Kd9*X!+%og=M?uV9#EA10rJbf0Omo2g(e;PlT4`QSFg-`HyJ9azUjH&(_6xw1l^&)zMv>PWe!1c*#VZwM-+=T@N^e!%sd$6pZbe>?P~Jm|k1Fz255~*>0r(fC|El=5qU;}# z{;|@ZD}Jje`v|1-x|;IBiu7Sfx~pPu#XLpXM8BO{q)0z0jDJ&+*H@%JQv6Ku zD@6-wOixryQOs71DE3n9t2jte_DKkzs`Lm&UXM}k>56paNcwC=UXPJpqIi+wPZZZG zUZE)aCWJRCU8BhBGs^ju;@ygS6lGt9@Z(B9rT9n1KP&!C@l{3HcOiU8=`R!;75&`r zARJVr_es(n6>}APDE3wCuXv*3DT+mkqZR4ClJaIL%03VDIZ7{4lzkuKf1>niMf$sB z{w<0-6sr|)RlHqM_JQDkKxx?zf__YCI?SZJ7ZqPoJgE4d;s=VKDmEz6!zS~$QcPFO zRP3VIU9pd1z9L<6GJlccIK^Vc>56A6&Q~l^qz_N#|B2#S#VZtlt|;|1QM_643B{)s-%xx<@k7Or6~9#cT9KYkS$>Y< z5XGU2{PrBvM=GAKI8kxFVu>PMrIPu6U2)uNCQAmHA&${8X_)G0c4} z(&?j*NQbM$A&R3FPgA4|R;Hh?Sf;pEkxp5eexu_3iVrG2t@xZG-L{hdJ;kpTZT!B< z_%y|~igfJC_f`I9XigedXI$N=;;xUSOiUSmfD@GMhQ=Fhk_pX$8j^YxJ zaiii6#cDTl4&nVJAEcyST_?F^(iiZ?GRiyt|@+T>V71I?vDt1<+ ze_8SmQanlVRK=*`7)AP@CI4*2g^K4YE>pZnk^X7Pzd>=c;`NHV6mL|d|61}tp!lfb z?Co4u3$0*KJoUOP} z@m$4aiWe!CDXvw#O7U97t%}SC=dx{?@ey(^}(ZP)g@+T_N zn=$DQid_`DEA~;$SERRN@{dp)qjP@(Cl#Mj+^_h8BE2n>{~g6cik~VrDt@aNz&#%FCo9rBGwIHXJr(;X z4pcl|@f5}3ilY@zQ>1ri%A2RSNb!8dm5P@ru2H;Paf4!oBE3UX-YtrEDDGDLjp8GU zPbfaE_$S4`DE?jXAByxgP5B=wHYk3jn9#H@@6Y8R6JMlLd6w|Wr}MR>HV7duUFiqc%$Mk74KBMU-3c3-zh$+NblK{cR=x< zif<^suXsrD3&lo7dfR6HuwsT{N5yW6Jr(;Y4pgLfZss4QI9_p*;w;5EisvYvr$}$! z%wMK>x#Crdn-sSy?o_-%k>0zbO7yk>0|Y|9!pF zC0~+aD@A%2XMC>W@roxY4p)pSo~FoG=b4Y*$cZZyuT|WrxJ|K2@g~JzC_bh52gSD) z>l8my{7msHMgBm_a_Q}y*hTRq#ZwidienTfD4wBsj^cTW^p;L}8x(gb-l+IX#XA-6 zQ{1CS@9NC|PsJ}38x`B)hhU~>DAM6N>5~-4DHbcvS1eJaM|ROqai`)9ioaI;jUrvP zlmG9EA1Z#V$Opcd?pJK5n59S`?@T{gaf0F*if1dHqqs`(Qbjt2Xa1dvzf!zg@o~kc z6kkz1s7NpJ%x~j|0Ad@(_KLj~^Azc3o_ymK=PQ;d()ByjuTtEuxJ!{v-Qj92eQ#@9&pWw zisvdWQCy*Tu_A7(SUy}^VR@G8GN>)}jSx`|4_>d~HlH9a!zCS;AA*t(d>Dqp-=KVQ zUjcUeCHF~gI_4gc4|xUT16@c2-(sapiQw-yc*t=P&+&cVJ?%fJ|8WC^|NFmtI;SfN zL6Zy;=!s`!Gx^=qwDG~MyW4I|uV}Z)zu7u8cI`KoKWay}L?<`+Q?8y~9^MqbJoEf; z)w{`7VS|5G`p&f-&M#TpXkRtH?v~Ik)9(yFSs$|2G+MtZZ*=Te8^SdU3fDF|T}#5F z3&+Ql+-ClG}q5q@wq!s%E*Rx!df9dw{!{M6DVJy2CW#?{ERW@;)F<0Lv&MvRMmFHk%4Q9=oRX^_K=yw^)Z7%G>U2vuk|a6Uptir&s;D@rzGBvcAP5 zb>Yov8-rVtH?^vGD2i{0mQQX-&Y#xcKQ?*iOPT#jE(||j?+cw@vY|1t>nOC+!jfqX z$p!n~^L5SdSdO@T?^#{ZGF@M7DA-$$I)py@cEI2)$k{u-ZlUE=`8L_Rpta@OmX!5L zhj9(bVc#L!HwtBhP}>8Aczxv1&hks{MTvb_^7EOeONl6JG0ViaE-O&t9G3I@`Xq~G zvYdVI`K8>`(JL2P_IBT{R~ypz&Y5#n=HvAtr!=RKB~`GTS%n7*&)c6Dy*YYvbar%> zsa>B?ePYt{nd8DJXB_13#`kosKX>>;z2&eaAl<%9&;kZP2W)VJ*ER;a+R%G^-F#m{ zrCpV{?TrovnQRsGhZNM#Vu>?Rm+1&6)hC8pql~s4#-bF;o7s?Dj=m8=ZS1GfZ`WyA z>$D7{g;8GD^@WMs?5go~B|bX~y(N;c&A0vW4qI|YqgE;PiNUcb#kXbK^AAOnccxXg z+EtPntV-Q^QFd_9-NRd5pIi~#vij4kyW8w&y=#WGJa~PruTPunTW?9NKK1i2?@Ha( zwz4#6^*UjH`i}8+fesxy?X^C_Bd+7?qA8Qmqb4@^t8y}v>O+acF+ng16ALdW{^No6{1#|h>B!XUPl-PG4(F?_yVEO11(P)9(-88D86=v?FIOceYxQm9opsRUcdFJJWal zu0F~3Zz`ShLDokT0y0PWD`yt|LT0EyY=(LRX`G>cg&Asy&QOVSYQnz`kI0%4-tlfh z7&8RgGqC_ORQM*$PFIK7UYwnLm>ojs9jW#eXvvo{mxcGe7s6~2Dsn2*cD1Uyx?`Y{ zGn0SYn1;ki`VP)ZeY37E8r_gsd|9D`ndyT4GmwILY4LU8`@(awq9`%hLWzq}8sZc2 zHR>Bf^H|TKE5g6W+>8>6P~#%b&t^{Y6*=2O^??NRgYbnNc4VSN%gjiL&^gu~ zFu6V{;ar)GT5WTx0^2z!`F9TM&@pRM(YS`hFy|v!Jn54OKYu=DTk_6f)`nVN-!@wc zKHgK__PXTivS4`Yoc+m_ZFaV+PT&5V^$ERw_Gn#^x+!#h%GR5rmH4)8(zcYUjqlE} zYKEWsx6~aoqWz=4iaH|u9(u#huYVs!#Wz_~t--vb?;DtkxL_IEOGA3hGZy+<`9 zmEKplyYSfqp~`#lmEzPLt*gS@M`i~HCS_eeJmvb(#?;MsKHsLg?Y4`p!eAI*^7Zv; zyQR(M)+fit*t7M) zP?IsXSH>8=D$X&M++>U;bBrZpjMZ?ACB??r*upVQ##p$*7yZpU;p=)w?|;X9yAeBq zV_QYt?=~jw=l2=iFEhH|Wn|o^;FsTuWpClPp90$4G-cp{h2{r7%y<%hpLed|!wkJo zLNY#{crn43@E+nEepbpic(TMK-U)Ezd5ZB18RJjjLk|w06!sObl9)t3mV#fb5p&Vi z{2NU84U>b3e10STxkh=)(x14SX?AeGu=v9Szh7hr{rw<2VHw4h;4O26Z$z?lzP%dZ zfd3i!I~soz!_Gev=O8V(7nE}_k&*m@BcC*JUQ5gu(ihxJ@^vMh;8P^uNPJCF{lV$X z`)1-hLI#7}nK^H%s8H|~GQX{4s+GWpHJo=6KLA&f%_mlDJ|1d5(?PUXfgzcXXxitn zguXbF_cEd6eEgkCauHJ(F?A(LmS~?#-D_~B;2qHO>9TGg34HiW2tIqm4<8D_7aKy0 zl}I^X12n9BL~#jo^Wjzbh@wz8lUg*_vV|%_`6+lW)4qVVTtMn#m*PX5tzHDXNqm4L zH^_#317wJw=qhE-5WmhPA=rX00qwVu(fAfV3A=WC8Q6_2-gyo2C5SV&c$c=glBC$; zJ*GZNQfyI2TUgks(-t4FHhgrEwh*F<1Z*M1Lm+4iA*A{rG6R3}mg);N43`>GeWCb! zuT=kEQVCoENcDx<3o2ErFQlou1UF+ON!1Ut<__A97*8a}^O z%s@S2j2$Mhrb$V-=;77KV&vh|rmfA#x7zfiAiAjkb3C$bA4IZKq3iR>_H=gmcJ`HI z9b((7IsQ?7-voOeSbDXVln{ix51J6AC0ai=dpd5R4tBoJj;eUuK-$GbB$Bdp@Ft zA6cy}IO*Jd2GVcC2@ll|ujb=H1)^epH6Piz5vRu$Wqa@y;AFl4l2Rp^^OYPdiY##M zO~^(neUcNYf#>5hEL0vLvo?-$b5kjgDJTKCCld$Ygis2R2Zi99o!H!3l#q>{4^{%- zokFc@Rx?1|0uUGI-@Uq-o|#BWur9KY!eDQls53$BRzRd_Py@mc2^JG*tOQKa$jczL zLMa6-#nlknc&o_Pq5W8|0-Rn4`-71-11FlBuoP!&be2G1Ko9&~Y2_l2UCrn_aJJH< z6_!LZ>S>&CO)EL@IW39jBVF{m8?Y|6F150&8D4_Zwx$#02`SBWF=4%S{Yfp`r}fkxKiCD2U80oVsx7RR-i zMrb2GG5RS^GLM2nQ$)APZV}#L!@?Wj!Ab zpst?Th#AGu3@{gn-K!Z;`;BrHJ5mc!U=N&VSOS$28O^jijQB+9TbM#f$eziXLQu^| z5osPYCgDQ~P9V@=2^bm3%OG`%35zROe1!VCQxogx+SASDwRZvZ=YU7~gc6*dY3d>! z{EXg(v)MGosQYokceI(f$Zw95Rr-s1u#8b zg3-<}Un{h&S%e{ybcxJe44eKEo4bai$kTB`I)QyMfO(3u3&Rs}hCnaJL}KPH#%#qI zo4ecuM*bFOler6tI(Knf|1+HERs>UxOZ|aWT8(7rmM*%QxsBmIIMHDVgK%N-3xpO)ub7>PJ(W1Pi#PRB9RdkxI*)U{jh^ZGfn@|;Ls z_g>wcSrMo6^1}Jf1!J7_h0fxk6V8GA&3*&(&p4*{fc(+*6cHgOe=Kd18#y>R*p_(%BSf9R6c6Gw-=hL3J+ zAv;2t7-MplN$D$0BE7wt%;Oo7f=^(mS;2G&=PBf*7&HBX`Xn`*A^Hb2g^60u1yZ^r zUetUpl}_)tK4)>n$;>;oQ`ZsBm}$=73TI57Gk7TfK8A16tQ_N{M4S~7{Ot^9drn%U zSN^HTb{jW3I_ntJsiTvU=Ug1=k~?;$bK#h=efteO_OxRM^y{17tANS9x^)?pJ)n~~ zjdd;*XS}quEiMg5G9+H@#5w3#lJY0Ykhq){Z>Kc7Exv%o>tQ^^n%d$Om#tts%V|+t z3K0L@!YOjZVX9~$A#tnMQc>cEPyDP3ixeON#6hcRLtDaa1`LJY*q%=H>Y>hS_#`U~PA`2vr)ssdx$~AKO+$;At|pC0{e9HmbOq@T-6h}8 zHQ&c3A3an0q^C$e5#xxfY#+)rt^TQDb;S3s&&eDrf=VJzcEqV&-PDU-oox?ABV(Y! zLm&o_(=p;Kh~V!z9S6d>-pH=q`t|GW%!xSNBfSXShH~(AjtrjSTrkufa~POsU|@F3 zAAM~9{J#A|!N&4Q-;EErvl%C;M;~iq6d7hxb+(9)4QT9k z)B#sSHnH&_hD6dxhGe)EFeGKmh>s6($sx?5vWz~_TUyE;R$*z_CQ)srA*8Y#ZW)oT zo%(aYjUD40x7-;UagG~0q4xl%P^JXu)Cwvf`bd4^ok0p?7k1|=_C+6ukEidjSNi0S zXer%BM8vCPl#}t|Gk%19&T`XPQU#>W7}3tf=m8HpXGNUc2>y0OOAC?b%#Cz%^75o_ z-;BQfinWl%n!bI5_R)hsvTtwEd>?#&-@aM<_P>tOw=u+=4nuuj&&=OR1QAwoXP?S#>hRRay5QxBR|Kw1Snt2ex!QLP zyeY0SpK5Vgxy@~XZy5P9T_zy6!5%+~i1-mc6q`CnY~IoGj-2dm)Fb&$Gy_>u|KmH+ zvbD{Q0S0mERm^vMF}i%b1Y$UVlgA*O?j;UsbR#*&;;)yF?>a7ag(J=7TiJ}S7)s=e z1oOw`TM81tD#VUGy-a_@qgJ8|`KbREoUX12TIGmLbcJ}*DiHR{+Yfn%aBW9sLF+Wg zaz+7u1)}%50YYn@6?Ygw=>o5Rj zbhlFG<#7f02AZJ!r7RwN$KMT;ei(f8Pv9PI*J%$XZ#^xGhUCI8 zsiy!pNc2?C+J*sGgGk=CbLE8*W|>Xo^@1Nr#JPtn&!t`T#{bXzI!usTDQ?-kmE%2r zh%dyZ{JeV{KO7kuUYb2Se*6&MhqNp0X%1RAemG)rFP$DI5TdU{`Z}adIoHv5A%=y} zTo2ozzEhRvy4MCX(s@AlkaC;vC9s8v`7S)-o~p$J?;_WN)bBVYSWXaVVgio+ErD9%+}qPT*H z?tHQ0Pl@P$S8Do3rMD{0G0gN^l)hW(`;`8z(tl8NePg|)bfaPtCI`w99~;2#N)J>V zrWhrnKE+C(p|tqaK)y?qUPHwEe7WLPM5K!k4dmacwD`^deTUNb5J5kr^j@W(Rr;@r zZz}R*&6FF&xFEJy?4~$Cu|U!Fg;h)%<;>9d6-tZGD@=mrq=D-+eXHUQ<-0}c+lk=& zt)lp(0R5iwp<6V0=34qa+LvRL?aZ}_n621XvA^OF#i5EL6h|sbzej#P)&W^06J#e5iVo@dmtC;~!SstLXZ|*{}3p6<=2513uJ?K23=qDSoE-wW8}AC&>N| zzK~*DMH#n<&sDmI;sC|LibaZ}6(=alI7a>jO7k%ymQ$+e`pCIP>7OgQzHj)m3HkYx zB2j$c0cG3*|ETdVD*jFJHO03SWjupleBlB897jMI-@r7b#TOpv&PsPxJWlZhMb~%D zM5V>Y9r9hM^iLJnD6UuBptwbGo8rxiw<+>@F6!s{s(DQ5-z)A@d|vSlMLv|od><T z^8AY8n+7zVYLfUY#ZHRd6~$K#`1r|M<`-WzKt2dZT738ci?6w!-^S-9Tf*C4ptnkc$(ro#f6IJD_*F$R#AM;AiPQGt%^GpZ%`DU zGYE^%8Q@-xe?svOihojkS@EBWA1QvOD86J6PQ^_K*0YylUq$!bFYzgZ^wAoBn&NcD zGZp76mMG#K3z55Ak@rVf&N@Xt1xosQ#a)UwD&DDhkK!K1hZXs3DED7~Qv9pp%Zhwb zlZq*Cg+22=7j) z@DFgdToc7R0gER!B$wWUchg3Ga;+8pejt+T0p0 z{N!4j`aB#yK6C|iNvyiIwg~z}p%312Do#7RrXjHwZ^{Lr)oAG9x39aU_L=%F<3gXL z1&Zndh4xNrwXdODIdp0WH3l1c)Ka?u^y-@)h-+1`I!uic>lX#6)BUv(e*rX#*4c$l z<*Yfwp_PB<`s{?N;K1O3%ZED^Hx-`x`Pp~>DjM8*uC=-Lp^toNX`2f^&R(;xp!4Uw9_Hoi?a zq$0VpX8805drrZ}mzR&P>oGR%@D+#C4qx+G%8q>vp&GpPSmVELQbRD@p(M4oU2QP^ z?v9C{q$NIDySF}f_^S=U3g0Jb)=1bUF+Hg<@vyT!?Qr>*KGf8|-KzC9hHFw96R-D$ zR)#Z6MyChr7od&p`Z-0d{ln@qMn>xrhIg3b)Q1vAGz3crei@o`+?T=9Ga7={q=r!B zsro>&ou2$jT2kl3R~`OceQtsENt!*T&Stqa_+QwxHh5E zzkPKW<%UxllYR+Fk;M9ifd^_KZw}sc583q#hubJSt6*fEZzSH?s~OP{DlI~Zft`~J zUv0>)xMld*!Yd9W?MkjpscNgPl54pj!KM&XT^QTx-P?ESwBUTu}*_4e^~Ba?27 zb}Gr9)~~ilZQt~6>A%N&bid6?fmP9)0*}_-U;9LTLa0v``cr}*{cB`h0xac^=FG{? z>|DHS+AY)2Mql--9h}}b9dDYYj4nK<5V=Eam(GVbeD!GUll6g=tBdj&n?RZ4>Jo}Z z)&-)wif<_%QMmU&8+{{fA9S4_yl*c49~;314}>vxZHyc1*6^UvwY4XNuEdD3hmEZB7o=hYehQ1_X)KsJ$UiW1XJqY8r9QMI@_ODB5%)ZVYEo{#pI)<;U zHKW)a!HHGW2;;aQrd7h7wa{pE5@wX5x}dAkmr0Ew%qi=>bjNXABYTU{iTbd2bql$p zms)c4&YBab@>Skc=&#~zWbZDHCRD!KFsLS}dd+aW zRhM7z@fwWcuA_4><6QMw@($ltXRH4@fAlX6)^3hsj_lOh+dBr+F>Vtd#3(+NqbhND zU1EWsWB0JHG5N4>dm_ee;up?#xKD4iZcl0qU$ipJ(K|YQd|ihEyZ*fB?X~0Utg*xE z0!3pnk~_`e2NcD zVkK*d53LTP%o%s*I+c|Vt+cCz%eKbtAYi zVo$j{r4nNxc>MnHb?XC|_sU;wD6GL7w&kJd&n>h^=&I-f5y!vTu$Tg+w{e6^Cr&+r1^`F=fFE_ zBSAX6Dd)KFtfi6Q?I-8B)9@Fsukqf2!y7uz;Mo$BSP7|4BBRG&$QXaZ9wzhVpi_LA z#3afc%V5F@q=MLyKpTGoe;)Vw6Z`P4hClH|f*qWOY`&oXZOP}CI~_s)KaiI2J4T&t z4+kU^kgLRAh_HEQEivr7J#hxug54?Sj>O62#@lN5lJm~k+iD*(^{&|4YG*U`?!?!G z*&p0b+%0l^U4ucnpK*_h3I%`7ytPWEqF|PhFo}8YO?(HC^c2I6W4{P=>cO783RQDR zCSQz8cnPH}TX8ToyJY6rD6VJp?7q`Y#eXOvQ~XCJjN(7mST|%Ptz*$2Xf39zm=9yM_?LvNB)OYau59JXwkF25 zR@v^LQZK4f-zwWnF{S?MQR?q8rCyFHWkMm|;x#ot=!@ILgk77w=1DPO*hKE7eW_aV zacA1(a7@ca)p9)K`!*=sY07qOjO}NJEzRx(K7A>1FSvNvbp04U0o9DZlo)0&v`eVz zIGo|d%(mz?1Q(NJ$Fk35_t}cGHD1J%R|g*_ffwIo=NSN zlIah)&`5s_A`O}TR4mwTF@n>;!o%M1XE3(sZPISIwa~r{fol-R$V6f$zu56QsLWjm ze8vFpm-1diRzA}AAZsSQh98fZ%*PQJgMgJWig}+0$*c6tR}tW+1aP!tmpm7NIXLaj z{BTi+6^Lqo9{%*lrJU7{eV;eE*OOxtKV{V6baE8NI5;?WA$2!7es(4}+H(pkLiYB& z&3Xp{8JrF>TO-=RMN=l5zBeY#%wrIES!PeM!u#MlL@{?Cpcq=g-wFX*;XDK~!U%{J z9s?y-c##2G;avo>@)7tg?LsR^60MM&3Yi(B5E3iYfD|j-%XqayDpKd*wC_L6I>xL( zr*_5)EW4Z>zs`pB;#M#mw89{qHRQO5E`-GjZNqAXOAyG|i$t-)^Pt2E^wA|&ptCC! z#J=z*&Vv;5>gyCkD?F60R(KVG3_5lfE6~%ESi#>80a_s!fh@jT_5`v@Z3~&iHlK=s z)$x6VICG1I=#feK$zGuNIh#Kn8ukiv?DI5(^xM=~*mrALnT+n-<`LCt@1jq!?P@L!?SS z;7I7`GKduhBSx$+ngLqj90aoX4$rg5E>^gTNwh*00#?S;RD*rwE5@^rq-C*mGa^{@ zL7eutKJ?w@7T_)WFh;rkO@yhRlkbyD3=S*a7Y~j4!gTO9wW7V72=*odizZX)FY5l ziqstbERj=-Kba5X&$o!rx()HXYm@T_M)UW?KAl+JUY5t7Aua%!$=@N?GG6Ohit-My zynOp9mdASj2I*4Iml4PaV>rg^`89>GiNkoXB#U>K@8pES$!!#3q@FVourf;AX`qbp ztmj6?BpzS~Cmc(n+nZbFJZ9OJ)>taH2V*O2fiBD=^!caOaa^n0XbrK^?n zqzGtP>h86<)(r%mi?!|nyBgGDQdsN^^)FIb?F==b3n(mihFV05>)js7_&Xu7;2AO@ z7pYwF47pH9EP21NpFt^Cki?qzplphsBZWoJP`7o(CK#)pp}NYl_mJ@2*bTc4S@#Ux zN)|p7mYzNXq9d@M{i3}OD}nTY%e0^lk+US62J4_DrzInC}e%GUhiTkim&m#{9dWWX$jGg8)~* z)I8)iW1g#DPjK2_*pE{V$HMXb5a9B+3xSLRq{>*x;RYaw7RZ{0xI4j~!`e&DKLabq zDS0_Aq}H=}<)O6>A#y#-`PzOP8RNCSWB^%MYp!*B$nuR%ugURR8y41jFwTQy`O=;M z7OAyp%QauLpLM=YJL832(Z>q4W>5TIMZ=g89u-P!n_j@&pt2=0UT0Qmd&RX?PGm( zkSta0zy>y5B#dO#`I1K^x!6cCE56>{3R(OT+Y6Z?Uyf<%0eV?z{Oz>lZW}vM6y_6!pUld%Mr*}&(djy+dzpG&N~GGTH#v+pareK7Y_GO z&SKw-ltU}bI9081DFPXM#xlMd>_C)Q;5h`cdSYgN2-&2T{sIJ8%M1jt`9qpmWg+9) zH!fzpt_G~_9B|l6e6kumgfv+V{)|AzHl#FL4ceJ9IGofIQ%*`a zCN#QjB!$i|=zAl`DEhZZ8RQ{CDK;5eAx`p;AvFaWr+K|&w6@#W1p#&Bft`Zzst1nN zDo)8ZaS~29RIH|@$4P7fJHZ*pMEi`uw3O+hBrbaTxAkFy&qzTmnskuTS){3D2XbJh zN`W!kK*wx~V9*uO$s;p?IdUiiz0Vtubud;p*r-X}x@g^CC~A_cl~J;*>aS!sPw`S( zccT~!?$Oju$uV9xB|SZEN_sVOQ_?%`rsP=Trle0y*_2~KL$Q$Hdo?Y(DPf1CuL0s- zbYu7$c$YmdcCdfrMPCBb@w)!3SQ-M@9wS+NlbGyy>)o4<9UIao5(XJof=VhzFm_}k zgg2E5m!g@B^8kkA@iutoa5+&MktJ`OBYg@^yu^Mpye-((B=|fNUY);r^%Dq0G1l>R zGA}9)m>@q9C6CC#aX<~iyK$llu6X8_Ckc`KE^-`_Toc`7YNQ3+wwi&EvC1?eRrQD( z#Y|vH7VS3PwmOhoOF!x`m|fp=RK0Y{kB6F5g!Eym{tz6cD$26R`%0)Z8#&a13k zx9)T^0g`6ek28qWORZeQ3`YG#bpwLyy*17Z2|EToUj#vgERrr9;3LU z%ZL8V+WK&Un{Y19L_}}A4?~W`I-Hmis$@zy2m+pZ2prs)JBkBv$&*XV@@QslHvRWm z+wC5?rd41p?M0@OHZh$k#1!M{thD}-JFD9^;8^Z9%kmb*UIO`BaC%%autFs`VS$HN zGq6O`&%j?fIHRw`2^SNDbvP5yb_LyH^U@JA-3-nkg$C$ehZMVKNMcHnzX0Bd7(??M zBe62Ny~gp@!DMi4d2Bqx(d=n5p%6J-{q5LYTdDa{Bqn3-D(C^V)J0M`;?NBU)X|$v znoZMPvK(D!NFyt?KJiF%O+k~ULcMcGC)okfs{d>T%SC3pS2^U(!&^?Cr$SvsBCDxfE z%4NE9OPp?JnWCIWZ)%JQkC3DCswQslI`2oyKf<~8+xRP=!bM5sSTU4;CrNe zZ-c}pG)VgIHEqmLXrlkgtr3iE4ixim++Vs<`C}M=O7pDmtPrD{MI}qrR6;IJx*_x| z>CAK@&iMLGihIST>$kgmH0!tQy4?*(^BtsFirvv`dcSVdy;;!ao~?D$_1jezqsXl= z6%F9@F3_aYal*G3fjWAVNz?RZ{XV+RSTo7W;dkPZw*Lh^zE=kGv*wV|@&&>Vkl|YH zl<$!d8#JzQz2-!HT+8udm}_^FtuQa}WGn1)vFFfW|3g;_-ePFzf79ibS1dd3(N}Y~ zYk&W0?sgq_H9va8#}_@$xku&Iwax8o?rMJ2Ji0b;b8>_W(;rr-+c|%9p)GgiA6BT_ zo8491?W}q+{@p7hZ*7lS@X`9enz?!RXu68K-Ql~dIGdk}yG!>EX`a{;JGuCOSjt<&C-2TO{CVbd2HyB=CL2raIvKuQjXdR-YMNXp&MP?)-U)TDc{?cF(bW+ zX7Su|*pEwhz2)FGHaQs0n=0+*>cI9fPTVXYd@8}I-c(3H>J$R=C&0&n zcjeS*k4Vblvl%HUIZ)7p7n<4CjNm(qxc^C@?oHAeL3PtiCb@fp%<=jA2-)AO}Y=xG{i}HTYM&gk<_IfqD@?rWY;*f24!Fp zceQWU2IOd|4X8~=l-j=soFSX*EtqN;Or;~%RkyP+8HHP9bnDPl7(Hrwxs5SZv|G8n zSmn4U$E_$+(r==#TP1TKAxNQsCRa21xIMMS6v{Tj*b&7R-nv_Mg z0&Co2QW7P!Hqo9M$8vt}y*RgqE+ajQ@{XO}uym745ygjR(39P$F(Bti)D*%h2~KxY z`QXiBiJD3%!^vC6o-P-G#C}`3}rocIAGUdYF8Z^ZmoI>qepQa6yMF^RyQwJ-Tp?T zsml@bxpo-rwFAeY*Akk0B_;(o0UFB<8E?(0b#lCF)ov}?wor>|Dts$WOy~sak#$7f zt6eoae~+56F;=QFTSI13>&9eJt>zVqTm@HxTq{vi2~{{l=4Te|9gLv^fM&hJjrR18E5Nk{r|UMG zVXEo*6_6|~D8L4H{a7>1oXAC>f$^&xfA?{_LM#~X4b-Lui!ho3n*Ex_=o*|&E6Nyp zIB0g8#FcR*CE_jQ3h>;za5J+fLv0xt2IJY-5`LWYwoObn;Rta9^!d&&^5%!~V!~jY z=voA_9_2#-Mp83}|9O&qBEd+S;E^;Av9V(SLill>a4EK#@gL{eTy){jmQ@vE`)vLY zO@aK)mv^it;>3?_@aK+Syh*IZiCYmhtDi;Sbwlh~{RAe|{Wwvvo{*Z46CIYoIRaad zIe=0VWU*IEZ~{SVS+g3Y%E1yI#z__4hRhE|ZgCL2l+9>L;wW%XvuXxdCC><9eO1xh zRx|JoWT48Ei4+8l+}eAF`6!gnO5?YGRM`CXPnr^NG3v&_5^f!W*dQ&3n|Qn0t%}KO z;KPr3wWvibE{;z;wJc+0=`Q_B4~ zv4td1z>$AIWojW#FcTIE^AT>UR5Nvz;b{31xcY6Ro+zDZCSjEHiDiQ05ax`7eGP-p zO416!KgN^(4|{I{UsZAU|DSu$O>#*>2#f5(WfOuB6Lu&f>lKtGYzj&xK!OP(#1Ie_ z0TC_kVG$ERK*d&ls6}fnDk@gA)D=w(_@4l%=2ZspI`b5I~oEa8@yVD67K#YP=I*gz11b$6^8 ze_OxDGvm)+%^i?`R3MR~qTp8)ts6Waf(6$7E3GVZ<>Y@Cl(V-f_DF)oW?kWfFes%t zY{%h*Ba74t22G0?2NQdiNkJ`ljTu1RFp8szcVQCnfC*n+pq0HIkGY2?a;CbaZLd`x zg2vT18^E#Z+cuJaXU?C=_?j&1|Hw_&o}J^H^IwCgeOF^%;R}q@S%f#^KL$2)oQMB& zU^L@@HLMBv{)F%L?+Af%p=p0C(LN0ZsSXL1MWu)92eO?x$4d7nj@Wk1fvD7Kn@%wiNVwtTFc7~8(Ro0wxZGv7_jQFV0* zwcVleCg!N2G!EOFn4{_{1=}nZ9j*6dAG`mkU`ObJ$Fo47MeOp1yd1d){u_CzK9b|h zi*2UY9!Fk|+EgoVUXD;G<>zRT=v>(*Z`-f`=Eb(x_?s8oKE0clqqYdO9y10<(LHeU zLa@_gEIabpdVFUjc6N_CE*@uG_UuG|nzIudOzicz>WzyXX^(rsjO|oEZo!NlZGYT? z8Cz99-GZ68CwBJXBc9mV21*UzQ%q_E@odH(iIAJZ_!hcwy-5WOp7{_#;~QH$b0Fq) z7Jcf$aEqAlvC%ND{noyr1y2b0Wbwa|w$>k9QmFgJd0%1qGY5Dz$z zkeMB|nTX8dQ*31po$#)PeJ;mu{3jgGCmp+D=enbGlT zPZxD=ihmDZkq+eJOjhEAEa#;m~gNvT#j=i zjIZa8fq0&AI*XWUtfOoIzM+6G&p}Hk7QrOocYv?w9wE><(6qlRXfJ}n>KS5%&x>|W z4)9WFd#If(IBZ3YEmR#S+hri$>~Ce)w7K*xNn#GC!=#{I(7|{I-gF%uyv0d51k;)C)GQ*jSuvg0R-BC#ebh#E#K{kTnBzEstg|NOSw?J&l38LB>$#P0`q(pD)HuqN zAD8xc3w6d4gJEhQQLoO;C+^3<$v4Z&#Xi)66EOjXYez7brZ9BLgW*CEUr)BqzNi?U zu_t1-<|3`^p&C>O&bTu#rdKsxN0Bpku?rWHtkNlLbiNdr*}gD#?GWubFt~CNjLv^C zjuoP^$1@|<%okc`|8>vixoUMV+nnu>TZw2Rs5be^bs9D_I=XG)Hknw}v^-MPR7S(F zXn-*POFpi?6*alx}=d@xjOdd=Dj6HH;p&R3w17i;x z_k1`khFJ!)0%j%5Dj0h(?IY=|wMroEe0sSN=6;w5VEA0u9@hU}I8^7qAMW2#88>uX zlh3_H4PoqYEdS4-_)nOxVN5&|`|pJtZ)m@P39(h`IFdVmFYJdo1Y^UQ)~s;WjWimbpop&(20hs`k2g3`$J^X&TK6l=wl)&&( zH4kPX%wm`&FuZ*#h2bU39!JupPMJ^7hNatGF!#XR3-bWXW*B?;_143k*S@3a^Af>D zQ1<#T6!zgT96>pJp9OOc%y}@AVeIik!|`g>2PQs#8!!F*`LXVPw`1jTsxO~ERXCfE z_&TxfybAEq<02S7dE|nt8(~UeR=||Otbth%vjN5)KQ!DN#BnK1eEc?E`uX!?-50{W zx;(Cgdwd@6f}1^ls&F>G`1Gv%Ik4CWUg}i1|r^oBU0hmKDsTdpWaU^%@*=s^| z*9ix4gnjWaPJ5kb3Ola{?O=Gl$b{k8KNQ9uN7CiBrJGNWc3wOB!tnaQIC5a@;rHjW zvUvXkaO2||dp)q>tQ()-1byQj$NqGfhA@p`cx{Nl*rPhX);@pQc^$}t=?2parVorg z{Qh04@y~%9uM0&mb7AapB=^ZaeUAP1@W;Vx#MrY5MQc^f`#w-V}-rtZJQ>M?(%Xg;qnov|c^ZepT7e=NQPS2ke zX*ah=w~Ptr&zK!4nK^U%tO&k78_B$p zn16os_QFXe1(^jXpfjr^4_`5W-PA<_Trh3-p%ZXxXSy>pBW~?8+-aF^{c-NJh+Dt6 zv1dBLP_P^Sb>hDc{MVZQdhp+H{%g;FokBsvy&}PcXhESl|Fz;jBX*=MoB!NHPQ>uq z1x9289ZVlNV*Q;<=mfIrLL{~4~G!Kt1$aJ?m8&5mA)kwE&!8rGQ=d%GB{hD-U9^O=m zH+dzlJo%=QOfxu*dd*CR|EW^ww&ys?bL>#Xuc~I2H0>$>(>%}NiTPfjC%k%V;s)Kmbc^zz8Hk%2o9cdZ&}7-vy-7B%Be)-{c`fyt zmDg}TR?}Fa2Kuo#s>H@$JD@CEU`CtR08=^Oc%$)GmwTzJmOsASj=IZ&<|LU8W83e? zm)mo2bI?}sM_vSWFsf84sCB$I-_(ma2hF8bI^P!ipm!?l0DQxITU%c$_&2DbfGOAas+XZ&h5X689=ea| zd_AG7!{ZCiaG!S071zG;{|-I zo2C`O0K7fX)O(`o3oUhiZ}Va`Ew9SR_i8MI->B$Shgmxyd*?DX^1Tu}S>IM0EPmv> z&TE<8$XAl-UJ`Ma1WMeyG5EQ@!S5v}(6U*}W~~Re?Q~{G_u@?BIeq4g^CRZp>>0BP z&!3T>7vUGTCQckRXtcSFom^N_oIfYOc-ExpyuWqeo84_ zW|d5uF(uyw=bdrfEi)1uJ#1{hfxNvx{HCAx=J6qLlWme`%E%LPGjZa`(PR5(cXNvR z7nY35pEG9C{G^Fw_w3R+tLrbl;#7%$R>92Tl1LRN z6w=EN&I!sGoiwFnX0bDKc1bq>b@J+Q^uTdA8<*ynTvC+pMXSP_S{^;n@dD$7=0~Sb zI^UT(edeSRp4HBsP>-?nVrNo6Z6?nyDakLMI{gxJ7QM`w>hGM*U^cu?Qtv_%*BOyd8q!P0gz4eI4sh_8Ej%+6JcaM%sK5h>hx@<1fdyl*v!1bsfGE)P9aW* z$-0BH)GN}CCt-~FwTEAe5mb3(kbdz+a*Ah8$)7cAX7Q|ypW-a_>*V0K9e*P_fp)Ma z48S?cpWAU*XD2Z^X;_V5olw2N34sP~!$6}z<3O`u%K#@8@gV>l7L$(Kh z9rsU*EDm3lbampd5|)Inajy+t7Z{L+=^wuye?1>buc3_$%!KKemcBT2m3wvYMkJm& z>yisgCQSxQiai!s8!}$vWadpOndD?no`oORbjW0HJM8SR-yg->fATWX_$yW8d%E$> z%bz^^{E3A#rp`q2#y)BCWb_Ef=R1Ao6u&qL-RAs!7{jaB2kNgE>-Q-9{P7iS za-0a4j|u9qemfxh<10mc>9xK1YQfLu?>*RU7)Egt#)-w% z#P=@z{PC@SqVl{U+E{#_!Or+>8SlaB#Vv95O#g4=^roT#T?99KP=_WF|Ip-$tov)w z>ud$-P;3l6>f0mrV$2{~0c3f3)Q6J49Gjo;^2&Oy4`b_vW%6|gX9?nK>r22|Nni1t z_mSv&IHK9a;!B5}X;z7EzT=>&#ts`_%t02vd&oKXz26_VVtx_v`*Xtd{3%in;nOz$ z!`6!D=3*sARsRIPGQuau`P)&;hG&nfJX|a_@*l3_Ygq7bP0Oy-aIt{Jf4F#+mj7_E zc9iwX`t%N-vC6|WHSU+|RSK}VSkYp>?*jW)R81Y!M>p76iyYJHp!{b`=5?>f03&uRud@xUfE%Zl2Pn-Bu-Xquo)UJ&qNU89`6l; zs5aIdd4kCH9YpoEAyE*H|Mbrm`-lU?9FgxDqTXcje6d8lM7&zOL0lo;F5WF}68|VZ zCO#!TBfcsg6nT=Ek6L0gv7^{qJX4$`@}s2;w^`gKzAU~i?iV|w3sIjd7sxBb=fqv& zd*Wvz8kf;;D~=F3lMzHW;wk|0JQ4#sXHOV^vE+*-Um=;Z;PmGVHT7?nyiW2)@gebP z@vq`L;-})bVhXxE<7+6k5j&Ge?^MbCB@YuPkjQ^7iFP!TL_BlF%jJHxJzePZI~qeVF94#EIfG67kItFPHn(;&pPr zNi385ZQ?!R??~ili{z)oXXU}8uB+~s@{zQBENdPaDY@lKEXdmaCr_mHP+#Zm=VL-YfS%O5Q3yMX9g4W67-~cM!Xg7!Ui9ILH0PsQh!}f3DKIO#XLDzE^xe?vF}-T6~#Adaug=Be{Pe_pjuhh8q^WF1g<;d5h%jB;t8a?(fL`Be{Pn_Ym^Td}EP; z(XT@y-Ij7cSAoTVFC>2@xn7#*-;hMS?MV1#i{0dYn&iRaNO1y*_;X2wFOvHu;(WRPN^+@K zF0LgJ{&w+qa^EaIMk3xnOWq;ANg~`H`TtAu_mUeU4E>vtFqtIE)m`i@_d$|}i)V|I zNrazD!pxET0&%h2mq}hNu9y37B|j)`k^57UUl89Qk?aNqxpJKTqr`K> z^F;Hz2mTjHzCyf8TqoWk-Xq>C@&n0?{}J&|;?v>_qWK*Ky}wJ|Cw?M+CjLvrLu(Un zGJiKAT$*@-*hp+4wh=psTxrN~-Nj#sQSl6MtT}m8__4_6z>K#-Y^vX75pl3MR2(gy zElw7viWiBq#Vf^Mi8qSNMDu$R>E9;#Zt=I`1L9`U{H}!li;}DSzJ&X`a(_?!T>MhR zqajn?keDLY5?hPy#8br1qWPT(`?->@6K@h%imSxU;ui5;@jcP}UWENC$^6hQ&qtzo zg4jrmh^@u$;xEKA#NpxuF;^@W=ZJTRzY+I{d&SSiFU2HW%b33uv5r_@JV|UXjupp? z<>Ia4JK{gYZ2gYuDh?8dh&kdIajrN|+$i!3CY4oh=;_)x}JZs7!g~GW5w~} zN^zCAQQRcHCB7rJ!h>_>x2;$xUMM~yJ}y2jJ|n&*z9SwKzYs%s(9Zb7VlA<**it-6 z>?mf71I5AO+2Xn4bg@XhSiDTUUMv-VE8Zt=6}O2y#GT@9@o(Zs;-}*GqKml)mb0PQ zR6I=_Af6!(7bl7N;%xB}ah14Md{X?g_=WhD*cEdh%tudgh&W7~B<73r#YN&Z;tk>h z;%4z#@kQ|y@iXyTF@PU7%tr&UiP%bPD|Qomi9^I;;uvw9c)oanSS-#FuMuw$*NE%I zKZp;BTg7eS>*8DDHzFsTS)N*AU9q{?N^CD?ioL`>;%M<~u~?iVt`qMN?-lPCw~Nn- zJH=h%KJg9xsrbFk=A6Ymr^ikrk&#W%!{#e-s~xmS*`*jQ{PW{X|LbH$0`46#^TM&jOmrMOnS zUA#xUSA1N2QhY{yL3~AgUHm}&SUelOhxJ}$Hz9{}xd_#O&{8ap0{FnH>nApOr zuVk@~SYK=|wh}vu-Ne(x0pgkB2=OfO9I;TmP`q5cLR>E1BHk(9Ej}SWB|aza5MLMH z68DPliwDF*VnR!={58aMv7UIM*h1_eW{KU!Ux)+5)5X!^+2T}jnpiB(5w8}n6<3LC z#e2p3#plEw;%nk=@hkCLG1ST{Z&*A@Y%dNLhl-=cv&D(x6mf=FEM6+k7q1a-5Lbw0 z;$7lK@%Q2%#oglH#P`Gx#kAI5dFqJ0#6IF6afmoZ94Af`r-(DeVsW9kSiDZWNxWVB zwRo?1zxa^&sQ8Tdg7})aTYOi1Pdq4oA-Zk6@+OH5#in8_v8{NfI6_Q9c!7ACxInx|yjOfn zd`E24*2`apc#$|;d`kR_xJ!If+%FywzZCx^rnK|ouO;>p`-t6?=-m6eo#G#hb-7;(GBh@lWFW;(jr;y_bHv*hTCiE)!RZhr|kT;mKb3#bUh< zp4?E}Bt9T+6Ss?RihIOb9lh{%#l~VYajG~?d{BH?#I{OvKT=0*Ew&TKisQxA;yUpk z;s;{)Q@r?oA@&!e;xuuFxK_Mfyj%RO_^kM%_=WhDn2_bAS3_(ho+u6$hl-bp3&bbI zKZ_~ZUVOF0iQ*J-mUyvvyZCGIJ@G@aeJ3xzOz~22zIdH@lUOFM5q~S*C%z=UB7P-) zE1uoiOYdCqA@NahP#4dCi1?EDig;mH&;KIv3h^qjT)b6$PTV2BChitnb@SqDE6x;W ziGLQK72guy5!1SR;p>QF#Bt&(ajm#tJRp84{!2{jq4>l`;)!BMFuLUEzESX?gNBHkhXM!Z+NUwlmbllZdus`#P!iI~*WD_@G3DRvV3iG#$k;&?Gv z%o9t*x#IO=srXy*K5?_SMSM~GtN4caw)lzonOLWnm;d@=FR_m}Rh%ZS7T1Zp#lMN4 zil2)~zfk>%b;SDOsbW8Iw0O37p?Hy4Dy|S$i|fRD#CyeU;&yR|xKrFGek6V^ekUgM z_VQmtY$!GrTZwJOUSc0{m^f1Wr8r3}5T}cC#d+fOVySqic(?c$@pk>r5;uy^i!X`)6u%bR_3`rALA*em zDJ~GN6mJn%i?@rv79SQL6JHZ|i{FdxXeDq zo%n0<9`PaZQSmu(hxnSfTl`o&D2DoaB01_=@COXJZinrH<&l?+3PI8)dq@n6siM(` ze^bd35kJpNINW9#;&#Ijmn}mK1BQdep<<3WM$8rS!~$`;SR|H+bH#b$67hPmR9qpJ ziEG65;s$Y(_<*=s+#+rjw~0H%o#HO>O>vL7S3Dpd5-Y@SM6(}+^&jx+i*H!t`KTv0 z6q||>v9-uIuTj5?*hB0s@(phEA1d-KY?Q}{xniDJAWj#H#1e6#xL8~wUN4r4E5!BU z2JtR&qqs?YK-?;B6Ss@ci95ud;vR9Y_`bMbtPsBuxwVYt#|sJ!)5UsXL$RqC5nGFP z-BuULJ;dH(UvZ$ABaRWri4(+JF;6TKOT@Y2JkhS}x?XarxI!!w*NA-c8_OHN?&|@$ zZx*+R+r{U^9pX-LkGNNSU)(Pq5D$qJ;y0q%U&Q)%RsUi=v7y*hjEJqpc47xHe!W>= zxepWvi$g`e3C^^CF;~nJ3&iPSkys+m73YZy#l@o8=Y;abuTxti|MlVq@h)+rxJi6K z+$?Spw~Nn-JH(yhF7ZuqkGNNSU)(Pq5D$sG5SacUhQ(AdU92bCb#kpGw-Y;vJ;dH( zUvZ!qzrHRvL7SA1XGFCGvNi522EV*L8ObkqgUS3R+z*i?*&@$33J$URH!BK8o? zJ~P+{OCBobh-1WY;smikoGuoLCE`MHvA9IMUMv+?h-Km$alN=fyi43DZWgzQTg7eS zcJVoJhqzPRCB7-{5%-D*#6x0*_>CCG4HwTxs+ca;6V3WX+<%$%i(ostgB`>kVsEjp zI8e+H&AvE<8zS>xL({K-X(4nH;Y@u zt>QLuyZD^AL)vQ7KtU|TydUg_Io1yV#!Oy>%}s0jksRiAl@Zz6gPmy@}!FCB+gwu(f&TaP}di;zm)#`yyiDVgf?|*hyR<~~5B9ZQ$I>CoWZt{Xb zL!;gcpAi|30N#>;pRcjwP@1tObTMd$rH=KT^arws-uK1A1%ZVFa~BmoSu|=#&DSB% z?75=>=*-OA0cm3E9p6X#-k-ju==4ZNuO0PX@0*deV`0Xjms*`U;y|R%pK`Cvbt0ea zgZ_dKUuq7wu-x|UOV4=cr6xm090;^}GWQB-?cUeu3`n(~$Xx_!=f3*z3)c1gp5Ipw zVM7Z0^uF5A>?_U3_tk>tLTPT^mkPgh`Q5kAd7MSUBT|P&{7!|&Pe%u*!@Q~gJFppy z*)Ik1$qApW1eW99Kz}XK4@WSN$ai44e}rGKJ)XM5B|Mb~CUl}lZ~O~(8)ICOwgK)T zs*W%^p@c#74kcYd|8N4|mKqEvt%pV^l)%@#!EZVBLrLZlLm=GLsDw^6j-hi*xX^Go zCIsA(fqjq@xhc#^EQZE{#JBN(ej;YaoXZor8EszTZ{T}b;@fb!)Ja+c!5ts?J*1>u z{BsKe=K|r-=jQ(q{I8MjzMV85L6cvj!k#2L;x*UF*TT(xCn?K_!Q{s&zAMp9uFIJJ zp7g!(4J8j_*u6;!PztsRC$o;-e<-TdjS)pnW-u_4Vg$cN(=a3K1jew!vP1Y6 z4zY~2Oo^eLUJAGG^=h3^W_{)%P=}9uYO!iM#8etMwQIp4bZSper3v5!Y6se+)lG5J znxu_QtQ{B?NN0aV#J1)Tqp+HIs+!F$DPizOJrZsV9 zq@6(Ra4p0_OO3id-Q=2Hgiz^$p(!OZa9XODLfh0Kb!!Le1o|f4(m$2arY1OU*h`zc zp=v@@Rw$-*sUp@21cuaQsPq=jkh1D>6A8#~&= zhHv{3JP#q~^FYoz+RpGi2tLa7JZL-5^B{6zJP+E6U=S5i4C8swHsA9g7Q%QQwDB1( zLJ&8?cpkK^@;rz&F%R1A@;r!pVji?T=y?!)qU%LP+cwXGI1uxIC3duj4WHs7SZP#}?7( zu!I{u9fGB#jxDXxVPPNhbO;uhI=0|O2X3*$EB7c{?gW;*Rgfhg2!rqE5of?4mLNG4 zMq0FvgMk)t9t^d}To`H5%5el*#C#ZPkqcp@Me7O}Xc0W;)UxMZT0Hq{JuO1D6tuM@ zt$X10u%|_^?2L;%03$8fVh4*Ka7Gg>x~JjN+7|{s1WS*2T(YtjTw2G#K#MpJhFWAU zjN+no8Vt0EA{c6sY(mna^=cSs5!b^|i(~_l7OkZ)&>~bSSSy!7pEkdouwXH>Q zvArDdwD3Q6w1+L|WUV7Rz@UF-0o0^3V2-BvA2ha*=Yapz@gIJ9J;v#vw~74tK5+5> z@AoXcZ(ZQO{k(>GshR&Bo`o|COD0~_IU6tFMbTp4wLqQlm1z3n1+Hr51!;Ku=FAxr z@zzm%m?Q4v7kCwMySDC}%vLR1wsLnk54UmuYe8?fYe};{c+GaieG-?(Ga_!=-c9?u zLnCh2h&wLgKI3G<`)+vef;ZIQi4SHph`2Rq&5gJ%WIZe5o*Z$TMWFsis6XRGPJ(q4 ztS=$tG`bIpxVu+`5ZH7^q7g! zenW?DO?=`{yk*^uXcZ+!q@_rApdb;qR@9-`{*w+R(>S4$=N4%b?Tllnv z3Bw#qFAF;H>H05d_Oi!oWDOX5l;OnYKxhC%9U7)L8ph@UR;M+D(`@E_ej{M_$M-(s z+YDXCmk49yo9GJzt1|@!Iz)>Oo7P2;t({(ckHrK=qQm-K2-%@ zLfCB>Se@Uaa1mN`SigCY{qb=@NjlsZA0EBL;#&^84Fjw5SHwp>dsx4l;NXuh-4`Ez zk;US>6LuShar_uvD!#}`3-JWtG@`S}P^z7K|BvS4`pD%o)!iaT%g-vZ;; z>x)dW?(IQ8nx|lJs*0@pebDP{1&}&CUWc)E%6p;LjusvE6utu4UygRZdO_2P)k|&I zZJTElscDY$9xXa-TBNUd&YN}64&c}j?)*{7ba{T5ra!*kNNhaZ>|x`xvZdesr+6OLB_LNd`C3phx;MPC*Z_V zk7GaCS?n*46xrYCKT}*Fnl)E&zlCyw@Sv*DTDPjq((H|%d7I6n>+|Lq!DNYhE z5NC>W#7o7+;u7&D(VSo8?^emTiRS#meWPUlGG;j*7M~EG63uyr|6e7)A-*k|^9=v} zl0O%}6axV-e)Fsqda07rMLrv4`t}`a9VKUry~IA^AaRIj+6}^wm3*E!Su7MU6laT< zh>OIl#T&$>V!3#$_-pYV(X>0H{|CvBicg5ohdCp zE#hkN*Wx|mec~U)N5v<^__cYj$$hu@cX6L+-tCS2|5Ng}VgMIxmaB$XQ;dkM#goNT z#9m?_agaDf94U?!bHzOI0&%8j-WiU3TqfDPGaNF%p3VF%70tWDA>S(bHZgwf+#lus zi1?)VXYpn6Rq-wH9q|M4W3fW~Ms!17zLLaRVqLMB*iz*51kYM3kJ>fV=$C3jc%c&`{@`?;DiJxxbCgHvWa;y|LLwj=k>hs?IiUGV#P_8}Cz8nr*ya zVj2==8cDMl#qZ4wWlCT$gut0co^u>pbFy3S&EU}|KY(LLAYF6v#IY-XC{ygXS zlg~M>#Zdo$aLzHi>yMpte9`gEIqu|~<8LtM*o||Jk78=@DO?%{N8FQoLmp=59A7YV zj(5WQEqFg{<{S$nZlj2s%sIzjM%*@LZgFhH?Wh^YKS23;Z^rSru)czDQ#Ipw>M>^= zv%4Ptxy!>RfQ~rh=zR;-n|F-OmYGScDl?A%&itaOcQdOMi;%N&|5-DRl{0p+$-Mu8 zxkuEK`BH8y%_?({Rc8wQ-)oIcCLUuRvifJBXhMfiOCGL@R%JiQ8$VBZc!T>7nsM}= zv;I%dIik{ko^#ZV9)N+#nro&QbStcFqyvf6koa z05l2Ch2@B2#mVCT);Y&o=-kYAGttZ~K{oG;0L^ztLGv9R(99KqKhHU$-tdh5=Q&5O z9)6y4^y-0+h1o8Co^$l-;paI=uO9y2nRD#X-8bbJIo6zGkF4(4?a1TU`yB5|$Hf$L zSX~V4KF2;)_Bl?|KF7g38k>ENz05wxj=p`4BjD3Fqrchbn1#KEk-8%e6pi9e#o#0- z@{!r?xbLO*@Cn0bdd%l-?0MY%QX9AjT8%g`C+7b0z7}+Y?$nsu_I)S9EeN-QnA>Cf z8o@0Dw`noA2lkx+x4v*Ij=9~luQuEk!mT9cwtintxTV8wM$By`XQhs7Z=_kzVCpOs z=!EOMxu55vj`#!fl&dg)xnJ;Rz|K>0BM2ua=`oL^o8223q*f^5D!PS|IFo_N$zMjAoLVl?;SO8I{mw#xdkgYKCrvqnVuKVzER{f;x$tps^s4`zPlo-Ux@w z6H{TIm&o-HmnAlZFE&JSu>>|ma?MWC*|Zl2R>2+)an(&YGz9-^)N^ZxS>EIm@XxIq zrX!~)`7$ZDUO3B$!DOxcA|^b1vtqi`e1K)K#-TlD`A6H;Ul$HE)iO zwrQRRF+Ju%+ak|{SRC`9ZKdZyl*K$~yT|h&xKzzcgSN*!4`M5f=Rw=cFvu0L6UOtP z?LE(fU~BL^Xk&9n2!iGJJRro5_OMkqSJ~HdCs+yCt!Bt7FnbMYIR^$|3DyU7NY;kY zp`{oGIs~hRI<|_84r}OYPlsSFQODMn(P3q+@^lDR7(J+W{nOj_CrsH_*yz7E7|D49y{8@hW(EO$0~1! zUXa$oo)4i~4w9o_q($pw7=$OL!5}|DlGQ6MS}%ox7O@D1S|lr2TC{Q?h8Cf^4%)hw z7Hj)b9Oqqt~& z8U|X#%P`a;S=rK}^$i$k5v*@&k*sWK(fSDtvoxbJexw;WTxPdX*dvQKW=!sYzzPR!3f z0(R=%w2OObX6u$_GI$$Y&y2XcG5u>aZ-&NxxZR5xV5#Lr+!G_529|tw#BJ}Fv46FD z#BCMvBH$GAo17Ik(cKDZuQxGlWX>5s=R~mEAQ1RBCTG1mihG)P#Hl`LA8~T|@Ict- z%K)*t%VX|yjZF_9KHu!yQ#-LsR?lwE%o+KUFVPOw|Ma=#SPlIT%qYjwsxp&&T)SA! zqJYkwuoXEL$&cO7`hR$ynB(hz!`@W(sGsMFbs@8tv>!81?7t3%6mJKxhVNoIw7z#Y z!#$4Fp$Wr`hOv2o)foqYdn4>&{YJpSAKx0pw;7&{FA>JZ7r!@kH7@>#Y-FH~k8_pQ zPVbu#!EO9$tHb(T2-%-5zd7n89eZzTRLxWWn$_ zCDn1Bj5}}i-vZ;;`z-DF=82~uvE!L1E`we>W-+8J#2hdw)DIIckNC6#wKQR z8xxRU_Mpn+fAii{jy2WoO&wa9eXpM!>1GP|vqzaHwzp@RC-!cX;_mGn)+6_(vQcnv zYDf%=W{(}*%^o|@?4bc0%AZdc87?BS_WwKgrk=<6(eLub>EbN$3UP^elW2YmBAnU7 z2yT!&f7>y>&7%382YH+1XT%-itKwVY2VyeIk8q8|c4BuiDvlNN#988%VyReVPb$Xp zJLrya?hoR_(%UAP`!SgQUnTF7{I2AEk`GEw!vH}2Y!SsU^KtC^oR`B8XvlGZaztz` z{=7HUtCufT9|6`Y>M23|d2gy$A3xRJ)H-aZs9(OXkUUXrA#$G--OXNWu$$ywVn1<^ zI7}QVo+BRbUR6#kFuiNVrQ*%vdU1pJU*hk?KZ=itPm9lpFNv>+Z;9`S@!yU3Qttl} zU0k@Cza+7aSYJF*Y$0Zd9mO7EZ*hQlx;R1{EuJS%77N7-#o6K|;$m@$c$2tXlO7_>>s`eTUt0|C_i^{7B@?5Yr1{03>UOHN}QvQ?ZrURy;-QEcOxm zi$la=;#hIKm?sv9GsRirW#R(yTJc8lX0cqnO}tZ#|Ng=wa(`U>v-qs|s`!TZj`$Dp zWAUIE|DA;-)+J1eSXXQywiHhiJBrz2Pw`Z7usBp4EuJk-6sL%s+GF~cii^an#T&$> zqPcIuj{|$X!?13`qj-kqz6ZLzRSH6h_sWd_lpfh#F)1HAjx~>;-KBG<9!C4v^Y{x} zAQ4E>E% zL$|ui0|!GjQlsN5LR-!sKQ7uc`u&&ReLuNid_}_6h0#gT^ym%mhtlcRGrA}`&iKAn z5!(7{g|q46f*}>5RA&{ns4+g8o7>medPd!7PSjaW*Fe-MlkdnJ`7VljdI4zBFKJb{ zi(9^;{}6ocA#GrdgW(zvz7$@auxgxh#r?tdsY~a*UUON(+SFUqR@W*k34e;$PbIHN zxn;zM+mdT650@q_4X>)P=B$D?C%P+NM!ssSNm@ImA~`a)BJ^DCXl|?oV=I!gc2m%Z%5iQFV{^-|h~?P&4Xj9Zyi&Lb@971km9RRo zd=UKq*)UXgU;og+gnBjI$$Y}okT(f6|(7qWkJJgk3sA=pdU zwlg#Wc&?Rw#glu++PTtMo4Bg7-%NPD@vZ1JTiE-?srO}=oTKNUPlVKayguXkFa>Wk z_T-UB!5fV{+4QGP=udGmqF04?Ry19oSGXy+g+^Z+<92)uscM|tE5eS~^E{oz)$DDL z^xs~Q>V(nX?ofYo9xwXCm2($u3Y;8@){G|a2uCLuv{-V-H9Q}C<_6lO?g(xwdNi>x zu%v&%mDjY3IxDTuXD_u_^6oWv6ts&5(Q}LX!u|2pyjL*SvQS_z7~lh@F8IL|e*{CJ zrEtSCtAWsW&HHiM_ct!#wL~!CYXo!6kAQA`B!zcCm|yClgi{#eB>W5Jl+YuTWPaL* z6U^Il!sey(l`F2yt9n97Pw-b;Ap8yy4w<#x;SgVQlQ5a-6bCX8RbuG(=6??UCvmCN zF!+V}AOK6H=ooC}y$B6UrMeq27`~suPmt(_`KugDr5-oFq3~jcZ4iFSh~Y4wVPL70 z7gcKbV=6b2m=@kh-^O9)A=oP2NjQsglkl@ZjX(%_4J&$XaRn3X z2$Rg*1{M|KKOZtBGeqD@`tmtSGBXfZ%=E8=Nhx#!zoIHDFlCyA0~9Whkb&^2(xhBOyg2ybW_ETildSYAL;np>E>&cTTo67a%8z9$a?RGYy|I3I-*%LoAB2xCm!I(9u%?kEJ zepIP8Yq*OE%Wogmo`kTTSdY)#>jlQ*6ybvbu$#7b4qOBL`rHXv$v2votKs6c*D3oQ7=G0scmkGCJ+0kQ%Y8HV#b3 z|3J?`pb6t|!gJ*PdkQxA{LpV3_`hP1Xuo2Rn zy;u?{HVJ)t;RM9#%V+&-76nk7+2#Wa4X(xd%3$)+{z$B$=W%oY)a<%AE8Yhd8vCQ= zhZmY8RDO5?ClA+*%gs}MWS;icBu6>dx%_=tD-ZrC!y-I_{y}Fc&vEQ%3LBQ25nk}6 zn-;`8VL=ArKZ;QBF@Eoe@g7aQ0K+AIqu0@9t}M>d!LXVGMKE(oT$*F%DbVa(XXyhA z5W7(hIA<}8`QnN1W$^DJ+$S&$N3OBqXju<~l|cl zNd`ml;c5L|WWHhZ3bUlIxoO80EQ{Hq#=O^-nktK;RsMo^h2 ze`waQ=VNog+#<20!xH0kP+c$T)Qm5J87|onW9b?erlqNku3r2# zGM29Q9OF+$Wh~6-kvcyw(MRk2^gl}H_ktg}^DFrAb^hm2B&2o3&L4!o>8!MDhe7*c z81sPI*W~@(fL&>=4M)rECfsO(VXJihxUTsp__N28)Q#)$3VwK3#DMWbdc2bBTbbNw zCZQ@mJelL@@huUaQ==Hk39k@m?}3$dh6a1&9?$m99~1~m6dUWfZ-72W?D5_>b8ZFd z{5u$&9zykWc=rxCW+d=(b=Wvj+0mF4Dpl!D%n1vTrb4t_${upGalw`d5vxzzf>kDE z%ZFGKGrma3IC`ucDQv7&MjIP(mC+_X$4#rran*6e7Th~gOwE@+Z^Vs@BN?^A9UKUu z!6p7=R}Kpt^{N?Mm?)=Ok@w2M#iomRy?TiaQHTVcgywR?M9>Ztb~jb%E)E2GyXg_PDB`B~b}#6S zM*=~&<#ys!{u|1Fz4)&s|4re)R{VD&|MlfR_o7VV6k|UjVsMFZI*0a?jKihI-9*`( z4lVd^qUU82J&Ib6QOoo4*7OWd8t1l%v^p{S#8%nvKzv-LH~(*SB27JxYZY5pyakJW zw>gpKaL9DGJIqI*HUFK-e+B$^7XPt)fz$c#H2!1x0xVykE&sWuL;+SufLRT=rbGdj zD8Ld0Sfap4&x={LYOINPHI^vQhyP3{lU5eRQ_h?{n;+k4XFkD$|K~K5d$GcT;-1vrVm;vv?H} z2(oO!4*bWWRyjG$Pp}RDHQ~Sh{O4Y5&f9IYo0Df+K{JXy`OkmW;=*?~;ZwY`HoG@Z z4t`+aDS}$wZ-Z!gX%V+L;->X>r+a!${=JrWv9IOTGCB3mQ}8EkdDFbS)%RN7v~hSJ znOYuRT-LcaUtiW84UZVtszq}*8gY9?T6A*znYQLWiJ=gu_J3(}o8w|7eMUt8&p~s` z$aIO0XSjEux&6(FywG!?J2!Jg-&iy2-yiLQOZ_j7^y_Da4h|sqF6r5gdhR8?z1G;j zr*z!eXSnH^Zjq@+(@d7cTF@xdOy-&sIl|a4@v1w;JD;-+Ok*@H4pAB{uVMD1-TXs4 zqTNJ1mbQULZLV>xHe!=xH4z(kFHW!bxar=RFFM2BgGTK78u3mi(6U*}W?9J9wEk{U zrklLzv|&AiL8ugB!F_c4r1PEQ+hO1h+FZ+4JSnemZl{TpXP1=Z7f+pj$;84LbMlL4 z<(mxxhc9;1o5k#UHhxKK*v!1bsfGE))qNjpR^g1ZCQWy$ZXfue8w5@tJ~lES(j~Kd zX6Hz!tn5zNowB+|+Tnvi`IBblXGG4$+V@lPFPxm8mzST{vCG8n9VZv#HE0Eq;`}*< zvkGUq9#o@HC4o#s4VBd|81+|TIWAy<}6lc zmG}KszW%P-)5$Xxdu1FgW}86lEp%01RCoT2{Jej<@YPAbN?ej~P3T(py5Nn0erW}MJ>I?@NskY%?7`c=erf58 zLsz+1BbNSYykE_nb;*VJIv!Y3?6JVwO7ih!I5Tfj$s{Lp@~m0jrU5!;9`OvCeFaBW z@%P!Ps{XH}@bvwsZ%}B0s>N>$hrbSZbny`T@7=0n@d8|^r#tb(^ytTP&4=;Fw*j91pC#1eaVd;HzP?yI%I3=W7>|u_4eX519tRNLIvWWbtzQ}J{`kfr zzQHI5<1-I$LB@L*j12>;b5jbwiQsdv)`#QtBG_#36(i7L^&W)mPj@|j`E7+B)AjF9 z_zPqkhEX)CU%9t{vi0M%gFn7p%o;}E#`v&wKUObq!fwOB>I^}A5n6Ouzg>|1@hwDr zY(tEXdjo7ee*(J=1FKVr_|CSC+voQo?Ed&RAwGNF>cY>)#~rGSk7@DPih-)ob_&S! zqv6_Ezg|Z3>i18iK?$d`2tmxT3VNNb05T39d{AWVly^XHAuT#=(`g1Je>t}M>V@U8 z<%r)ukrToCE?)xHO8ScDgik`+aOC)msx_`immJ#2hdw)DII6#FL{ z*oX~nt$2>yFHzOs*ASq>{S#IFeI3L2v&U5)uDJ^OW%i89!!<42FSFJw4}QDLf4KOn z6(<2%pWeYUR(ZIlMfzo)fy%>0?oX@~O+4-6WHg7^!E^?~@EmZg<^GIcO6Ik>4(iK} zdmQWPpnjHt_AvR3zlFs`Ft$}=;>1b$lO`8VoH}dvWG5y}%FC-1E}T8x+y)(Xo6L)8 zwU=xEwYZwZO`!O@N5|=fOedqdhKu7!oa`d;QWDjDwRof4%Ou|}-a{gubW|G2r?w;? z$}zsa;u$338zWATdx7L)@lq1uKa@Y8<1wBvIvw5XiF~F@_u=9=xlb0kMw|X-Aq054 z+&7Ak$^T{XO}W1({-F9n{;I7Xq+dtnI!WXMSLUz3IFv;FoF$$|BED&oOT>93!tED7 zlRFoI&^?(%JoQx$PLxq@Cpl9x*Su3dS2EXIP@W@sA&K-&JtBOmJ!~T!T)3UgIebmkg_ujEAaOBnFAWU^5KD z9KnLA+QWk3g(FN5|FBKTkk4U*xWKj{(P4T2M1Njm$R6S#k^P+RBgON?d~uq1vB>d( z`d5j|#Z}^M;$7nJ#0SJz#J%F@Vi4z<@zxe2BCk<&?;{Qu&lM+=379by*`D}aK(;4_ zn=jeyL4tgP+R(;+G;Hhf%MtX!dMCHmkIdUY6Xs{D=85 z@8N>K*`ooTD}UZoFrJIWtHkBvDiYz@&x2Tl@@w%P`9C24$0cu*{G#NYlK&=oujEf9 zACjDk_Q!lQ7Tbya#2j&=I77T#Ttu>-B`=eFt7P+CF2w(ch&Y4bkjfKs?PUgRM#EWlA=C6`+5*^rwhdNDs}f${KidDI@b5$M%FSX~_E?${odQ z(exv@_m*t>5#$`nXN%{G)5Rju^e5pp zH|W19d5?HNJS2W2^5%f$ts&MF>xpJ>B>cHL&eV&@@t$%I@icLOXx=H@ja2(Y3A!| z@jKD2LQ+nehVhZE}zQe%}jnx8LpiyJWlfiK`qrP6pWDK{IZEX50Wzkb5JM z3m~ay#t*Qo5YJbVzZDZvw~QZ)@(gQ>SnXzHuG6G{d(rG&g4|WI*}DX}pJXoI zr2ZI@>o+MEibZ0Hc)56mxJ0~Oyjd(4*NYp(jp8QpkK!XD7mPCf9pWzWO_3`|>3=}{ zQv8?5)r9m<6l;pLMJ_p||H)z}v730R*iRfR4i&jXmEos~7m62&bH#Zgm#|WQsaPhi z5xJ(7{=X9+6`v4a7GD*)=#~2a6hp964vY20#$r3MgUD5~)E_FIBc3PD6laNx#U&z_ z)iV5D;)CMD;&$;l@qKZ>__g?*$c4C!uc3Idc#7Cp94K;$F7GGK6Q_#P#A0!d$OXLA zzgAo--Yl*W*NeXq|4ZbGUxt57d`kR_xI^42?iT+hz9)Vt;2d=#F%F za6CnKH$*T~KjuCMdL|t7>d_snke(Tj;oqI@!usQ}g}om#_dAgLD!x1tasdhb*e`TG z7npfU<-317MITacy(*2E!Q2K<5^!@2e->67UPh9>+ML27BMJV^ug54G2g|A_c z%<~n!_taVXRz>SQ?_h6Pcx&zDQwpB1sJHO>iuBUm*fI86MQUl<(%}{9*bSE+eZC^H z6}vf>F_nb!xw#>;8?j$>bFR0OFSx2Ax3+esWk(aD0pp)gj&eyeRO)HgDo-d)G;YbO z)5`}S{v;#S#tx~lvDGPGpPOcEiRF88YZ+Toc_^B0Y~k|6(%QzBR-RN^$JpHRaOq2^ zgO{)`v0b#E+4VCd8pO^eFUJApCuMcNC{y%yGz~$md%N-i+T%1N`fNo=dv*Gu6ka|9 z(n`hNr~U}-x%NY7Z&!~E?Up}-(AO6{Ul1y5Ve*gxodlCZtJ4B0gdNX~zFzHE-wgPs zI$nLWfUj2{mA=m)tmoDOx%2dF?w&zNx2(qM^sMyG$*WSz-O?J%Q_E_uPVe+qg|jt1 z8}8kcmz~qB?wXW?=_&6A6kH`V|b0x@PZb^VQ=EsNHx~s5~dObJn@)>U?6 zHCcrewENM^MHAB|T036r^mgtxUDXd-_S|^8QnRB?*GA)FYhIog9-P~_>^IHYu4uB_ zUDI?`^R?luaOZHRaJLqvp@ZQB^y)z9U_)m?_{8Ncmo;12=H^yQPbzJFi*umXqQ&fB0O|tMROp{0$g z2o24t2u*0A_S_;GMsHzFC9j@e@K@}292u>Foo;l=Hvemu_bx!Z6VgjFqBTrAw(Yt$ zcDPc{lgCHvlzQ#b3pYMmx76EbSJ`&!l~#?RhGGb)7ll^!#}2?`oLMiXOUzjftxj5- zh*2VxIvY6&4Q&_oQmo8-(yA-bPgfQs6tLwnPZ`k@O1*NYt$w{CoU^uI5qvzC@lm&w zIw|F^SA_Z^#_Q{s;#~X6(l6RTW${wVjy5bk!Ia&L-CZ?4+Nd<$gy#TlR*J$)hCzc;qoJDjO;<^52vwUE1Xw2M@<3vV># zxKvm1c(s@XME{8L)2Md zvI!Lphfb)dha7q5Gf}P2rq?3cBiCz9Or>62Ds$DpIf8nv*@nxA{skkb=f?W*&bzIT zH8t0!-I`FAvMN}f-WmDa6z&r47CsgI zy;rztGnOI=ZOW!lXNr6~s+hVRDi`xK0>S@*VH*P`qjC)lV>dD2IxC;WfxeF=P3 z#r6Na@4ol)NJ0`2AwYna1R@}02LeP45CViP8+$5Y^`R^Q!Xj%x)QD7xAhIZ-KbKOa z6~S7iR?(uOQj4v%T9;yLU4pGasf|nP|NEVL=DnLoP;C7z_TTxudEYr_&YYP$ckbMK z&n&l7UGk2^o4f9cYCotw?*Fa2ZSA}xX?LgXDSNuK_nvyv<8Gf^n{;c+EuFU|?MmF) zE)av&>sH^FZMuI!gj|<)y8Z<<)r=k9&+zX#2y6t z{%Rk8((WDw@f9}j?0aO=&Jh(UyV46T43t5K-G4;{TY;^iv(ljJ$Rl;G+eqhK7vV1B z-?91Nkbpb6gIv4*-5n8{0uFWhcO`&wCzq(B^zZJX?xXJH9?tvdaI@$7f-MEn1-lBo zHAcg(>IeT?z0PQ;t#0!QLJK>b$oued@bD?0hU*wN&1m>p^Z4@+34g)Ec=|&h=x4c@?vF3nZOAMb*RWRIWg`lV z)R#|SHF%VL?<+%J#XS(r(?*`nS=yObrZ3w}^)#5CybrIbzUzL-M+fC|DUaPMkb?Q( z8xuY|MZvJjSDHxnvL#(2*{y(b=mjNj^ns&?DP3-n@SS$~3Wjk%3D0St`{kE;)cP2g zzhk5hIZ+r`)S3Fs)QSqT!L*LzNxDtMx{oK`H}n39jlNzeO*G;M&lxtn(U;&poq)KJ z_aP?wk^(-qadY>OXGx~17sm}0# zcj8jloyoax_&Y2QJNHgw;2W7oS6*bsA4qz!@BF=(spNhIizWA zqn%5yyH-X#m!}#o(Pg4?r)DL5h*Tz6eYRX)!~MBqyoBLJaw*PoE-jyR-p z^OZ4~&;2tc>3#%E&r0UwTz4H2XN~l+^u7-vW{nE2xZX&~(JIQ7?Dl=1v15E~sX5u_ z;~0@ORV%@Qh02G4FScrV2}m9> zf+KZsK33~KqnPudS3=M!A?Q;fF7AGo2lg|liaQ4F`Djcuw6-!!&CFJ2iMw{=I&Ukp z*i{8qkyQ&LPHR@1NkI_`MiznRbtmEgE@0kwLaxoN2w;@oyb4^bC&oWU^6+-e9h=Od zI5lli?^)^$`0%FQmKC3+7F>4+*$y?|$7Bg_0~N2TzORb4u*NK2RlcV0To<3ol4*M1 zy7oCC`YEJu|2hj{$G=Vbk0JUC(j3~7_+%8V{Rbg>9_V&e%Tb5@)K#|GrcskN{h&?b z+}QLf(mdfgs<;=TYT9v0b$>-3R3wB4DDomyNV_Ts4>Z{Xo=_x&ZSpuQ7wxJbY?Cj+ z#(WJhLb6tg)Wr(>P z<+0##P2$Ql;tC+i%dL~*Iix!uL5#juGgz<7bRt};mqNS+uh%Z-WR|D5X;QPF$LD9) z>1Y3>LJ--DFfZY2D5Cz@#roM7Ll=+oe{zw%y}CToxw^c`y7;K3i`E^B>uK0_F0aS+ z6C+FEqwGcWv9e4aBr4ar+`W}!xqIs-%iS+9&5>$Fe49k9Z%@NTbz!h<;cNEWO4(%P zeLKlc$apCXNtCUeOHy0=z|Ip&VfnJQvdvIU0+_mV~$A zEn~U6j)4Z7@YONE%L_5lbqqWNj}%}lhpI5T!eiAuAq74XS$ns+BER^eLmg=;P8ovA z^~C=aHe#cUlL#JA3d;!8jgsYypj!J!5iBz&aH@f2tn}3}u+Ju<>lk1b5Yp*dBai@Z z8kZ5|fQyK>x~U;`tD==U`>;4jt{lrvaa5VACY2d(!gj13Hw#1yW2>*WX5CizR`(Sk z_riOO@gSoaJPPk4Sptra)N%MI;Y?;KGTwx5Da_@*t!_k+#lA?fx4KmpV3So1AE~ni zk2Fi~C<+oQ$D*^8(OSHAGm5ISj5TVjK~C7}UWH62*_m>BSxZB4l`z<3t=5@R0eGa@ z8dRp_ZFTF$(KIu=AfXCtW7KYecaL2mOUh$zUK4=Y7ITgV06PXcKl;@>0u%iHQ^ z1oLi2Yk0<3?#aki(4#4N)zOwc}BsP;8THo3{ci zT;IEnfmHYiReQxnCP2)w%V8Q_2*2wxoo%nvFaS?5jm)#*IZ ziK#8BaRD6)5PjCjAa#UoOvXmf-jtAp6 zg1HqQeOx|@P@#%3o`9|4q0 z!hZ@p4urr{iUYZG9Rq{l?P|oyCQ$^B5)FWn+`R_um(oe$n=4A3=Dxsrg*f30um+g*m-~;HF97b z18g5?Lyh^d@RossG2pW=iUUe938@bxcf=9VesB)9wBnFh53{`H@tOS&syxL=wWWT0d z0`lt&FB%!-D(5RjvqDd6NLn9eVBk49g2Afy=n$k!Px0yywP*QPKO_0eszRrlL zY%FA^z{fdKAOeZVjX}A?Vy0|$lgs*XD%TJ2kAqNqYRn<4jwlXUV#5l*J2spl`7#)WBj!MzNjPkEZ~eC)NQK*Ngq(jClENB z6FqJrgrbohlxjiVsTRQFG4UYa0TnDFaONtuEF$bz!6E_=8(qofb=3%LfJdiG;8B>y zWT#r`OpdL61lk_86%!6CZBq!3+KLH04=BVI=-OthCD>|%&z~&q%}UecUjbfJ!6L$q zP=Rv2yq1A2wpxOe_vN*>LE9c%F`-1&7axU`qhglVG^V}=WudQWZm#vt< zmImoNq3dp2ErF-l@x;y3z_S>|E(N=-{FNK7=<^9?4R<0^Or9E^Sujs1Ne?7xJmonC z^Ti*yWiwr6U^LUU+2Ad3W!){T| z{bC%)X6F`mY_A1%IF8NEE$rCr+{kns8*(E@pCHGv*)XaswQGX_8b5*0CusbHG8HT$u!Vw4V0y^vq(nQp+M;DU zNL-SHK@jBTZpG?Z#nxL!upe8B3C}8JWrXM9Eu*Tkjsa!_B2X8~v6wk&XXjX=3(Rav z>Zp4xJf1oTOln7jlr(ulx0RGSm6R$afahjR%=|KVhIM|< zt=K4QS5A?x96XTlz$xu`<_!s|TD%kK>{`@SXBms!b*wx-KcbS{!TeMV|#$Qn?JoO01BNP zZhNY#tS3w}txNL7$yQ`4_OM8>V*P2IlDb-pxQ$9$MsPC{UzLH4B-CywSqxdRYHtW@ znc}OhQhJb|&A;CKQ=8x=TdqC!?n#m%6Eoy6WXhr7wR?EF^x z8BX9|C?h*@q)M#R+dJ>rd!eXO;4_&_qBd+%+7g=~)jk|*Cl{4Dw^Z-tHR&S>gc!Tq*~GbL|h_?q?V*wOZ;G910P6U(j{?e zm&CjRGFGJawU$>|3sbFDe)(^KG|Tp*QCiFVR?9h7l}cHa%J5RzxyXtRhLO=6N-FuK z3b3Kf9BZ22N`!vqX-($WU{ey3Kz2>yKg80~(vd7FDJd~A$r_w%^?#`+KPuZtZ7F2M zsLFVT2Y=31UfVQQomcJ+WnZ3`Gc=Na>I^SqsB_cUkY@Bg&e)|S&ly|C*sc6iZA`W3 zuoPj9AS_mubOaTsc6T*H6Zv<(B~?2@skC7kg&l{gp##*ct{Qc9sorlGd8*S=S(cML zk4r~2=8&qe%+I%}&t+~ZZF8N0(sCYU33UdcPD6DIVV#T87upg{Roy_AKpnX{$x1|( zN-0nW80xIP{3tsG4<^)JR5ue=zAx8u&d$nuacwShu=bmF7oh1&KUD0&c5iWMsx|nq zbZiYdHg*`TdylY6J#csc$i zq^tT?RXCZ&4Bc$klMLgjYu3IdtcAIwtV(~{$i#t{_fG4bsIFh7=O!jpA*D>6yph?+ zc_}(MEC@8s;7s(n3mls)*<1aLp1t7ms=!z6?PNcbs2zRI{_b*R#`MapY3WAgn7Oku zLet*Wy7rtIS7oYQj6!L-fzgt=q5XhV44IWf=2n%=URE}J#=O~~jfMWX9hK%(;lP@1 znxys}`o=bTI=dR|-I9X)QSpd^6|d_e+uqSBV~Jg13hgR$uG`1@|E7C3Ngdc{j9X}_ z{kYV&QAXvk1*moYXR7}!^`DJTc4POfEE}@bxxsEt3!D`n+TIBp3ye0f&(u69!ao$@ zABymwt&sV?QA}aV!%(rB`*altA0NXyna`U~Jp83)G z;MB*x7W7**qJsLyAnerl@<7Nz3H7lKw7$g%JM~S%h@10moN{yv;GO#Xd9ba4M|~`p z)^|O^x{eSuvT-48)|Kvvy9QyWzAbrJw}@k*J`Vb6eYYU&)OVyczUAy-=-~ImuFNp};87pc z2K7CIuug-Z(Yl*0$1t6adlF%%zI5ng8=}5e@VZ`JMOddn(8z?o1V=(0_glm{*hU5P z#e+wEm;(~j_YT5L!@TImrW(dw`l0~MIQkC-wcJMtECNqEE%zB1IGvT6k2_bhdp^Y? z0n=!=19F=+0p#)0aaxk|I9537g~y}og>{5{gRW~P>cx?P4iX)QXK)WGG7*PBCvrk%;28_K^V#!>=R`Z|N!A3Abb1(l322@J_O;ye z3C$(wC_f*b@$5Uf2h_%3tgWv$jNT*i>>Ig9)V*Qxp(jB53EKXSck}x}HQ6ajZw}SW zt@@k~UBTzGrcawXx21D4=Y)2jnl*P>lfo$?>>(6u_HjJii{}l&cLjO9lm8E5JM{H9 zeqw7uUR$J7h>*(`q|u!;jm5+gBIL>i=Ll8`ZX}{vY!T%2RHnOI=mUZe5uxX(&@|FB z-AlsfNE7M52!2e29v|8P`K<*z5W(jJWAf7lbBNHNFEocq8PB~b$e$tfJi#g=^c*F2 zz;HFNGZ5XU;^#=c6$;IENIh2wy;yLI;10n%1@9q3{vkp3JO-EzD!MCfTF$dPu^T?JDG`x2oyPq0Av z9BL+il3+k^f#9`*9B-svPKBa8$4g0bc$4^)@P8-tNufFMfbk82p9-=wC!fRdM2=w- z69hRx&3sY?2MKad4^>`bJoYdUqMknp z{l4HC;bSeg$~RiD4H0@cXP)KB6dWM@0-=ipCkcPC(5nSE5|QtXLhlgVON9P=gnmHq z5#b*bntO3De|}e(dRBOBL-B5g#MkN>c7Ev^ZEt05lj)}WTi+v3_e0cekj(rdat!#vix`mWPeEf zv*71~NjOgO(**kx(Y82Ik;wZN_txULCQ%Kg0iYTOi zT48GC-y=Or=m|nk6`K7Z8VT$zo z$Oo!Dh=5O!M*aR#kh3{ScM}{&gxnY+UJ{B0#}lD9Ah=v`H4*aH3B6h9TZO(~ko_X% z9vAv4pQdf9&wR|#@nE@}2-M85M8`MyuwDY#E?zu+Okp9nrJ z_?+OYg1;AhTd-d6wBTO_xlE7w>Am0Lgl0cUekVb$nIYX%FjbHX`^XSqwI_j>!a@YOm{@ZS}h z&vn%Eg&-F$l5Q)==VQ`61^GNjn#&W3x_?r8If9-hd_E5|eudx-f;S1)3Em;7`Z36> zehhd*_%90nMesvG7yAjwc?HAwWXl&m_ZFp`+OrWjQ|L8<>jn9IM!7wLTo+0DalvDP z#|2*{q96FZpxS#4^eLe~5>$IRg71_5gU@YDcY$C#K|a5c-%C*K;Rw2)(5hbpoiB8; z;CR7u!3x3fJ=vBCpI=R7K35A~CwQCSUcv7R-Ya-e@IgVYs-&K01z!;SjUZQ9GQM8$ z3qdaABR@{CjUZQDl7Eq4s$izzK*37|M++7SP86If$hnEsS1G9aU(l$H2ovt9}{ulR_UCJR$g7!B+*jDwKM-s*m`w;HQEn`)Tk!f?PIA zy1k%Zu&ZEi!3@DcfXv6+q1&wb1~&!75u&6+k*9i9}4n0netxE_89u(x#WY)LZyA7!J zYy+x2+ko#&e1jkjsFZgLwiWCkm?oGdSSUDFaE{;=f*S>E1h)#_DtM>hKEa0s9}(nQ zYL@4Bf`1ZxPw->GPX!|*ZTT2MzhGCv{(_eX@@vD?KS6MwV5Q)-f|~^E1n&_1k>EkW zp9wxL_)EcG3vw+u^ZT>l8No)uF9axJmFv!CM4(3UVzw^V=`@W5I_7j|d(Wd`|F}f-edF zPVh~^KMB4s*dWNY^32b|gEKKwFh=k~!S;elf+>Q%1v3N(2o4e)COA@%Yw?*+x!_E} z%LNw*E*4xRxK8j|!A*j-g0~3XCb(CSi~X73A;F`9#{^#yd|mJ_f*%T6c-LY22tn=^ zKsr${Q?Re#aKTZ6<$@K0iv*Vna=QWQyGd}b;GKd$7JOLnS;6N8e=qn)LGD*TeSa5> ziLvR{g2{px3FZjq3XTyh7UZ@8eE+&qaEah@LGB^I_!|Uo7Thj)yWsZ(_X+M7JS6xN zL2g1oea{NMAov@>*91=r)(iec@UMcO2y&2;`rLw1g0X_}f(e4%1bYZ_69lHu6&xx! zT(DShykNOth2Rx}3k11|0`;vItP$KSxLt6U;P(XY61-3FkRZ2SpuVRBpBMa<;O_+A z5aiYjl>boh6T!a=y7A)7c%LA*ZXn%JFi9{)FkLWP@Djnnf`x)(1@XA^jqY)(-*=Tg z1?^tl_fg(9%m;&V`u#so=zJpN<_TR%gnU{~R*v7{GP3$+_Un_Ko}Q(5H*LDdX-1#^ znYQ>>?{Qj*cRM&wwu0`kO|&#dC72iQc&u_b_Jg!)6L$OVZ**7R-{{&BS(DM|I$oW> zKHrtUG5?iDqw?iOqvFEAYmG+UGYB06=XfKQkW^qVCB(Ta#v{&+I5*_^7xD=vl!Q?20{x^OYRlh%7ow&86VF{XuU1(+`5QvRRc_jbd_ z*fLYGsR)wm+5Gi}nFyDbn3R@=e+GeYK_tgzVoIMfm@ug_;i`Z-Ip_XHqhoB3`3@aW zK6Fg!$Wr@%TIuYnrIo_TFD;rjdhU$!(uGSG&zxO8eCSYv)8+=3`ZH5AGgGl6Otsm{ zh{JY3txe0<(bvs)0bX0w7`c7Q@Ny@P?Iq~G&U__&a4~gyRn_9T_P9@~)$InMRKa1oa9YR4K0xwGeb=+SUaqrRm zw46R)>z1qiq!gHa=VJ%r zzDJ50`|SO|7+3#Pi@e6Zd-EFm9BFad?Y*Q^QKRR`b(3A$d5zv9!;8(jI}biGq*F~w z!3Fs_FW)uf_pcN+W*=bMcaZi;q|M&z?uXO|kh(=tW5nK~#uf+Mr+m?QjS&a(8e4$Q z-Qqjti70C9xAzx~#+JOs+`Z%Kk4JHr<#F{-LqoqKQK#KecKWDFq(^C@;9FGgd&k8+ zAY&_s8{A7dc3gdN)U^lhJ&mmZx4G*|FySHUwCNdF|D4&b!4>Pd#kv_oP*{1?ry#H4 z#%go>{RNku96v1Sm9}$H)=1ZOl)EDGv^%oxbk`n~xnjax*LKgIAGR-QjI5Y2-L)&P zG15<&7aQaE)*E+EcV|Ls@1N#gJL&D|*A(GM@-_uFSKtUB)uQP6z%LMPQSlJ&(AeL! zdf2c;)DCi(`@Rt~-HjUT~znmXjdL~+%9U&tat<^dLr`C=_rja zuQ4<4^SMRXb@J2cd5yk2=-OhQj&ntvj&pw}pBjIK{l-5qwpXZ{KJwJ$-vnN&c(S-t zjkU*J*W$D*(sL>*I`Xuug>}m7J3I`vYhh30EiUY(Y~ie6Pvr>TDX+Eeu@wKxDv`@~D)44i0;JL2w# zqo{UGf4cqSICBHQYqQ03%4a@f44M8k&g+o)@6R<+x2*!-o8GR%I2CEWGdD8uhv~5u z296~zn`h(JckJ^x(zo%z=FVdhjEh{`?u@W*8CQ=t@Kfu(u7XPnieKDRka=?Su((%l z37EH7x4Tby(5|``-BMxV{B-sIHBi*pBkv4qz6Z`o_lm-Rar;ov( zo1e$AsRHG5=QVb#c&#zI0y_N18>9WuQDL6;xuQ?|yyNqK)#yGFfto{_O4n(hIT4z= z9dX^BQ1gRfQ}d0jsND$nsYsvqv@d#U{-IagQh)h@%)sl7zG~M+Ln?+3%dY5DGc~{A z<(~~{^NMlm8tlp&U5#fr{|W3H&oXR4eQb2&Np8zajnR9P0v}c!Z8Y{8D21=@rh=co z^BlTOyXSP9PvAl}pGLpxyeX*58-LjR@-sxaOdoF>R)FC?Lm1)m+zZ0`F*$w96enUI zWz<;AxH;r-*bkgXDO02#1KknZ8R7G+C(jpA00`}anMtNQVgSI1kayk4&G<71GS)1PY|S{Em=rbF zFmuVLMAQ{R+)HBa0&D`va?zt$tR8a>(&B9k{~RGVIecUnYwf#?E^6^p!n*nR=M*Hn zSk=tnIg)DH-g*{`15|dguBNa#HCh!*5f?%$3#N!{5-6A=u2eB7*hW^{_dppf%?V7; z31jy3ht{~mn!Zaxn@|3MQBtUBL#c$|9PBdJQP$Ryn6SmIwWZZHXySP{!XpbV|dZZQ``Suq`B#^Z6j#N>PyECr2< z8U!ZVL|a4c^QQKva|<8OLmuH{|2MRiSjaOF;oR)a-XrhUA!^SzpX?XMZSNv+Xbut? zM#|=L5*sDE$&o~Cv?CT|%Vsm-!NBpL^g{n=JM1U2y@KBz5OmOmN1S2;qwPiJ!B_;^ zz+){vK?{`BIR$WAgFq>P0to8Z)(FJIa|L`Tx=cqCb@W(-DdIAgD6}<=rwE-No)6Hb zQ9cMTLIo!hn9zf#^rc1;gS^a1E;EuCRL%blKWKbWWqx#SWb9K1t$_%!k}t|gU(s|ILoYY+O5@PiEvI(5P{C{sC@#j+Apnr zEzq>~sSZ`X2f$Hr1jhm>>o^fz8LI@x6Bvu#tXLn)F`9aKo~YDl;J6|fefBxAPg)5<3p70^ zDTqPsvwm3~1leFH>o_Mo5zH4gM#zOnJ@|-26uX2lS_Q}R(wJd$@vj_avLTbwy;ep<@!K<8?>ZT>K^%vw8=y=V>aMIiS39 z@xsd&PoM9fGk4zXCI0R!a{BftzkI<`f7QZ;^OpGWrsbbKf5z-tvu4jK&ra><&rHwA zT$EitWA1`-7=h-^oso9=%$aEr>%Cy%g4wE+B&vVX79Ajo{$=u);qm-T1I-W^xo-Kn_RpNnx;0EtvAhVYh^0d%g?m1 z1V6fv|B<=#GZK3zX7xzCG`q(odA-xJJ7y%Nr}R!t%!JRd%2UT8HX*Z1c8_j7!5Y#d zBdK>%&A>GB5)+e?Q3k71t~E2&>XB+qOtm`s8BQuJCUJ49wYacLO2=*q$%)owEPo=) z&yuHFDSjqS${d*8&03b)jd}D-%HKW3VJx!OP4-zmAjwK&&` z&MnUDW39}+Broxj?B3lHP}nQ{nTb5alpdLBqvmz7=BHY1QYTwirdsiSE8yq$1+&R2 zwq|n|0c%-dqBYNtdgA|uejLnfe^M4T^oC}oCQTJ0xZ?Kf837k%WnjT(lU2HlGWvjJ zFGLN0_eWgVg444kvamu_t<)WIRi<%XD{5_VWse-{SIt>9{EW=>e*W%@XV05GeaY+| z{;4n@rs=DrclNY?y=TAu21|i$$HPm>Wsbpx zvud4k>Ef9geeLp|UFcB#7!c0r%QdbGs?-A7ri*%mXF)Bc4Xu>5SNRr9pINnVu@PFM zyHsmqK&iu3T86_~GH2o9`2|ZC%&fwJE#VdKG{N9XRT;^FI@kZ=piAejoNcIu(cg;Y zx5`H3Tz|_41nt=Wp0!T)1~WgVJ4{nr2+01q8M&b`IZfr*zc(W{B!+jzuVc%`pg~n? z*lAJgz*C!z!DVKgBL-L0w|v1Zs_uWwzRr6(Z`phzpv#6op+fc_AI0bj;GJ@uBY%tx zaayhdv{UXl?(xoN0xh>z23yXTj7J#ePxU0iN5f6< zIt_yAJD0~95U1mA1Fgf1S_LIP)P-`y?LgR>?{S=p@)Q2QNefEPP7~(j`!LJFR)^`|Tr@mg$$4ijnC3edW+cUG#DATHk93Qy=r9!+W$^*JM+69OL;^=alP!0ft3dNa7gZ0FP5& zsiSUyT$Uz)l%ZpL(_zv_AXmeHxZo*-kn=dI5<~TJA!PM&AUX35x)FH$<>yhf(?O!6 zx{P`4>~(h>H)sn_eXJkm>D2c*DlYioj5w_i!6weh|0dSH!lL1D!CFx~j!!g=R~EaV zJlDoHjn}<`En=xFE+~%Ub=EYGpI1i6S*m3_X|~LevsBGF>DH=FS)aD!84EeCjdeOJ zth5%aA3QItQ{MNumbJIgyuY=^@edZ7eG=EQhCkTg$-rKY+T5)voX4BeSv=g1;8=4m zTxNTx-B1AhMh;Tsz%}IN)BwXWM6dj^HrCLP5U5F`n;w#JPeC1Xl@e5WHUS zR>3`jcM0wnJS50|g?b+od`|GUf}aaos6WpAju2FK+m`%Th@D=q9qL6I{0!j_6gp4n zLZQbA%{8ygf06KM8D;v-f?Fki7ZH6oO|``TlKA}+|FGcCh0l8x_5Mm|HOC+Hn?k=W z@gE8PUHFl>_?bVy{Y300*o%ntSwvh0{R9U}{9uV6D>zB`-x2z9q2~#`Oz2fY*9yH| z=)FR7p8@83pU{s8>NQO`J?gyh%IEn}?GMOniZuIkVuGM*cc9aS?k6}8ApB8*ckVXxrdsFaFg6|79 z2!1B`gRt#r6aA z3UauBbbCR+AlE9B&k+P-j$odkT8jt%XrYS)Rl5hjTxbqDF#STo<$|i+gTF!OYX$kN zLiw8oIZQ!XT?fGZLLU%(NKjoDi2u3JPYd!Hlj(mg$hFX<-w^zh;Cq4%f@cIj6Z}Gu z10=lu+X|{RHlUM)?kUJM(v;(v32}(vNWn3JY7GwJ)fyb&6~gD*X{M_d+$ea1;7x*R zEg|I8S{)#VTA1#Kf@*CcXs)Ry|A^pG!RG{jDfp5gcaf$%$7+aw7UY_1(v5;&2wLcX z$d46NYk5F(aEJU9!QO%yf*kK*yjq(G93!+^%LAHgvl*|}@&IQE9T4OY5#v`0sx>^I z)fyfk*KRZZX2D&8dj!>eJ1VTdMEmfw|3ErA_5%=C$aes?AJxwSRX+OZ zx#IDZ!ub%cnwkUdn@82S>&6CtI^+b#{H^VIHF*s`sE(}JFeIR3HxzmW)?%m?49oK**wRNr?5vOj5G`bg^ zz>LI-Tzqr#V$MHIAKtkTUq#2)G2@WCB7X^4-XEN9-e*KJ|!%uY9WHZocf`JCz-w#ba8<=4+t6uR#*?KJm}BP#DMd zjzoBk_d5Kq_Lf3+m3JKYD~$-=D6GlmK2Q;CXc)yW0{GnT;=hH@y2Zm=Z6u$ktXn;U zz;q=Wk)ufN5YiQy%!E5V>Y_?^8xi*-iM8AFDcDgaZ*BN$9}7lT1(MF>vd!p$P-I@h zU~llEmAPOLAMVD2Y*{%H!{B*TyAnR82mZ{#B!2_nvT}uC4pDg`IW~z#+M?K7 z!7}qnc|J0Wl3g()7+pxlC`7fyIJP3LB(ZoQzG|sR-p*qZC_0MeeI6vL!h`a}u^N1C z{{QnM-T2mN6u)%FPnUVSV>mnkkFF8U@o%3V|88-CLpHLdJ#>yC@*KR&MLCD9M_$lm zbUeE0a5z61=R=k<{@u(cwqBk zu_rK|gMCF!Mz^~w0rjOD4uRUEfecX`L$_KLTQeVBu|Gbc8s0Lla@R4i(I$L#3~aNB z=sE`OhDQo7bfqeNlS8T}BThN?=sn>vG)ka^hdb&gyF_Yi*2R-9wa2|utk!;Ofj=eN%JW-C z3`F`dGMC&m(kk#Haf&UH3UMnw*E+n;Z#{)Qd=~h#?f7i#%3LdPPDT;(7z3Zd!Lkel zl84}r{!%ckoI(~N`_gXKb?YYKHNrG8zBFyj;Ia|ZMh_c195Ae;WL$}igJFx^s-;Ve z%KYh7(~Zh;ORJ0pB@34?G3?>9;7F1h^_em6%AwdNHmI&_SZUd`g25w4k1rW^egk5a z`Ae$4@!_zqH!c_~{os<}JJX8!=oolo#n6`A}lws4xj4Va14jsV(=&(yb zjcbKBxnSzCgU5~>TVO1}hP6xQFIaN+h#PHJNR5kXT5uC&+O*WzSksZXpwiOuLx&D4 zEp?2+iIz~a4{cK%)N!uSwgpS)t7f1^+o(v|3HT`Wl298c9XWRR_|b#WvtZ@L0DpI` zy(m*-{ut=?KPUE?&~(n-~looQdv8R=n``5?t|;Wq2dG;-$5_ zjd`Kj&WbnNn;p!~E}Fj7`@p%z zcND`&1e0=jH zDA<+}RO`E6Wk8(Hi|9B!V+2kHp9|Z8-x{9z^87GQeQh9UtUv~QOVUp3)3in>|C<=Q z!r?lct`(cbu`8!Ldn}4)JmmhFv8Z??XMNa?H6C(jk2Ucugq(#M)%_Ox430giv7shi zGad*-qf1R62bL?HG;H3P%p19;_ZTW3LX@ENbpg?qk?SDOm{-?CBfGP-xK86F6Ax|RAWb= zX`CRR)6a>8L^K0sO9PgWM&nguMu_JN2x-1+Q+}z?8wIZyz8XV<-1mfkx9}ejRQo|8 zy|Sr8j#dupJtf#6a-Rx~!)Rg?#Hmp<+Y-ymc12WgL%`lbX9%({V0^CNSV27OC_Y~; z8UG!@%LT6#Tq(F#@EXDE1#cEq=Mj4NMn`>j2<{g=AQ(Od^Mvr968w$eD}pBl-xB;l z@FPJN>k0XJ1!*rL-Ab^NV4`4eLE1nlmm`=fNW%*GdhBJQ&{GA~`A7Uhp_dD;5>#U^ zh`(0on*>$60AG#00QU%=#v0~#P*A<4g66%5d|GdazYJW{{G%FFJbDC$x?b9l zjt#Ysw4DB5YYktYep#7*<-Xd+`#u{b9y{!3q>zml7T#L-F0-bz#;UzR*?5P*!u!K& z_YSLOD{Q>`s&DsMyXJPTIq2d#D&H-}V6pL<4HhiE=2mmy?t>9qCM66to-qu+x7M@O z*y7%4>=+fWPUS_qcF@xMFfFHhhIdYGY@7FRqf1$Md&1KDFzmjM9_-oZNq@M}YtYVH zQQG3Puc@WC2A1CHX*IC)mfTh|y7aXgSb9r+wxzemI_+~ame$>f>be@&pmC*#8odXu zi}yEr4s^W!!GonG(`($&xxQpCq@vAUwDi`%(p#!5y}KiJ?#$nmZ|?BJ(re~qHM(Hw zy{Cz#7d&O@1y?M+>5y{ur_|J%>rsAR`qc?eORurh+A%6&=fU+ujM{Z)R-9$&H6Dw? zjoH38yUkjh7&9A<=S_8vn*PDon?hOBHxv=pPPQ?S}KZWLJ54r-7~aQV`nKn+cX>uigsUdat)_y_pod!7~yPwDlH}+$^LkvKJG6 zH)QK&Z*AQqw%)fvIBdNuLDHEVwvQeFMdl?8vZu8d8V%y6*6dhYcA=cI^{ybv&eyi} z{u-f}OGpk;MXDW*djP1Rq>7;}cILu)F!qwMm$+wMsf z2m5l-yP!S-1@o?j(tL|8z1o(Gp3Z6M#dC6OQ#s&tT9c#H(NlfwE4UBwqm*sAy&9P8T8%2745#4->!aSFT#=1_drd=`St0ajhY1{EwLY=+kcUWWH5+BWbqydNH^ zm~&T^-4va(s7AbU%&{}P%c#U>>g>YN%#0xj6^}m_=uvpo#|SFy3y*NVj@N|-Z?w*Z z;j`n@>!@pt^N=AGqA)#n~i5xS*gCNa_dO|(g&kHgiI~+%CL4I+0Eux+LEISyLHU!*e#>0_4Bp1Ejehk z3>qGr7?o)+91P34!>DYpx^S45gO*lhR1WI-_q8T}wS8DMuaI>&SVOc$2P>$l(K*N# zYqDN&(X8zlb05EKIY&^JHX?_aj+s1w{e=81PjG2Rvqoflb&Yf3#=oa2IU4=ix$Ma7 z1)H%W501%0qJPznjC1jAUsa*)G5XeGzx$wW#OXU_B52-Vv<)m=PTzbkf{gDxU#_abP_!6 zble;;beM5FsUW4_Ff$3a{Q@6^YAZ2jPAr{flZ;ndd)iujI9 zeRy;X>Z?Imr$Nx*ez%mKRVp^w*%F5fPMbsFmU6#8CrFm!M`;+*C{qRn?Y}oEt2ih@?{xCdFRi)6{|1=9qx1P2HX5~Qt%^5X@+BRE~KN^pf>wV-Mj zNViRB)gD0a75YxW2LvAyJR*2h@VKBd$|1dKC&0IaPa6`;_cuY#Y9vjg5>Z+IfP9u9 zt=6spId_w^>K`IP?FrSW_`1D)By=01(>~olqrWmY%imYeLGE+j_UW&hgZz49T=lrX z&|zv8@~xbO{G;lqnyX=*(ge&U0UWL|BdsI&8;^aG_%w^ zyQta6oTsep)0mA6`*iWIv47Wf@p+A&>W*_^pDvmn;B4ge&CW!|K6cgK zppCjaY}642oQ-VeeADxhmz`y$R+eQp4y?X>0{>0pFijH}f3|75rxGY8uqE1)kQt)5V-hm&~JdMwc&V_dxpILj9;RIviER}pJ;R<*) zADID;F=3vvF12$$a!5sOQ7Aq%ADKzXci5zv1lJ%O?{&7ThKSQS=|hNf{hQd9?QiYk zfX-t+^3z6eLUOLv%8$9hXHQ7ppe7_+qf@PHSe2twttw0)&YSdAQ<5*WO8izT?8l@1 zNSK1XevmN5S};jZRTjRQs%%e1-jHz_W*UF#ROGCVS(u1iBNLIEniaWKP0;e##EL9N zM5h&5*^j@{kZRYZJ%c%DME%d)<*#8z4%+v>%w8PY{wH|;wB`7G?ZnNQso5a@{Vm7# zd*ium$L!^ru^kVI$wOcGFWQb-zyGlv+xHZGbGZnl4_@2b&Shin1sSH{I~pD3oOdLB z-x>kF)=fFSQ*sTrb~-K}j24;+of=&hf&az42aWlb3p4b zqqu(deFsAaXCTg*?<5!={U{&vWqv#k;!=2>20`Om9JrqWaXM}hXs5mv7uxTy)E5b_ z_0=G((;#Tv4SlqmXs6>gg5lIxapt2=GUfB+T?ND#bS51!tW($2O5gq1G!Qn()@XA&QIW_kbbcM+C-G%X2 z39c1>jnLZ#cMJaqf`4+#EG&pnQ3J)&F*g4#yhOXwWIT)`&iAL(dcVfrb8GX&=d z(&WPUm4e}OkH0JYTESg{dhYRELaX)xJ!-xt@Mpq*Qt%l;8gZE4>w@ZfjKCLXG@ElXP@}Rd&a#Hd$twC7W67u*kFvn{t_*^1+oG&0`Il! zUT~zt^izLav@|fT{>_!YZdcNA=BYm|`9-4-UkQocd;h7E>t27)b?>6psD^LA#)wudoi+-^dedGE)a@vgk(F-khd2fr@ z?c3STe5?KI?T@whZi~1D-*MR0x&hy9ZMe4j^~QL7(IcUHa-;joNsaEQr`x3$Q9S~x5H5unwKUQ;7Fr3){D+p`Ney#Wb1Y#>D_h~>ny(_@9KJ&iJCO=y@|bu+4*A}OHl!9&K)oF}UQmwG3@?}n>oe=uK$+fJ^qeXa%W-vmq$~chxPpTPg-8QSx`8i>6+Pb0 zQT7p(bL~tn*jVp#^K7xyn>t@z-@;Q_!DEWX_e3J_%@TaK#Ou2G$rlWN-oZ${Lx#T* z-}l&whaLNI$!-1yjmR92ziw#kjqpwfo3z?n$n;f%4V!cyB(v1aWW7fQ?XT7`q_gxM z8Qi7F;0ShV zpt#b^W4emX5244){ge!EDJ0f;`JA}cyA9zrUe38*?cIm}Ro+{`htYZj2-jruQBV=8 zyR~=Di1;bh&o`^U_qqRp{}w*iEgq_jyqZZuyJ*}%GPH|EA!J=UJ#Cqu25i-5?Dnt= zj8bDs2ThauELzW^R~W8CW+XyJ)Zb(~Y5g274nEb1}(bBzbFzIYF|3yBO6V6uSpW%@Hi=4@llYawN$&NET7J zkYq>rIIjCJN3k?Fm@~Tm(4(25p>1gNTKm07n1Bu zasp4^J0M%JcKCWmXRdn`Nn7s#tM!feyI`6`<{{E`x7B(PXh|~~0S>X6H6NaxhR;F! z;KS1J_IU)}+>wH+3CoA_4e()UILH!*Y|Y(M&Q9|bBJ&U#O4EkN(*b@G(>xlMM^`ZS z!H4A0=xU+&LN+*`oB#h8h6>b|KRg#jkG#MiW#aLf+mvu$67|uKCZFL5+s`DX>3$}h z$L^Tr9v32U7CV_47nGRey_2FQt4vyZj11&;frF1*Ya0g{g^D`IrYGu&4O8KXyizdU za16na>xCf38wg2=x5pb8VjqGC0u!D+5aClPiwRnwm=9naOgN*` zPGrK{?1YnaLdPgdI;8AGMTB^i$2p5V6kWpTx0KFu!n^R6v3gw{19lI;Khz{3bT#@77&ChSiLMq2UR!hrIc%K^nul<9Xpd8_&oU0 z@MGa8!SkKzGWa?03*Z;Sv!CG2U@g3M&h$Li^G$cIymTHLpzB(l3GiI}?TBNivkQI? z{9gF|@DIX23jYK=`yK7}A@F7K=h8(T&%!?s|0{Uy&c$b^))zh(J`bL)kk8>if`1gA z>!Y56e;NL5c-pf*hW{KMZ3zz#Xb|w)u`hJ$n+KZu9)fr3I|=%H^ii*~9dO9nrCRFw ztZ2Ysh5gf?rTE|77ALsqdCAflp*?WK3?E1hutI|)P`H2Kp-5FN_MkDjHUXQ`U?-b- z{=~#Yjy%oxCjru}7KK(+p|#YHZ)Uh%)|0MOw`u)!O{xkPV!}tEwPp1dU@EW>aWAha zMBF|l_wt%K!SE|ZPzwGzp2`Rf%?}M9%PgYf?uhCZj-O{8mY>b;j6V zp4K}JD(XE{!K9nkZUOzVnXAI7*78)Vh2L6UI5s3!rK0v*%ePo9D3EuF(vTa}kgGKC z$TqD_Ee$2)@oZX~izE>E!t^V0Qd5#qAFHTq)~2RqGXJ>LZq_y#5yQw#-)wwzAvliG zWE@Pdqfm<~xU^yj_KF#tX)Ih?mBGJEkV7)~m+9QW=SzmkLMQ+KyA6I&a~VxPjq&vs zT-z=QCY14{J$Mdv=eKe!F@vUaI@R>Kaa+*@Kkk_QqbVZD;>ofG$KETrH^DFTg9|PO(W$@22PW$h)-w*rtX2#m`)n0-B^jMp2AK&(o zw*On-zUZ!QM!YTYf!cNj0Nl!hj#h%()ve2B>9`>vVX_UnuI=#B2HCdY;C(>p^8riX zbs7YXPY_8HhITqQ3k)4*TxZzvK6Nm3umW+;eBWx1@g>QZ`SCc2OW<`H1dVtk@-rY# z$1Mcy)Yk?Nu5sY;I4}$q)ORhyIt_wG4ia&hwRSpg0~k(yU7@c6^+$ct@Vb0_-qUFi zH1hD)L}QG0I&K>nPJJ7@*vChGG4NX7od`1xUjgX0!cKoUOdsR#gLle}!NE2+*7gwO zQ0z*8a*skTOA|m{zT=KCqt8GthXHXcAKfu{=W%StaX?hn3tlIK#}Pi()(ebR5U-ui zm*_Y=Qj3&Bfg!` z2}ICpA7&u;vLJnlpfcKmX8%S0Wr6`B^vxGq*{DIU7W!I=zln(Bp+(Y#eo*am5Bh-6 zKbQEYg+3|tTSEU$XtiHG(zn3{Pkr%3&=(7xCiDoQM+>d?p@+QMhaU1PB!0ET**w7SEi|pMjAwsH%oXH4mb9`>1B->GVTt_kaYx!f$X_N{Be+>` ztDtJvko$qqKNNgGkbOG!JSO;a!RG{jDfouq9|Zp_cv`Sg@N+>o+Yj{m1Zkiq-9=Ef zchEhB&Ja}XAN)&%9xOhHc}9For`ln-x5ZG;~$sN0iY=&pj@ z1$zmm3uX)E3FZrq5F9O7Bv>XmNw8e7LU5K~KyaSm3c=Na)q)!ZYXmn7ZV}ujxI^$Z z!F_`J1rG>5Ab3RZsNgZd<@HN4cf^P{n2%Zsa6#QI}H#(jl-L5&XK)Q`! zykLT$Uy!yk%5@i{6_qrfONiNmd4j6n2Y-anqXj1kmJ3!0&Jqj=(iTU(m4a1*D+E^y zRts(vtP$KSxJ7WA;10pt1osK<7d#;NfZ#)dj|d(SJSuoh@VMX!!50Nz7JN6PyGvoSJAUZG{~2iJINJfE3=omPK~&uDn9x_`lpf|5qx zz~V+^=;zoCLNu&EV z$bJ_4>GhxbPJfa8?5U{8arHe$Mt&3<+2zwspFVTSKhj^&;-lCWh4n2)4u!P4!F2mF ze3`y1eD0!QclDizkmG3N3_Tl_9_WaojwoBlXV0AKnvXKLN7cKT?`Y%;dFC6G56jb* zFI4jG(ROZT&a4yPKu%v$GB--*8-*j;?I_uo$g3LsCyvCGv+IR%^~Zd}^N;2igP*wk_a{8s;hqHVN3ovoRNs-{%K6g^ zM&gKrKYO?r_! zhA_hAp|RiMS6VE+ry9Ffi`S<$ZVqMKo>WG6<6n{L_uUZ>GQx-Jix9C1!lAhV>XFqQ z@j93mV>xY9 z!bY4O6YGev!`v;B-=;E$1g8~T0g}#q2IswXSB8c%=trn^Pm=j0N0a;m$zd;oycVGg z`cc#HwkX8+Nv1Pa%`)IRzzf*-+OrJ22wiX`g$r5KG?MEnJc{HDl6^>y{t*9sBx=Lw zu>m0H%mtq!>4mGnqRI;w;qPzoZJA#?K9R-Ol7vwFZUhD((7pn3e3*~F2b`r0JcvLI z0!G_?_>1QqgkP(QXOlclzGNFffVXXP;UXNT%C;*5%yt|CZM!27%627KD%(8>w4a2y ziR3WbR~TTn?;~Ke-HVXQcBLBuX8T~{UzKQcOY{g@AT$So z=0>|16WL{a43D9B0w+pY#-g<<6T3hYwa&O;s&b~{P`qiBhe}?q1!)zlfXDO%3Z^K* z2_eA=S}+BHdX@Qj0^jD_a<{#0uE;OG=%BXUvxA-MoJrUVd9cPIvs)d5KBZw2v!WKp zV2%NUAF7z~1h+b{rDh!i9TZV%)-k~1S=jF{m<5Z$!a8O{u(H_WnMNt$0KCgsjepxQ zx&$6)k6=eHx8v}yQ%AsFl-D&crH(qv;Gs?ng=Ch5WF{fD1@hVEQprfpg7+vr!Sa5I zwiwCL)|sF(W(nhjuT>}1>2kL=mP>Y_I3!R`=kI8w%$rH0s4!)<;mu32bsYsW8oIy` zu2O+NcBrg6F0lnD)0nY%HSr`oHh!!EC`Zvv@W_yG8@$U{w3>L*4mT041}|90BsRih z`7QpH(>X_A??hFh%>PFC7RX=fnB>jy9wig3<7%+Zp-tDZtuvvHN?BT6$69qloj!)v zI0ierP#lkmRe-pv@HkyHjyRD?2o_M6+p(2qHPkUn``j#Et<#TIu$3&r!K0A1iSMn3y*C^*EyuAfbHw-R+<2%h=g;i zfBvy2(@tNk%)A_)SL=)LoX;`{o;IF6@Y;P{`8*`dhaUmY%i|&VN8pdZAB9hX?iBc* z@Tu^e<8m$hCiolSwbMGrg279S<>eKqbsa81tG6>@pR6Ol9!e z{ddbVA7^`1dwl$R%uCYyte(fbq$e>isU=por*f(KQh%BiiRnm@YC6)SLaP@i-t6%d zcF9QVozWRHa}KQ}=NBG-I*8X-rg9q3ZJxrk(TMK_)~hQ1E<65>m8lEILg01?q*GvY z(?mfY1WPl|Q?U1W%9UD^QmuZI^43EB77u3?eXw#;&&&b`S=f^krD{E#y7a+H&ZyF1 z&cdpdM5#Tk&X{ZT$htzjJey`{x=WMw;7w*6+55NJQ;jh3V@Pvbxqj93B6SYGWO`Av zQ)940T5z7r*WU?t+BAI43sY78Ek7?7te3EzUiF+KwKYO;x&E|iCBsU?CK7$c#36q0 zL=A!BB%D2a2+d%y{pGP)3zyEAH(P%=Ztmp^X3z4g8B2PLS9>y4Mqk4*hsZHANzX6} z9?-XJGEp@8UFW)eKRaS^?2nt7OY|?S+1F>}Kl6xm9qU{2MPT^gX#}Cmwjubh<$8g` zFkZWrque~lecCPj0-#Pq)?UcGs+Bw9h9Ha~;h@{r5#uM2qj{Yc66#~Q_^jpBw+aO) zb})2sR+!xJ2)rVQsRdC%9Tf;W^L?Z_yGXW2E6 z=;Z%r9#L!cT`$%N`}VWv5jC^htM0OqhJDVzGLI;S>2bXc6D$oECz?7&@TvmQc%xdQ1gS(XMRLJF1Ei*d<4!JX^t3CAC38>)n1#RIZ8yjr^IIq-CyXT zLXQxd-_fD`M4`Di2x*%6sJ~KZjtr1qCv*)F<=afed>!^rOn0Z?4}|{{p^peYDg0jv z{i@)b!mk(lBf&3-$j3rQ!hBj2kxxfKzwlFq?kAWl{E3IbfK>hTt-Ab9Hn4B z*9iYc!L7pop3wIQ-Y5KrgnnEQ%|z*ApGm#EUl7?(68(Z*1uqs%6YMW|iQs6#B0+V% zK+ja6XA901tQ4#gv?f8VTC3LGD*b|5YZY7Ur&YnP z4HY#ItN-Vj^Ul2|F)V)C|5w}2@6LJVoq6Y-IdkToGiTnJ_hbrvq2R@WR1lIcUyxgd zNnb8FM^ODg5wHH2z||7Z4cz3vLy$^E(sv1}|0U>sLO(6|ydYJM`b{RFA)BpoYA zRVV2r!Onu+1*rjLdbS{SprkJqq$-s36@uzHk8!)cU*T`7(owuZj$6s!^uC56sEThZ zm?#(!>?D{b$nhoRsBr->Tj(6YT)|<2P49!_CB9H_mS9M5zF^b);c|)RoGi;P5?n7> zEVx0iL~yfUnP7$B9>KkWRe}!+J|g(I;8TLn3ce`#ieRna>w<3z9uzzz_@3a0f*%Xk z3w|MJ$bE@LO)Qk@Zb`tC+ z*h?@?P>m14KR{@%3}XHq!Cb*SLFxmTULZJCuuyQ8U`TMjpc+Ra-%_EA1lJ3meEnem z0pDc(V84tE;XnQQ!Dlg^g$sY9^jy5b_Wr1D4A&3dTy?klIw{r=?tZo2U6oV!agl8o z=)61OKAaTb-b zt~@n3cSkK|y3a$k92V~_07Mq=sd213N-c*sebm;$l+O{B!OeHN$oElcMaS?C!Ep^A z)>ySi{pKn!SJtoe@;z;ZcPiqsYLA;q^!HK!3&}7;-yJF8@1w4^zmGbZY(<_SNaFWV zIh2GMdYg2`WFs18=#QyXSn;8@5N7C4fR0t>=FMRypH6hVd(oMF!Q|&Vx;dP|-U#_S zk{m&DF3FuFNAiBN38A=a5HLrx6h1oRt|xg3Nxosk4Z^`3Ly|8LahKs>=JVOd_k;Lu zOjTrD`*3g&Q~HO=IM%^tnm`d5VUiajj&maBrI#a;8t1qPOf4YED-y>UE^`vkG9G+r zzzYE_(vjqI^Z3tTk>+B*y{?NkXMPW7$@6oSdxJN=Z9by zKEgO9!pL`U<@k@^3{UGb;uys-q{C#5j`A6wdb@w>=^j})!juxlJf3hjyvtbO2Pl_@ z<1ly_%O`w{GlS)sJe7t6lLx|M?G!=HXu*kFI>sM zV~V)etYm;o4=m%_$nq~1_!oG`DyKvg#D4;>sCN3#-yHo1WIuCLBmcLSMZRX}q>-r+ z+p;N6Cv021BpV29iTK_TGR%&)%YEt$6_`&nD8>T;`Nz`8uOOG>hJZmKmm6^jp8c5Boq&>m|L z+F2th*RH~Zfc2?SaLK})0T~NB_2~40bzN$w9S5)p{?Rw)i z6!v!tlnVTeOyWzoSITzU^$mYY)uAN+x&mI6DY|!&uz23`Y4ff|XSsUj>}izLoY{P> zZg(i-zyAh3c$0VP;5+HNCy+PPLGhi|N8jkXDe7i#vF8@|t=4U>ADV;XbH0)7{Kd29 zr!Jknd}(Ua3-%vfyl!qZwQ^l?^uep!I511aMh=>f4_$`U5FAK8=L1kb7JDHcYKySz zgaO%ZQ0Kstho0q)fY-7SH2A(g)PBN}45tMVcFKDe^7xWLd8~_;$AO4b-V!AI7vi+j zX(2@DFw+L%U7c?(+Uc}eh;WvB5IWr)DVOoO++_&sJd`mLbBO^4#Obsppq=s(G1y8# z9M1!4n6SKC5!QJSG;V-A@@c2jZbF1pUN46{zV7S#RUoYMP{t<6`;#L=2g{J=l$Q;8 zyiTlN3wSMW55mmD{y=vPGL<%IKc?@4ck+4h$6v$@;+RJNI6V5^LWwq(fiF`NK=RPl z!s{^Uz2FBV?iG0FdE`3Ug#%%I9!+)j??E2lytLD05gn&z>_x^LL_+K-ZGU{+ z3hPX@Frb#_h*Cjk{6Ai2um8PvEi83~BQ>%bwH&VtduGI0hCPv_V=UD(G)4ZFYHdWM zzp}+6&N7CX!OT9E%+#=jxR{}}0y1l>4)(yawM3T6miEI5LQd-WxPY+vff*}lv_N9ZesR{Bt+ zUoSM@4#}_VG=P7T&}EW-m(WTNiu7us)#MfEr-at)8PvQt;(7fj_m4!-hXwi8%y?z@ z1o0MbBBa%PHt1GDpF;%AXAsl57m2i*w+2ne^X7evh})Dx{x?YTK15V6sKDMrrwa}c z%obGr0(^Y_GT&H1P5_afD|n^gV!>+#iv-sTZW7!kxJ&RZ!3PCZKY{!wg?>g*^%KPZ zU+LEe@j9XWpdjbUNKX>vWEtrtf~r4(UM=(w1vd(o3vzan`A%o=<5}U;dX?9Oep68O zE6CA$b~PCSTI*3%{{pSn%>X%H$8uHw0;>Cpj3F3LN7Vi4sL;GKH@0VRe*bT#kI3w2 z^PgTHu{oZ#i0C8Q8fQ@-(V~6G9V!k^2@MSWuxjt1*i!!{7cAxH)cv7oNU^Kf)!?bS z!532!w`oc3JN0QLu1y<)2kVW(gZ2KvL1-OrYVgfn*WgPzSno?%-{2dvw!vp&xN{=* zlZ%2zh37=<=jMsn6TYDPMC{SQCu09*ZW@X-YugBzSC~+_M7XBq3_hYcYif_>!7wzJ{J7=oQXlJ5?>S8y&ksyJ*Dpr{?$1X zhWMV$4z8^;2D-QVcD^)t&miBEErT9#8M~v)UP7&0DT+q|EnWxj~;&QP@;0?t99wDxRc$onjac8l;l26>smk%iscyRv_G zfI5fxM&B1GV!u?E-EIC6X!gfp06KY72O9#Hk=OLyiX|cYrKyl*J^JCj;p+}h+pa5jN=M#C0L-1SPKH$2tFB=j>MAh3+zJ% ztMT^*uumi(u`%+=#+QInC$)vt2@R7}g z?@Q;irr^(#V9S|gQn4*LjBKh3QQMXoX*MA-}`d?RCY&)sag68#OhpS!Z z4y6S*q3a#+OpQU)$R>G^*b5&~ci`+#qTf)X2V+%$$esfI#+wL6oa!M)9)TkqTaCfc zL3qrI6PWSq`VHROp~fJP!BjgI!-6}i)Nuq#Q=g+{z-Ap6=0kuZ9Zc~PbV>RAXDP?W z6<@DV5`n!FJJAV~;b{s#B9%iN<<7>j8$6^En30C^^Hbar8Iveur7fc%B7?(d<$B;q zZnObG4Fesz2_{cf$@v5q1X)ID)fxuuO6C)i;I*ED;ZE?-oDlNhEiC7&WPrCPrLRD3@=Rd3lkIgH%~MWt>t} zI{iN6e*eD|ykzF|`LiQd+s{Cif-eQzs+5i$I@sEjRBa}(o>sgJrMygGCr`Yru)+l`Q&5hsfuEwPcmgcJ_5{<&( z3#JYpoj*L^K2FP@z4V%e5|f*sH*M6s8B_BYT(fxQ?5RTs4~|TX=(hPb7S(MF>fx4Y zqzKcS8^fBH<}@G87*r2UUmV#;`V9=IpIYtGoO*@oxqr=#j(lXEOvl1UX*2sAgYgB( z^uM>69_~)xcMS`+TH$%hr?c&{1T|ntsa!IS7ZWz2HTAAzN+CuGgS}r1F`bZ@`h@oKu_|68!X#mP&y~e}qJO~#eXQ(l%s9{)GGe%le&c_?EPI2e zfB|u=AKkCvo#!#i(JtsZ;qz#Tuy0?=v^-5~bjE)ddJ}Y0htsWMNB#e>nU3am^jEfc#GQ%Fbba6A{k^fCMBkcI zXBthcrt1`z#QWWMp?|oTa?mG6362%ydp+Z43bNyp=6!&;PVg2%HJ^<5T|)mzaIfG# zLH-Yz|3yLechav5z9o1_@XvxD3w|Q_m0&E|kNLX@_7%((94|Osa6S?D!i9oMiRjd; zCB0ba+lAgHbcN9O3VpxO4+*X2g(2r9iGNMv-xT^!LaTjOsISsD0Kb%YrEdVO?5jgg zH~blSUKvEtqlH%M+Yvug=&K|h&CzI{7`Gus^FPb;Wq&2A_c>s1q0dI-*-G2c~!s-J;Y6PUoY z63^*P@@)_-5mfyR@w6!g9`uELBOUr29&hmgv zF|!;vyG&t9L*3^wAcsoVs(?%2$&=pLTd#v{6@EloQOW z_f46JqkB|p&6vZTN5WF@3A4fbso4?$uqGv>`VK-6>JV<=u+-gK+fjaxJW6$;?I=$p&qN$t z+Kw`3`670d`Dc&lK-8_k9i=pfrmsD-`P}OM<92sY`P?ByMsy&2h8W&kA!LoW4#(Br zmvLO>?TGl5-urP};e8w|(1DbJ&^i!4vMjNq%-cBhAyWX_j7DkceSlt}T`rJg4 z@#e4vVE!>ewhlxoJzfJDzn-ZhIpz5U$=fM;)Kv&}MpTPYIGCd;${ZKZ=aP8|(+UtB zKbz#3zv1``ka0=}q7)gwu}SDb6#1@AYUKx??hXY=JfEKCcs_e*Cn0`fnB;cpcvZAY z-AJ-9ocb=wyO7JAz`Xr%dhtAao16f$B`D)%vTkZ^S}A$Oj zpDKp`cjXurf^V`3=T;TPn}l-1a2yAZZ9arTcrSEAi;XUo3{wb_2v5NKVbT*;Ul$ok zWI%*+5g8LGgR;GNmm>?qY)$ODAy7sO$k?nb7&j5ayhZR{d~b+(8D0;MjYWjb@P1<< z&D2Up#yoAu(iUwq;ua#+i$@Q|F}xHWJD&*5+yde@JFCJ-N<@N~)NLX(4T-t%XjB5L z>{4b<5rFFl&p4beNxE6^e}X^dX%~XwB+YK0U~|o`8>QK^IIN01$yu;YMXJbe(9%2! zw0|=#%^q71@91fa;{WfYXPpRXNQZN)BMG| zUaAIlPW@#7aoX_)+Km44+v_gz|M-vY(r#s51G=v8K6t)-(Ph~XK59Puoq@v{+mX-t zpwo|g4jOeHau(rQ(jJ|5IxQCwn4%85H=#6Y3%;`vgQ-C^d|>zG(JOOj3Yt^ z=QQCnFz>iVSIUt#17T;mb>|@hd@PscF$+1Q-yf(-whlBrnOH@1(pK zcrC9OVVws-qZ0D!7!aq^)`ND+GcY?-gha~Yi;$ML9bugZLE{c2Qm>$$4sJz+Q(jTP zK0nIie2A8JFT%{jkuY5@5`XC!*f5R0T2S+um`z|CXs7ueLj*1-$7jkd24AKofaIg& zz)goq?*X5)53+uA94tD|qc{+0=hjHm=Yj0uzKo!85D{-PAWoM>bex{S@9(7{65a5W zy30La=&gkTwLC|Z3OeKeqq}Tnw3D{tJ)=3@WpkEV!-FB@<$dSd=q?8^f1F_q5gZ|S zsUTltnLbbOYQYtP>jZBR+$Ok7@JE7s1@{T^e?Yk}3bMbGeqHb_!9#+77W`Q76Tz

    #POZqaQxiFvdZW6jg z=q*B53Vja|_u`*Q{Ldx+aiO0V`V}Jhek<{Rl=%0A{)^DZh~WFX#QSg)Wc^zaQ6E0z zn4T>0>RZx?PZRnA;mZ-eArh}_OoDH`(8{(XXga4(jn4?u34#H^PJ%rJ`w0HC*=Bu8 z>h-MPYl6QMF$L@AosNCgP< zjS-{BHdo2%|0WRo)_Gj?<`8<5A&y-q^?gKLAy!Aqqs&%vr?x5DS@eY>Bl_m^BJ@?dP8X%4S<$9`Eouo`w7TO`{SA}?axS+%h3XxK5MgVC54)xg>k0ak*YpiT z5*87>07gqa7WxfWF;O=X+#aQPGRd1aL&ZcbA^1G%+2o5Fhm4Vx14H;=aYvO9OrKgu z;B%`{s@u(%NUS4h4OtOejt_&=@b<=0+j8W(rd8e|99Md;2JZ^*WnjU|fhi!ca)AHQ zsJ%#rEl0lBHnrubmO~VIElrIy> zD8g3O7m&;$nTCLEYVl@}E!2vD%UBSCSPh_qSP7tm*aoSB35m>lIe8P3!@>A2;UExT@H_Z zj-yy3yOgouP>z2+vZEBj6Y$_1##|fhT*D%{sJm3I7mjwWsf5RE&OAF22AUA)2ahu+ zh|uvAIuTy)W@PvZcxaFbEDxJJ&9LH_VxLgyVaeA*T#1s*KZSDa+32cpZgu2=C+T!f zn(DlNm0g0iQ5&4l8K}};gDNcnO0-n&62y+aMS*0PKvbIq3#@CfRWKC>6GwJPp41_^ zXG+hM_VdAky?)6ZJ7Irca%bxbm{uHtbo_>)3cIXSt59m`xl=#YGVO8aTOJNALz zElgVp+19nG$$k1{F#B1l)|IJNLBKj-th-`EPLGW7Fqil;cKdajq0A*dd`fePwgJA= zZq8E*He2oWo!d+NzqgdwSiwhYfG1OJg-;&(C;O9r%C=ym=y2Zr;gg3<8$CRK^uY0h zhebr5+9Kka+d@3;#!I^&hfO4&dV^kbDoeJ+ztzS)J`$XIuTGBJ9q)F{+C~h1P-pp)xH;He*;T!`KZx2cA6iKKN1a zx()~$U+~)7k3*8-v|$K4<$VZwZ-STdSQjm?z>x<*gWq!D$W%LB))k1*VW#n$DnE5Z z=-?crIm>+tqn27EvRuaNa<4;J=RweT1C^ z@fqZiPdlAfj0mT^-41z}ZVk)Zg|N;;8D7klaCNM9I>`49r@Si2<8@;F@ERYMcOSyc z!~Q_G2TVmxt{c-If_L(D!$~e;260TI=NJo9L<=R_COKgIaXg1ZIx3ce`#s^CGv!-A|R^HV=hY$KQ? zI74uq;AX*l1bKD7jgF7~jk=bL1$mDpoiE6HBfeh&k!SC8W;wH+)AGS>7^L|KL zP41xFYN0uk!+Ja=^m9Thvt0bcrrE35x9Ro1Hc%-ZEH-e_)95C-u&CNygKf`$S zMhNUJbh_XG!EC{x;0Qs!6f^$>K~CS0zEW_p;I)D`3f>}EBFKKveD@0SUQfDOkoR=b zPYJ5)4EhzJ)pZ8_rqKL^i<49=?>0fsF_Bhp;H)R>jpr!uPmHG{>g)T7(7gLKnFH^a#wl%a zr<()s-?v|u&3gJd@Bw_FIp)B%y}^>IsM4sNgNvh!$A_*eE*})PnY;Yl#l9^$b*{Au z#k&XP)O}eruJ}ISiJ~9+#vHyedd%VHVwNR6UK4X3x+vw z)*B09!7y)qL)6@Y`sg&@k!bUo1`on9ux#kd8Im-%KE`;u!9CX~!45zR77ugw)EGNm zrRFBzkysZj2wKk}byBX;ZB(sUaj?35s7=Tm@GNAwb{5r4sE^ILEJW&HXlKZ^d0c%= zPC_PW$jx!>oSe(>q}+x3n9rs1`9qh5ifR~N5dwc6<%2u#V2Gji^QP3ha_oF#DSh4~ zC4-W8&a>m+nMdgXRSs)bdmv^cl(Ha6OwSwX=7o}@V*+Hk?{;t=>-j+IU_niS*eskL#DkaGiHQ-^tWPFrIx zd^VCW&;B`>tgejG^Xxm2V5vWiwq3|sWK5#-hNA{au4PM^+2?tNe=T3sG(cp^ofGij zR<~u-cR;bYzhDNpdjci-+`|EC%KZaGd;bg;!+QaaYrN+nxY~Oy!mGS*;JDJur4TE; ze8^$SowMDTa_1>VO~XMOEabBo1`FpQ%ID@EINAq;g~JdVGnZK+1`8LEj2J8&Pa)-= zSa7;h@F}JHDQJhMB_P)19oxLbWF_f(AS<0o?XEwKp)m~dhVSo3GLPgXB!5P7Y#m6x zV#IM>hnde(wv${*ay-ds__$n>6G)bjoXorvNj?i7zi>I`=1KjH)RJqiGR%Unz(RdV zTsq>+Nf&`+5iNKdF(;FBmFC3xNKGNdO^yjO7tA-z=_KRlN#GZVkH10)wOMZQf@MN- zjYr(=l&|v4B{`ZBXRtxGf{dS@W|%YC+&@titR*Vym!MishiX7kW`6v1=mu2y0QqL< zT>Qdk{0yDT!VNfnhR)SlQ99pH-kkCEEmXG^ud2_@<3Hy&o=$EqF}|_6M2D{6bmkH@ zYYfi+B-#S?STj}yi0rA*792t_;yNLSsc{0+PpK5Z@E5!j2(~O()I&JzdLe|ldxDk~ z(GZY}rMQfRZej>tR0Pi>$Z>{ctn^nh@CSI9MZ6wYvzT4Y7)#gGV~kyFIOTXDUWfM@ z6F0dp-Q?C8ojf+DU0u1j>LT0S1NtA$kc5CRxQLM}hI-kKENml}kyfeOil5KYoZ;!O93`>CTMszNNuqNd7G>G4wM%52BEt1l zS5&7Hd4;w63a#TZ-Us=8-Z6$Lh^61i7UluN%1-dQ-h4 ztyxR09=@gAyVWDWV|r>wYZ*cTD>Gmv1jhEv=-b`ew!8(SaY+j7O-8JYAp$Lw^{|Ps{>gVcW&3&`Vn%xZ3KE|2xkDCUArlxmVxeF@Xau6 zO-t)CG{d?&yPNehFu!U9y7%hWBMaNb0?gUHqqPUo2My-rr^XUeb1oUsr(MP+J^Hlk zbXSi)y%Q~eYI^&O#Plxs&KWdv%K|CMnbs>tYNy0biG5OfcD}fi_2KG*_ST$iY_2p- zXny)-VPBGb9BQBr42o!Y8rfl_mBWFC{V6i7Xwnzp3@u=WHA?^2rZ4|j7BA6I;}$Gi zGBDCUP4z%k8BLL%e=y4i!Ft za)sde+`*^I9gNgy;USDa+X&mHqv0fZp=sXA-mm-k^2JLhjU-EUBY5Az=99=0# z+H{1SJZ?r<=Rwf; zJrWZb5U0~_0PU1F%OQ{d8(qJ0gmoT@_z3c>X4-iR(wy>^LLS?d_2WB)miHrsDK8D4 z?qd|Tsfj$MSHU~^)qqwz zyz@L(I@+Z*()4+7UO@L{1dXYX_Z9=G z3(Xfn=6^uwM}_9vL6-NT(EEk{ozU+Ka(aRJk4rl5Q>1-F>4LmpkuO{D62WnTlLRjl zoFy0%;#4j9)t*OSw$M3(qXhE=o9ex0Nc)P+9QOEi=2^|z1AvjKOq97;eSy=y3<6*@{_pJe?kQK;JXB&)Ul#kc9U#X+7?SDyt-?IA&vXiM8EV99?ms-d)nF zcsTU8zD-dZV@q@D_O6X7vx+xCkNe}bgNknj-n}-q>~`P0B%{u<#vIP|xi*ccsM~@wt1{`_dl8o}DLZdenQ2N9(-_v@AM3Kl-T8iaFvkcegcC`_wL|?oe!A z)S_rw@xwJg9#>I3D*s^d*tWU(zRaSw-hCa4t)o6SQ(Z?)e^gOrvFoBS`TOdmXT;Vm!Ey*1ZW)@|R&pgAD3 z-ZgS<&3(`{^TUCtr~lFF0o9B(&%dQ+FXErgT~ysRn1&eF`J|^5-%`^H=W;`$|Hv@E z(Y@|~yKHT)Q87I+y5hE)y9XJY)*QR;0XM!)cbCuHl9yzb$L_eXW@?hLaYWL*#F(8W zHFwtxN}QS)3cZYPOwM5Y;fsCl(wL3j&EB2w)b}bHb9hM1JN0c!e9+n&<%2`kkrpAK(pKpjtF?vm?{RMWLCDv9QHx^by9_+MMF{K*zT5l?Tp&>Tqj^chb z7uURiGF~YDO|hAMaZSIPdum|$Hl2KX_cfCfQrrulN8ak=ZiKxe(TlK8;(ZAFReTlB zr22SFp)1=i*N>EV;fgQ3rzRmSL6v0mdg*|xY<+I;wr2VCeJz6BgDaELkGrmX95vrv z!@TY~)BRy}Zguu?*8-%BGzU;S?@cMI_6M^Rrwb*y63FWsfYvH3f_~ha;y>#4-jvTYxDL?+;?;St=K<&H5eE@GT=4&{bt#NZs z!Gnr}7^j0an<`Hz#z%m|a(g%%1*Lf@C@9T2=5?zFV&60d)flWF`VMkLJxFkS=780G z8Ts>8sF{X)~F&D<&OH0VEVo!_}qyq(!E@9x^IM_h+W(BK^fke z;8^4BhTv-NJqWMza_qR$`v{IJyc~~1RnD!-P?bLcDrzwfuxmSt;ir)Ss`7ORH??cK zlUZ)_P`|*PYCj^mK}c83dcwXLNfZP#`wc+D|kySD4`44^Ycaw_=L&ioIxs1>C9)UAWkU` zdUHk0BcW8~ihLAg{4bbGk-sN-5k=18L&%E<7VPL6=2c&UIu}&@3i4h}axBRivM}4ph>g7{*7BjFo^4p7 zs7B9oo3XLbT6;{q+oH!=@riNhL&D24D^*Hr4!xeOEAC z*_O5~S#4hyMe|F9t!1m7s_e<^%&M`3D9_ni61UtQnLYyx_P+k+5 zPUU)Id$N3Mf)xuqMD=$pBvvKzJ(|=mZa@TEK^PP}c&ntPGp0sV<(S zt%HYsTS5uEWnAZ~WT4C@+?5RQo`Mu_B?FJaBL~;}4ueOKHGUSJ3TdKU;|Y-(U*l3W zW<%kNh~7#D>>5vCjS&ek6CyR9P$V^ma3m{tJ&vpxOu!O0tKfLTE_fP>y#`AZ7_L(E zQbjZT1Uz!F!Xw}j+zVi((N!IF&t=^gs=7>y)FoVjg%DE#_5!vCs-3f9jpDKIeYDmGJR)v(#cp@dBm4|5&4C}UXE&*VE;T`4R z9R<z$@Vir8FB(pmm|5VyNpo)4QsO~*x0$I~_-++wW?NkX)@6Y%7VN{$33N&6V*MFOJI#R2k_wi9wHB)Rb!KW8$O%wR7nZsp z(B)!lMyk#qPWmf&HlwU`s{+|RG3KP_K~Fy#pTtb(cQMmJqzuA={$hSX(?24!9hVL~ zvwDv8w7JfD0s@{kM=1Q2nVqZymVX`A4|Gb*vChth$keRN?wQw&vA$T9YJFwSu`W-w z&Mr{#JyUvh4JKRBfp(cl4InjDr3Q2^+Phtff>U|KhTm(@GU^kdnMi4rr+2}{^V$zh zAKkNO%BJ?|?I&3ABYJe|F@H?^^q$sx5MAj?wcZ8Z=?b({5f!dLXDnXG?ra@cU0}Vj z+FpVX(UEib4*!i7B#1KFxh?_94P{@@lJU zSTX<2*CtGxhJ^s>C}GJ`W9TIl0)qotsr^$k0~u-Q8R;2m{R7<=&z?Vf`jXk*15;2; zpV?Q{-3DruFYVWAXH>XNCfcXJ0#S$-D(u2hz{a%1rBfnepwGD9Bm`$6Agi zYZbn&ZQG^`7LedjxSosqM4<3@A zZ!8JH9BhESD7;?b>)V9YYK6v2S5P_C38l49wQ#|){vlHQ@JohH7&Q=&rJ;idUl8cV zt3Q6hg854Va~3QPfGsdYu5}=9@q(GNmn>PZcuDu~qI;l=e+Tw(`PkQv&yr@>F64pZ zTdrOB7chxyv_muC>5h?}?XmYqD=e`~_ z423K$8$sg{RzO$6kv14%sIS6q*tr-=q4IpU=7b03v0nM`jpX6P6C4pbIJ*hoi%}S2 z=}I}$rX%bu_f0ft8VY2&EKira)R6~4W3S&Z0t|@L<#L$nl;=yfbzYRm_dhM~W`uPf z1dUf9uNwp6blMG|o$}g3UK-*k4_U(U$`RIi5HyY5s48{j!vseQ^1YMsymt`i3oa5|Ey({Q(@O-m3GywQ@%--) z_X_S4RIh!Ae^F@8U6Sv0LH0}1hXnsD__5$8f?o-8TMzlW2rAt$=v<-43r-iDPsF`# zq2N*?{zU4v8u^NaR&&^(w+UTA1g&(w;J;sJrRxR#tnj@g@k+;wc-m@UzCTI&2SRiD zk>#r8-at40c;r*|I)MS9Qw0YT!Ivkfbhe;pN&3|izeMO&Lf4Ln!F<-Xe zXhFV=GhX#e;8dYG)6MwBg4YS^wGOunT`E{6SRttTCGzv$O*u~qJ}X!&sQM++PYC^` zpz3dkS8HZ~{dhfr7YK54o%BS(%LG+FMEoM5uMu1;c%z_NI|IHFq00qNW;eE4()HSd z$Ax}M@CCt_1@)SP{}%eNAh*J>-c%wG8w6GV1g+NA09*391N9n&M4?r`MSNGGdkSU> z>NN=$2|Y-#>Dq(>iC0rmkT+B4xq_;{BYv^a*9oeAk9aC9SU=V8f!l=MA$XVIy@EA@ z4+}mm_`KkLLDl~u?@giA{{ZxV3;luMUj;uAJR$g{U>xrGtY1sP^8}Lwy9z4%(BR7y zy1$@a(=bTrk%G!jH2C$JhRG67eGALGO7I%N>jaywZMa?HO9jgXwH@3a39Z*WP=Q1F zdd6;K zp*6)D1`P?d+iDb_y)CEij5axzuj}BC@S`d z%ex)>>|1U-XKTWyR%)O9rE86@u*+KbcD)hsY;$jW=Og!!=Nnu@-mZ72O~!6=-?r#2 z?|kGN@~Z}G$mDuo;BBmY@NSDjoOj66h)WH|9EtW!sP`Ff*ZUJ@Jv z`6(|ncv9MIkKPosV+?lK`}2H=^`$%q{e8@Kd>41&?V+em-i@e%;vA2d{h?U!#3